diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 000000000..cb32dd44f --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "overo"] + path = overo + url = git@github.com:peabody124/op_overo.git diff --git a/HISTORY.txt b/HISTORY.txt index f3f316dbb..4d22602df 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -1,5 +1,36 @@ Short summary of changes. For a complete list see the git log. +2012-06-04 +AeroSimRC support merged into next + +2012-05-26 +VirtualFlybar which allows a more aggressive flight mode than rate mode +support. Also PiroCompensation added. + +2012-05-26 +Revert some UI changes that didn't work consistently between OSX and Windows. + +2012-05-24 +Merged the updated firmware for the PipXtreme, thanks to Brian for a lot of +work on this. + +2012-05-04 +Support for CC3D. This involved changes to various things such as the sensors +being split from AttitudeRaw to Accels,Gyros,Magnetometer. A single firmware +image fw_coptercontrol will run on both CC and CC3D. When compiling the +bootloader one must set the HW_REVISION to the appropriate value. 0x01 is for +CC and 0x02 is for CC3D. If the wrong bootloader is installed the firmware +will not run. + +2012-05-02 +Reduction in the memory usage due to the UAVObject metadata. Now the update +periods are using a smaller data type and the various flags relating to access +controls and update modes are stored in a bitfield. The UAVObjectBrowser has +not been updated to allow these modes to be easily changed. + +2012-03-31 +Support for ground vehicle configuration has been added to the the GCS. + 2012-02-14 New QML based system to allow more flexible UI. Upgraded stabilization configuration. diff --git a/Makefile b/Makefile index aa5a8fbfc..8a55572e8 100644 --- a/Makefile +++ b/Makefile @@ -72,6 +72,7 @@ help: @echo " arm_sdk_install - Install the Code Sourcery ARM gcc toolchain" @echo " openocd_install - Install the OpenOCD JTAG daemon" @echo " stm32flash_install - Install the stm32flash tool for unbricking boards" + @echo " dfuutil_install - Install the dfu-util tool for unbricking F4-based boards" @echo @echo " [Big Hammer]" @echo " all - Generate UAVObjects, build openpilot firmware and gcs" @@ -113,9 +114,6 @@ help: @echo " supported boards are ($(BL_BOARDS))" @echo @echo " [Simulation]" - @echo " sim_posix - Build OpenPilot simulation firmware for" - @echo " a POSIX compatible system (Linux, Mac OS X, ...)" - @echo " sim_posix_clean - Delete all build output for the POSIX simulation" @echo " sim_win32 - Build OpenPilot simulation firmware for" @echo " Windows using mingw and msys" @echo " sim_win32_clean - Delete all build output for the win32 simulation" @@ -172,7 +170,6 @@ qt_sdk_install : | $(DL_DIR) $(TOOLS_DIR) qt_sdk_install: qt_sdk_clean # download the source only if it's newer than what we already have $(V1) wget -N --content-disposition -P "$(DL_DIR)" "$(QT_SDK_URL)" - # tell the user exactly which path they should select in the GUI $(V1) echo "*** NOTE NOTE NOTE ***" $(V1) echo "*" @@ -209,36 +206,173 @@ arm_sdk_clean: $(V1) [ ! -d "$(ARM_SDK_DIR)" ] || $(RM) -r $(ARM_SDK_DIR) # Set up openocd tools -OPENOCD_DIR := $(TOOLS_DIR)/openocd +OPENOCD_DIR := $(TOOLS_DIR)/openocd +OPENOCD_WIN_DIR := $(TOOLS_DIR)/openocd_win +OPENOCD_BUILD_DIR := $(DL_DIR)/openocd-build .PHONY: openocd_install +openocd_install: | $(DL_DIR) $(TOOLS_DIR) openocd_install: OPENOCD_URL := http://sourceforge.net/projects/openocd/files/openocd/0.5.0/openocd-0.5.0.tar.bz2/download openocd_install: OPENOCD_FILE := openocd-0.5.0.tar.bz2 -# order-only prereq on directory existance: -openocd_install: | $(DL_DIR) $(TOOLS_DIR) openocd_install: openocd_clean # download the source only if it's newer than what we already have $(V1) wget -N -P "$(DL_DIR)" --trust-server-name "$(OPENOCD_URL)" # extract the source - $(V1) [ ! -d "$(DL_DIR)/openocd-build" ] || $(RM) -r "$(DL_DIR)/openocd-build" - $(V1) mkdir -p "$(DL_DIR)/openocd-build" - $(V1) tar -C $(DL_DIR)/openocd-build -xjf "$(DL_DIR)/$(OPENOCD_FILE)" + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -r "$(OPENOCD_BUILD_DIR)" + $(V1) mkdir -p "$(OPENOCD_BUILD_DIR)" + $(V1) tar -C $(OPENOCD_BUILD_DIR) -xjf "$(DL_DIR)/$(OPENOCD_FILE)" # build and install $(V1) mkdir -p "$(OPENOCD_DIR)" $(V1) ( \ - cd $(DL_DIR)/openocd-build/openocd-0.5.0 ; \ - ./configure --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi --enable-buspirate; \ + cd $(OPENOCD_BUILD_DIR)/openocd-0.5.0 ; \ + ./configure --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi ; \ + $(MAKE) --silent ; \ + $(MAKE) --silent install ; \ + ) + + # delete the extracted source when we're done + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" + +.PHONY: ftd2xx_install + +FTD2XX_DIR := $(DL_DIR)/ftd2xx + +ftd2xx_install: | $(DL_DIR) +ftd2xx_install: FTD2XX_URL := http://www.ftdichip.com/Drivers/CDM/Beta/CDM20817.zip +ftd2xx_install: FTD2XX_FILE := CDM20817.zip +ftd2xx_install: ftd2xx_clean + # download the file only if it's newer than what we already have + $(V0) @echo " DOWNLOAD $(FTD2XX_URL)" + $(V1) wget -q -N -P "$(DL_DIR)" "$(FTD2XX_URL)" + + # extract the source + $(V0) @echo " EXTRACT $(FTD2XX_FILE) -> $(FTD2XX_DIR)" + $(V1) mkdir -p "$(FTD2XX_DIR)" + $(V1) unzip -q -d "$(FTD2XX_DIR)" "$(DL_DIR)/$(FTD2XX_FILE)" + +.PHONY: ftd2xx_clean +ftd2xx_clean: + $(V0) @echo " CLEAN $(FTD2XX_DIR)" + $(V1) [ ! -d "$(FTD2XX_DIR)" ] || $(RM) -r "$(FTD2XX_DIR)" + +.PHONY: ftd2xx_install + +LIBUSB_WIN_DIR := $(DL_DIR)/libusb-win32-bin-1.2.6.0 + +libusb_win_install: | $(DL_DIR) +libusb_win_install: LIBUSB_WIN_URL := http://sourceforge.net/projects/libusb-win32/files/libusb-win32-releases/1.2.6.0/libusb-win32-bin-1.2.6.0.zip/download +libusb_win_install: LIBUSB_WIN_FILE := libusb-win32-bin-1.2.6.0.zip +libusb_win_install: libusb_win_clean + # download the file only if it's newer than what we already have + $(V0) @echo " DOWNLOAD $(LIBUSB_WIN_URL)" + $(V1) wget -q -N -P "$(DL_DIR)" --trust-server-name "$(LIBUSB_WIN_URL)" + + # extract the source + $(V0) @echo " EXTRACT $(LIBUSB_WIN_FILE) -> $(LIBUSB_WIN_DIR)" + $(V1) mkdir -p "$(LIBUSB_WIN_DIR)" + $(V1) unzip -q -d "$(DL_DIR)" "$(DL_DIR)/$(LIBUSB_WIN_FILE)" + + # fixup .h file needed by openocd build + $(V0) @echo " FIXUP $(LIBUSB_WIN_DIR)" + $(V1) ln -s "$(LIBUSB_WIN_DIR)/include/lusb0_usb.h" "$(LIBUSB_WIN_DIR)/include/usb.h" + +.PHONY: libusb_win_clean +libusb_win_clean: + $(V0) @echo " CLEAN $(LIBUSB_WIN_DIR)" + $(V1) [ ! -d "$(LIBUSB_WIN_DIR)" ] || $(RM) -r "$(LIBUSB_WIN_DIR)" + +.PHONY: openocd_git_win_install + +openocd_git_win_install: | $(DL_DIR) $(TOOLS_DIR) +openocd_git_win_install: OPENOCD_URL := git://openocd.git.sourceforge.net/gitroot/openocd/openocd +openocd_git_win_install: OPENOCD_REV := f1c0133321c8fcadadd10bba5537c0a634eb183b +openocd_git_win_install: openocd_win_clean libusb_win_install ftd2xx_install + # download the source + $(V0) @echo " DOWNLOAD $(OPENOCD_URL) @ $(OPENOCD_REV)" + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" + $(V1) mkdir -p "$(OPENOCD_BUILD_DIR)" + $(V1) git clone --no-checkout $(OPENOCD_URL) "$(DL_DIR)/openocd-build" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + git checkout -q $(OPENOCD_REV) ; \ + ) + + # apply patches + $(V0) @echo " PATCH $(OPENOCD_BUILD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch ; \ + git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch ; \ + ) + + # build and install + $(V0) @echo " BUILD $(OPENOCD_WIN_DIR)" + $(V1) mkdir -p "$(OPENOCD_WIN_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + ./bootstrap ; \ + ./configure --enable-maintainer-mode --prefix="$(OPENOCD_WIN_DIR)" \ + --build=i686-pc-linux-gnu --host=i586-mingw32msvc \ + CPPFLAGS=-I$(LIBUSB_WIN_DIR)/include \ + LDFLAGS=-L$(LIBUSB_WIN_DIR)/lib/gcc \ + --enable-ft2232_ftd2xx --with-ftd2xx-win32-zipdir=$(FTD2XX_DIR) \ + --disable-werror \ + --enable-stlink ; \ $(MAKE) ; \ $(MAKE) install ; \ ) # delete the extracted source when we're done - $(V1) [ ! -d "$(DL_DIR)/openocd-build" ] || $(RM) -r "$(DL_DIR)/openocd-build" + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" + +.PHONY: openocd_win_clean +openocd_win_clean: + $(V0) @echo " CLEAN $(OPENOCD_WIN_DIR)" + $(V1) [ ! -d "$(OPENOCD_WIN_DIR)" ] || $(RM) -r "$(OPENOCD_WIN_DIR)" + +.PHONY: openocd_git_install + +openocd_git_install: | $(DL_DIR) $(TOOLS_DIR) +openocd_git_install: OPENOCD_URL := git://openocd.git.sourceforge.net/gitroot/openocd/openocd +openocd_git_install: OPENOCD_REV := f1c0133321c8fcadadd10bba5537c0a634eb183b +openocd_git_install: openocd_clean + # download the source + $(V0) @echo " DOWNLOAD $(OPENOCD_URL) @ $(OPENOCD_REV)" + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" + $(V1) mkdir -p "$(OPENOCD_BUILD_DIR)" + $(V1) git clone --no-checkout $(OPENOCD_URL) "$(OPENOCD_BUILD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + git checkout -q $(OPENOCD_REV) ; \ + ) + + # apply patches + $(V0) @echo " PATCH $(OPENOCD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch ; \ + git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch ; \ + ) + + # build and install + $(V0) @echo " BUILD $(OPENOCD_DIR)" + $(V1) mkdir -p "$(OPENOCD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + ./bootstrap ; \ + ./configure --enable-maintainer-mode --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi --enable-buspirate --enable-stlink ; \ + $(MAKE) ; \ + $(MAKE) install ; \ + ) + + # delete the extracted source when we're done + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" .PHONY: openocd_clean openocd_clean: + $(V0) @echo " CLEAN $(OPENOCD_DIR)" $(V1) [ ! -d "$(OPENOCD_DIR)" ] || $(RM) -r "$(OPENOCD_DIR)" STM32FLASH_DIR := $(TOOLS_DIR)/stm32flash @@ -260,6 +394,38 @@ stm32flash_clean: $(V0) @echo " CLEAN $(STM32FLASH_DIR)" $(V1) [ ! -d "$(STM32FLASH_DIR)" ] || $(RM) -r "$(STM32FLASH_DIR)" +DFUUTIL_DIR := $(TOOLS_DIR)/dfu-util + +.PHONY: dfuutil_install +dfuutil_install: DFUUTIL_URL := http://dfu-util.gnumonks.org/releases/dfu-util-0.5.tar.gz +dfuutil_install: DFUUTIL_FILE := $(notdir $(DFUUTIL_URL)) +dfuutil_install: | $(DL_DIR) $(TOOLS_DIR) +dfuutil_install: dfuutil_clean + # download the source + $(V0) @echo " DOWNLOAD $(DFUUTIL_URL)" + $(V1) wget -N -P "$(DL_DIR)" "$(DFUUTIL_URL)" + + # extract the source + $(V0) @echo " EXTRACT $(DFUUTIL_FILE)" + $(V1) [ ! -d "$(DL_DIR)/dfuutil-build" ] || $(RM) -r "$(DL_DIR)/dfuutil-build" + $(V1) mkdir -p "$(DL_DIR)/dfuutil-build" + $(V1) tar -C $(DL_DIR)/dfuutil-build -xf "$(DL_DIR)/$(DFUUTIL_FILE)" + + # build + $(V0) @echo " BUILD $(DFUUTIL_DIR)" + $(V1) mkdir -p "$(DFUUTIL_DIR)" + $(V1) ( \ + cd $(DL_DIR)/dfuutil-build/dfu-util-0.5 ; \ + ./configure --prefix="$(DFUUTIL_DIR)" ; \ + $(MAKE) ; \ + $(MAKE) install ; \ + ) + +.PHONY: dfuutil_clean +dfuutil_clean: + $(V0) @echo " CLEAN $(DFUUTIL_DIR)" + $(V1) [ ! -d "$(DFUUTIL_DIR)" ] || $(RM) -r "$(DFUUTIL_DIR)" + ############################## # # Set up paths to tools @@ -429,32 +595,60 @@ bu_$(1)_clean: $(V1) $(RM) -fr $(BUILD_DIR)/bu_$(1) endef +# $(1) = Canonical board name all in lower case (e.g. coptercontrol) +define EF_TEMPLATE +.PHONY: ef_$(1) +ef_$(1): ef_$(1)_bin + +ef_$(1)_%: bl_$(1)_bin fw_$(1)_bin + $(V1) mkdir -p $(BUILD_DIR)/ef_$(1)/dep + $(V1) cd $(ROOT_DIR)/flight/EntireFlash && \ + $$(MAKE) -r --no-print-directory \ + BOARD_NAME=$(1) \ + TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ + DFU_CMD="$(DFUUTIL_DIR)/bin/dfu-util" \ + $$* + +.PHONY: ef_$(1)_clean +ef_$(1)_clean: + $(V0) @echo " CLEAN $$@" + $(V1) $(RM) -fr $(BUILD_DIR)/ef_$(1) +endef + # $(1) = Canonical board name all in lower case (e.g. coptercontrol) define BOARD_PHONY_TEMPLATE .PHONY: all_$(1) all_$(1): $$(filter fw_$(1), $$(FW_TARGETS)) all_$(1): $$(filter bl_$(1), $$(BL_TARGETS)) all_$(1): $$(filter bu_$(1), $$(BU_TARGETS)) +all_$(1): $$(filter ef_$(1), $$(EF_TARGETS)) .PHONY: all_$(1)_clean all_$(1)_clean: $$(addsuffix _clean, $$(filter fw_$(1), $$(FW_TARGETS))) all_$(1)_clean: $$(addsuffix _clean, $$(filter bl_$(1), $$(BL_TARGETS))) all_$(1)_clean: $$(addsuffix _clean, $$(filter bu_$(1), $$(BU_TARGETS))) +all_$(1)_clean: $$(addsuffix _clean, $$(filter ef_$(1), $$(EF_TARGETS))) endef -ALL_BOARDS := openpilot ahrs coptercontrol pipxtreme ins +ALL_BOARDS := coptercontrol pipxtreme simposix # Friendly names of each board (used to find source tree) -openpilot_friendly := OpenPilot coptercontrol_friendly := CopterControl pipxtreme_friendly := PipXtreme -ins_friendly := INS -ahrs_friendly := AHRS +revolution_friendly := Revolution +simposix_friendly := SimPosix + +# SimPosix only builds on Linux so drop it from the list for +# all other platforms. +ifneq ($(UNAME), Linux) +ALL_BOARDS := $(filter-out simposix, $(ALL_BOARDS)) +endif # Start out assuming that we'll build fw, bl and bu for all boards FW_BOARDS := $(ALL_BOARDS) BL_BOARDS := $(ALL_BOARDS) BU_BOARDS := $(ALL_BOARDS) +EF_BOARDS := $(ALL_BOARDS) # FIXME: The INS build doesn't have a bootloader or bootloader # updater yet so we need to filter them out to prevent errors. @@ -465,6 +659,7 @@ BU_BOARDS := $(filter-out ins, $(BU_BOARDS)) FW_TARGETS := $(addprefix fw_, $(FW_BOARDS)) BL_TARGETS := $(addprefix bl_, $(BL_BOARDS)) BU_TARGETS := $(addprefix bu_, $(BU_BOARDS)) +EF_TARGETS := $(addprefix ef_, $(EF_BOARDS)) .PHONY: all_fw all_fw_clean all_fw: $(addsuffix _opfw, $(FW_TARGETS)) @@ -478,9 +673,13 @@ all_bl_clean: $(addsuffix _clean, $(BL_TARGETS)) all_bu: $(addsuffix _opfw, $(BU_TARGETS)) all_bu_clean: $(addsuffix _clean, $(BU_TARGETS)) +.PHONY: all_ef all_ef_clean +all_ef: $(EF_TARGETS)) +all_ef_clean: $(addsuffix _clean, $(EF_TARGETS)) + .PHONY: all_flight all_flight_clean -all_flight: all_fw all_bl all_bu -all_flight_clean: all_fw_clean all_bl_clean all_bu_clean +all_flight: all_fw all_bl all_bu all_ef +all_flight_clean: all_fw_clean all_bl_clean all_bu_clean all_ef_clean # Expand the groups of targets for each board $(foreach board, $(ALL_BOARDS), $(eval $(call BOARD_PHONY_TEMPLATE,$(board)))) @@ -494,13 +693,8 @@ $(foreach board, $(ALL_BOARDS), $(eval $(call FW_TEMPLATE,$(board),$($(board)_fr # Expand the bootloader rules $(foreach board, $(ALL_BOARDS), $(eval $(call BL_TEMPLATE,$(board),$($(board)_friendly)))) -.PHONY: sim_posix -sim_posix: sim_posix_elf - -sim_posix_%: uavobjects_flight - $(V1) mkdir -p $(BUILD_DIR)/sitl_posix - $(V1) $(MAKE) --no-print-directory \ - -C $(ROOT_DIR)/flight/OpenPilot --file=$(ROOT_DIR)/flight/OpenPilot/Makefile.posix $* +# Expand the entire-flash rules +$(foreach board, $(ALL_BOARDS), $(eval $(call EF_TEMPLATE,$(board),$($(board)_friendly)))) .PHONY: sim_win32 sim_win32: sim_win32_exe diff --git a/flight/AHRS/ahrs.c b/flight/AHRS/ahrs.c deleted file mode 100644 index e8b5742e3..000000000 --- a/flight/AHRS/ahrs.c +++ /dev/null @@ -1,1265 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup AHRS AHRS - * @brief The AHRS Modules perform - * - * @{ - * @addtogroup AHRS_Main - * @brief Main function which does the hardware dependent stuff - * @{ - * - * - * @file ahrs.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief INSGPS Test Program - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* OpenPilot Includes */ -#include "ahrs.h" -#include -#include "pios.h" -#include "ahrs_timer.h" -#include "ahrs_spi_comm.h" -#include "insgps.h" -#include "CoordinateConversions.h" -#include -#include "fifo_buffer.h" - -#define DEG_TO_RAD (M_PI / 180.0) -#define RAD_TO_DEG (180.0 / M_PI) - -#define INSGPS_GPS_TIMEOUT 2 /* 2 seconds triggers reinit of position */ -#define INSGPS_GPS_MINSAT 6 /* 2 seconds triggers reinit of position */ -#define INSGPS_GPS_MINPDOP 3.5 /* minimum PDOP for postition updates */ -#define INSGPS_MAGLEN 1000 -#define INSGPS_MAGTOL 0.5 /* error in magnetic vector length to use */ - -#define GYRO_OOB(x) ((x > (1000 * DEG_TO_RAD)) || (x < (-1000 * DEG_TO_RAD))) -#define ACCEL_OOB(x) (((x > 12*9.81) || (x < -12*9.81))) -#define ISNAN(x) (x != x) -// down-sampled data index -#define ACCEL_RAW_X_IDX 2 -#define ACCEL_RAW_Y_IDX 0 -#define ACCEL_RAW_Z_IDX 4 -#define GYRO_RAW_X_IDX 1 -#define GYRO_RAW_Y_IDX 3 -#define GYRO_RAW_Z_IDX 5 -#define GYRO_TEMP_RAW_XY_IDX 6 -#define GYRO_TEMP_RAW_Z_IDX 7 -#define MAG_RAW_X_IDX 1 -#define MAG_RAW_Y_IDX 0 -#define MAG_RAW_Z_IDX 2 - -// For debugging the raw sensors -//#define DUMP_RAW -//#define DUMP_EKF -//#define PIP_DUMP_RAW - -volatile int8_t ahrs_algorithm; - -/* INS functions */ -void ins_outdoor_update(); -void ins_indoor_update(); -void simple_update(); - -/* Data accessors */ -void adc_callback(float *); -bool get_accel_gyro_data(); -void process_mag_data(); -void reset_values(); -void calibrate_sensors(void); - -/* Communication functions */ -void send_calibration(void); -void send_attitude(void); -void send_velocity(void); -void send_position(void); -void homelocation_callback(AhrsObjHandle obj); -void altitude_callback(AhrsObjHandle obj); -void calibration_callback(AhrsObjHandle obj); -void gps_callback(AhrsObjHandle obj); -void settings_callback(AhrsObjHandle obj); -void affine_rotate(float scale[3][4], float rotation[3]); -void calibration(float result[3], float scale[3][4], float arg[3]); - -/* Bootloader related functions and var*/ -void firmwareiapobj_callback(AhrsObjHandle obj); -volatile uint8_t reset_count=0; - -/** - * @addtogroup AHRS_Global_Data AHRS Global Data - * @{ - * Public data. Used by both EKF and the sender - */ - -//! Contains the data from the mag sensor chip -struct mag_sensor mag_data; - -//! Contains the data from the accelerometer -struct accel_sensor accel_data; - -//! Contains the data from the gyro -struct gyro_sensor gyro_data; - -//! Conains the current estimate of the attitude -struct attitude_solution attitude_data; - -//! Contains data from the altitude sensor -struct altitude_sensor altitude_data; - -//! Contains data from the GPS (via the SPI link) -struct gps_sensor gps_data; - -//! The oversampling rate, ekf is 2k / this -uint8_t adc_oversampling = 15; - -//! Offset correction of barometric alt, to match gps data -static float baro_offset = 0; - -static float mag_len = 0; - -typedef enum { AHRS_IDLE, AHRS_DATA_READY, AHRS_PROCESSING } states; -volatile int32_t ekf_too_slow; -volatile int32_t total_conversion_blocks; - -//! Buffer to allow ADC to run a bit faster than EKF -t_fifo_buffer adc_fifo_buffer; - - -/** - * @} - */ - -/* INS functions */ - -/** - * @brief Update the EKF when in outdoor mode. The primary difference is using the GPS values. - */ -void ins_outdoor_update() -{ - float gyro[3], accel[3], vel[3]; - static uint32_t last_gps_time = 0; - uint16_t sensors; - - // format data for INS algo - gyro[0] = gyro_data.filtered.x; - gyro[1] = gyro_data.filtered.y; - gyro[2] = gyro_data.filtered.z; - accel[0] = accel_data.filtered.x, - accel[1] = accel_data.filtered.y, - accel[2] = accel_data.filtered.z, - - INSStatePrediction(gyro, accel, 1 / (float)EKF_RATE); - attitude_data.quaternion.q1 = Nav.q[0]; - attitude_data.quaternion.q2 = Nav.q[1]; - attitude_data.quaternion.q3 = Nav.q[2]; - attitude_data.quaternion.q4 = Nav.q[3]; - send_attitude(); // get message out quickly - send_velocity(); - send_position(); - INSCovariancePrediction(1 / (float)EKF_RATE); - - sensors = 0; - - /* - * Detect if greater than certain time since last gps update and if so - * reset EKF to that position since probably drifted too far for safe - * update - */ - uint32_t this_gps_time = timer_count(); - float gps_delay; - - if (this_gps_time < last_gps_time) - gps_delay = ((0xFFFF - last_gps_time) - this_gps_time) / timer_rate(); - else - gps_delay = (this_gps_time - last_gps_time) / timer_rate(); - last_gps_time = this_gps_time; - - if (gps_data.updated) - { - vel[0] = gps_data.groundspeed * cos(gps_data.heading * DEG_TO_RAD); - vel[1] = gps_data.groundspeed * sin(gps_data.heading * DEG_TO_RAD); - vel[2] = 0; - - if(gps_delay > INSGPS_GPS_TIMEOUT) - INSPosVelReset(gps_data.NED,vel); // position stale, reset - else { - sensors |= HORIZ_SENSORS | POS_SENSORS; - } - - /* - * When using gps need to make sure that barometer is brought into NED frame - * we should try and see if the altitude from the home location is good enough - * to use for the offset but for now starting with this conservative filter - */ - if(fabs(gps_data.NED[2] + (altitude_data.altitude - baro_offset)) > 10) { - baro_offset = gps_data.NED[2] + altitude_data.altitude; - } else { - /* IIR filter with 100 second or so tau to keep them crudely in the same frame */ - baro_offset = baro_offset * 0.999 + (gps_data.NED[2] + altitude_data.altitude) * 0.001; - } - gps_data.updated = false; - } else if (gps_delay > INSGPS_GPS_TIMEOUT) { - vel[0] = 0; - vel[1] = 0; - vel[2] = 0; - sensors |= VERT_SENSORS | HORIZ_SENSORS; - } - - if(mag_data.updated) { - sensors |= MAG_SENSORS; - mag_data.updated = false; - } - - if(altitude_data.updated) { - sensors |= BARO_SENSOR; - altitude_data.updated = false; - } - - /* - * TODO: Need to add a general sanity check for all the inputs to make sure their kosher - * although probably should occur within INS itself - */ - INSCorrection(mag_data.scaled.axis, gps_data.NED, vel, altitude_data.altitude - baro_offset, sensors); -} - -/** - * @brief Update the EKF when in indoor mode - */ -void ins_indoor_update() -{ - float gyro[3], accel[3], vel[3]; - static uint32_t last_indoor_time = 0; - uint16_t sensors = 0; - - // format data for INS algo - gyro[0] = gyro_data.filtered.x; - gyro[1] = gyro_data.filtered.y; - gyro[2] = gyro_data.filtered.z; - accel[0] = accel_data.filtered.x, - accel[1] = accel_data.filtered.y, - accel[2] = accel_data.filtered.z, - - INSStatePrediction(gyro, accel, 1 / (float)EKF_RATE); - attitude_data.quaternion.q1 = Nav.q[0]; - attitude_data.quaternion.q2 = Nav.q[1]; - attitude_data.quaternion.q3 = Nav.q[2]; - attitude_data.quaternion.q4 = Nav.q[3]; - send_attitude(); // get message out quickly - send_velocity(); - send_position(); - INSCovariancePrediction(1 / (float)EKF_RATE); - - /* Indoors, update with zero position and velocity and high covariance */ - vel[0] = 0; - vel[1] = 0; - vel[2] = 0; - - uint32_t this_indoor_time = timer_count(); - float indoor_delay; - - /* - * Detect if greater than certain time since last gps update and if so - * reset EKF to that position since probably drifted too far for safe - * update - */ - if (this_indoor_time < last_indoor_time) - indoor_delay = ((0xFFFF - last_indoor_time) - this_indoor_time) / timer_rate(); - else - indoor_delay = (this_indoor_time - last_indoor_time) / timer_rate(); - last_indoor_time = this_indoor_time; - - if(indoor_delay > INSGPS_GPS_TIMEOUT) - INSPosVelReset(vel,vel); - else - sensors = HORIZ_SENSORS | VERT_SENSORS; - - if(mag_data.updated && (ahrs_algorithm == AHRSSETTINGS_ALGORITHM_INSGPS_INDOOR)) { - sensors |= MAG_SENSORS; - mag_data.updated = false; - } - - if(altitude_data.updated) { - sensors |= BARO_SENSOR; - altitude_data.updated = false; - } - - /* - * TODO: Need to add a general sanity check for all the inputs to make sure their kosher - * although probably should occur within INS itself - */ - INSCorrection(mag_data.scaled.axis, gps_data.NED, vel, altitude_data.altitude, sensors | HORIZ_SENSORS | VERT_SENSORS); -} - -/** - * @brief Initialize the EKF assuming stationary - */ -void ins_init_algorithm() -{ - float Rbe[3][3], q[4], accels[3], rpy[3], mag; - float ge[3]={0,0,-9.81}, zeros[3]={0,0,0}, Pdiag[16]={25,25,25,5,5,5,1e-5,1e-5,1e-5,1e-5,1e-5,1e-5,1e-5,1e-4,1e-4,1e-4}; - bool using_mags, using_gps; - - INSGPSInit(); - - HomeLocationData home; - HomeLocationGet(&home); - - accels[0]=accel_data.filtered.x; - accels[1]=accel_data.filtered.y; - accels[2]=accel_data.filtered.z; - - using_mags = (ahrs_algorithm == AHRSSETTINGS_ALGORITHM_INSGPS_OUTDOOR) || (ahrs_algorithm == AHRSSETTINGS_ALGORITHM_INSGPS_INDOOR); - using_mags &= (home.Be[0] != 0) || (home.Be[1] != 0) || (home.Be[2] != 0); /* only use mags when valid home location */ - - using_gps = (ahrs_algorithm == AHRSSETTINGS_ALGORITHM_INSGPS_OUTDOOR) && (gps_data.quality != 0); - - /* Block till a data update */ - get_accel_gyro_data(); - - /* Ensure we get mag data in a timely manner */ - uint16_t fail_count = 50; // 50 at 200 Hz is up to 0.25 sec - while(using_mags && !mag_data.updated && fail_count--) { - get_accel_gyro_data(); - AhrsPoll(); - } - using_mags &= mag_data.updated; - - if (using_mags) { - /* Spin waiting for mag data */ - while(!mag_data.updated) { - get_accel_gyro_data(); - AhrsPoll(); - } - mag_data.updated = false; - - RotFrom2Vectors(accels, ge, mag_data.scaled.axis, home.Be, Rbe); - R2Quaternion(Rbe,q); - if (using_gps) - INSSetState(gps_data.NED, zeros, q, zeros, zeros); - else - INSSetState(zeros, zeros, q, zeros, zeros); - } else { - // assume yaw = 0 - mag = VectorMagnitude(accels); - rpy[1] = asinf(-accels[0]/mag); - rpy[0] = atan2(accels[1]/mag,accels[2]/mag); - rpy[2] = 0; - RPY2Quaternion(rpy,q); - if (using_gps) - INSSetState(gps_data.NED, zeros, q, zeros, zeros); - else - INSSetState(zeros, zeros, q, zeros, zeros); - } - - INSResetP(Pdiag); - - // TODO: include initial estimate of gyro bias? -} - -/** - * @brief Simple update using just mag and accel. Yaw biased and big attitude changes. - */ -void simple_update() { - float q[4]; - float rpy[3]; - /***************** SIMPLE ATTITUDE FROM NORTH AND ACCEL ************/ - /* Very simple computation of the heading and attitude from accel. */ - rpy[2] = atan2((mag_data.raw.axis[MAG_RAW_Y_IDX]), (-1 * mag_data.raw.axis[MAG_RAW_X_IDX])) * RAD_TO_DEG; - rpy[1] = atan2(accel_data.filtered.x, accel_data.filtered.z) * RAD_TO_DEG; - rpy[0] = atan2(accel_data.filtered.y, accel_data.filtered.z) * RAD_TO_DEG; - - RPY2Quaternion(rpy, q); - attitude_data.quaternion.q1 = q[0]; - attitude_data.quaternion.q2 = q[1]; - attitude_data.quaternion.q3 = q[2]; - attitude_data.quaternion.q4 = q[3]; - send_attitude(); -} - -/** - * @brief Output all the important inputs and states of the ekf through serial port - */ -#ifdef DUMP_EKF - -extern float **P, *X; // covariance matrix and state vector - -void print_ekf_binary() -{ - uint16_t states = ins_get_num_states(); - uint8_t framing[16] = { 15, 14, 13, 12, 11, 10, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0 }; - // Dump raw buffer - PIOS_COM_SendBuffer(PIOS_COM_AUX, &framing[0], 16); // framing header (1:16) - PIOS_COM_SendBuffer(PIOS_COM_AUX, (uint8_t *) & total_conversion_blocks, sizeof(total_conversion_blocks)); // dump block number (17:20) - - PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, (uint8_t *) & accel_data.filtered.x, 4*3); // accel data (21:32) - PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, (uint8_t *) & gyro_data.filtered.x, 4*3); // gyro data (33:44) - - PIOS_COM_SendBuffer(PIOS_COM_AUX, (uint8_t *) & mag_data.updated, 1); // mag update (45) - PIOS_COM_SendBuffer(PIOS_COM_AUX, (uint8_t *) & mag_data.scaled.axis, 3*4); // mag data (46:57) - - PIOS_COM_SendBuffer(PIOS_COM_AUX, (uint8_t *) & gps_data, sizeof(gps_data)); // gps data (58:85) - - PIOS_COM_SendBuffer(PIOS_COM_AUX, (uint8_t *) & X, 4 * states); // X (86:149) - for(uint8_t i = 0; i < states; i++) - PIOS_COM_SendBuffer(PIOS_COM_AUX, (uint8_t *) &((*P)[i + i * states]), 4); // diag(P) (150:213) - - PIOS_COM_SendBuffer(PIOS_COM_AUX, (uint8_t *) & altitude_data.altitude, 4); // BaroAlt (214:217) - PIOS_COM_SendBuffer(PIOS_COM_AUX, (uint8_t *) & baro_offset, 4); // baro_offset (218:221) -} -#else -void print_ekf_binary() {} -#endif - -/** - * @brief Debugging function to output all the ADC samples - */ -#if defined(DUMP_RAW) -void print_ahrs_raw() -{ - int result; - static int previous_conversion = 0; - int16_t * valid_data_buffer; - - uint8_t framing[16] = - { 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, - 15 }; - - get_accel_gyro_data(); - - valid_data_buffer = PIOS_ADC_GetRawBuffer(); - - if (total_conversion_blocks != previous_conversion + 1) - PIOS_LED_On(PIOS_LED_HEARTBEAT); // not keeping up - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - previous_conversion = total_conversion_blocks; - - - // Dump raw buffer - result = PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, &framing[0], 16); // framing header - result += PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, (uint8_t *) & total_conversion_blocks, sizeof(total_conversion_blocks)); // dump block number - result += - PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, - (uint8_t *) & valid_data_buffer[0], - adc_oversampling * - PIOS_ADC_NUM_PINS * - sizeof(valid_data_buffer[0])); - if (result == 0) - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - else { - PIOS_LED_On(PIOS_LED_HEARTBEAT); - } -} -#endif - -#if defined(PIP_DUMP_RAW) - - #define MAX_OVERSAMPLING PIOS_ADC_MAX_OVERSAMPLING - - void print_ahrs_raw() - { - int16_t accel_x[MAX_OVERSAMPLING], accel_y[MAX_OVERSAMPLING], accel_z[MAX_OVERSAMPLING]; - int16_t gyro_x[MAX_OVERSAMPLING], gyro_y[MAX_OVERSAMPLING], gyro_z[MAX_OVERSAMPLING]; - #if defined(PIOS_INCLUDE_HMC5843) && defined(PIOS_INCLUDE_I2C) - int16_t mag[3]; - int16_t mag_x, mag_y, mag_z; - #endif - - static int previous_conversion = 0; - - uint8_t framing[3] = {0xD2, 0x73, 0x00}; - - // wait for new raw samples - while (previous_conversion == total_conversion_blocks); - if ((previous_conversion + 1) != total_conversion_blocks) - PIOS_LED_On(PIOS_LED_HEARTBEAT); // we are not keeping up - previous_conversion = total_conversion_blocks; - - // fetch the buffer address for the new samples - int16_t *valid_data_buffer = PIOS_ADC_GetRawBuffer(); - - // fetch number of raw samples in the buffer (per channel) - int over_sampling = PIOS_ADC_GetOverSampling(); - - framing[2] = over_sampling; - - // copy the raw samples into their own buffers - for (uint16_t i = 0, j = 0; i < over_sampling; i++, j += PIOS_ADC_NUM_CHANNELS) - { - accel_x[i] = valid_data_buffer[ACCEL_RAW_X_IDX + j]; - accel_y[i] = valid_data_buffer[ACCEL_RAW_Y_IDX + j]; - accel_z[i] = valid_data_buffer[ACCEL_RAW_Z_IDX + j]; - - gyro_x[i] = valid_data_buffer[GYRO_RAW_X_IDX + j]; - gyro_y[i] = valid_data_buffer[GYRO_RAW_Y_IDX + j]; - gyro_z[i] = valid_data_buffer[GYRO_RAW_Z_IDX + j]; - } - - #if defined(PIOS_INCLUDE_HMC5843) && defined(PIOS_INCLUDE_I2C) - if (PIOS_HMC5843_NewDataAvailable()) - { - PIOS_HMC5843_ReadMag(mag); - - mag_x = mag[MAG_RAW_X_IDX]; - mag_y = mag[MAG_RAW_Y_IDX]; - mag_z = mag[MAG_RAW_Z_IDX]; - } - #endif - - // send the raw samples - int result = PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, framing, sizeof(framing)); - result += PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, (uint8_t *)accel_x, over_sampling * sizeof(accel_x[0])); - result += PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, (uint8_t *)accel_y, over_sampling * sizeof(accel_y[0])); - result += PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, (uint8_t *)accel_z, over_sampling * sizeof(accel_z[0])); - result += PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, (uint8_t *)gyro_x, over_sampling * sizeof(gyro_x[0])); - result += PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, (uint8_t *)gyro_y, over_sampling * sizeof(gyro_y[0])); - result += PIOS_COM_SendBufferNonBlocking(PIOS_COM_AUX, (uint8_t *)gyro_z, over_sampling * sizeof(gyro_z[0])); - - if (result != 0) - PIOS_LED_On(PIOS_LED_HEARTBEAT); // all data not sent - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } -#endif - -extern void PIOS_Board_Init(void); - -/** - * @brief AHRS Main function - */ -int main() -{ - gps_data.quality = -1; - uint32_t up_time_real = 0; - uint32_t up_time = 0; - uint32_t last_up_time = 0; - static int8_t last_ahrs_algorithm; - uint32_t last_counter_idle_start = 0; - uint32_t last_counter_idle_end = 0; - uint32_t idle_counts = 0; - uint32_t running_counts = 0; - uint32_t counter_val = 0; - ahrs_algorithm = AHRSSETTINGS_ALGORITHM_SIMPLE; - - reset_values(); - - PIOS_Board_Init(); - -#if defined(PIOS_INCLUDE_HMC5843) && defined(PIOS_INCLUDE_I2C) - // Get 3 ID bytes - strcpy((char *)mag_data.id, "ZZZ"); - PIOS_HMC5843_ReadID(mag_data.id); -#endif - - while(!AhrsLinkReady()) { - AhrsPoll(); - } -/* we didn't connect the callbacks before because we have to wait -for all data to be up to date before doing anything*/ - - AHRSCalibrationConnectCallback(calibration_callback); - GPSPositionConnectCallback(gps_callback); - BaroAltitudeConnectCallback(altitude_callback); - AHRSSettingsConnectCallback(settings_callback); - HomeLocationConnectCallback(homelocation_callback); - FirmwareIAPObjConnectCallback(firmwareiapobj_callback); - - calibration_callback(AHRSCalibrationHandle()); //force an update - -#if defined(DUMP_RAW) || defined(PIP_DUMP_RAW) - while (1) { - AhrsPoll(); - print_ahrs_raw(); - } -#endif - - timer_start(); - - /******************* Main EKF loop ****************************/ - while(1) { - - - AhrsPoll(); - AhrsStatusData status; - AhrsStatusGet(&status); - status.CPULoad = ((float)running_counts / - (float)(idle_counts + running_counts)) * 100; - status.IdleTimePerCyle = idle_counts / (timer_rate() / 10000); - status.RunningTimePerCyle = running_counts / (timer_rate() / 10000); - status.DroppedUpdates = ekf_too_slow; - up_time = timer_count(); - if(up_time >= last_up_time) // normal condition - up_time_real += ((up_time - last_up_time) * 1000) / timer_rate(); - else - up_time_real += ((0xFFFF - last_up_time + up_time) * 1000) / timer_rate(); - last_up_time = up_time; - status.RunningTime = up_time_real; - AhrsStatusSet(&status); - - // Alive signal - if (((total_conversion_blocks % 100) & 0xFFFE) == 0) - PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); - - // Delay for valid data - - counter_val = timer_count(); - running_counts = counter_val - last_counter_idle_end; - last_counter_idle_start = counter_val; - - // This function blocks till data avilable - get_accel_gyro_data(); - - // Get any mag data available - process_mag_data(); - - counter_val = timer_count(); - idle_counts = counter_val - last_counter_idle_start; - last_counter_idle_end = counter_val; - - - if(ISNAN(accel_data.filtered.x + accel_data.filtered.y + accel_data.filtered.z) || - ISNAN(gyro_data.filtered.x + gyro_data.filtered.y + gyro_data.filtered.z) || - ACCEL_OOB(accel_data.filtered.x + accel_data.filtered.y + accel_data.filtered.z) || - GYRO_OOB(gyro_data.filtered.x + gyro_data.filtered.y + gyro_data.filtered.z)) { - // If any values are NaN or huge don't update -//TODO: add field to ahrs status to track number of these events - continue; - } - - print_ekf_binary(); - - /* If algorithm changed reinit. This could go in callback but wouldn't be synchronous */ - if (ahrs_algorithm != last_ahrs_algorithm) - ins_init_algorithm(); - last_ahrs_algorithm = ahrs_algorithm; - - switch(ahrs_algorithm) { - case AHRSSETTINGS_ALGORITHM_SIMPLE: - simple_update(); - break; - case AHRSSETTINGS_ALGORITHM_INSGPS_OUTDOOR: - ins_outdoor_update(); - break; - case AHRSSETTINGS_ALGORITHM_INSGPS_INDOOR: - case AHRSSETTINGS_ALGORITHM_INSGPS_INDOOR_NOMAG: - ins_indoor_update(); - break; - } - } - - return 0; -} - -/** - * @brief Get the accel and gyro data from whichever source when available - * - * This function will act as the HAL for the new INS sensors - */ -bool get_accel_gyro_data() -{ - float accel[6]; - float gyro[6]; - uint16_t spin_count = 1; - while(fifoBuf_getUsed(&adc_fifo_buffer) < (sizeof(accel) + sizeof(gyro))) { - if(spin_count++ == 0) - AhrsPoll(); - } - - fifoBuf_getData(&adc_fifo_buffer, &accel[0], sizeof(float) * 3); - fifoBuf_getData(&adc_fifo_buffer, &gyro[0], sizeof(float) * 3); - fifoBuf_getData(&adc_fifo_buffer, &accel[3], sizeof(float) * 3); - fifoBuf_getData(&adc_fifo_buffer, &gyro[3], sizeof(float) * 3); - - accel_data.filtered.x = (accel[0] + accel[3]) / 2; - accel_data.filtered.y = (accel[1] + accel[4]) / 2; - accel_data.filtered.z = (accel[2] + accel[5]) / 2; - gyro_data.filtered.x = (gyro[0] + gyro[3]) / 2; - gyro_data.filtered.y = (gyro[1] + gyro[4]) / 2; - gyro_data.filtered.z = (gyro[2] + gyro[5]) / 2; - return true; -} - -/** - * @brief Perform calibration of a 3-axis field sensor using an affine transformation - * matrix. - * - * Computes result = scale * arg. - * - * @param result[out] The three-axis resultant field. - * @param scale[in] The 4x4 affine transformation matrix. The fourth row is implicitly - * [0 0 0 1] - * @param arg[in] The 3-axis input field. The 'w' component is implicitly 1. - */ -void calibration(float result[3], float scale[3][4], float arg[3]) -{ - for (int row = 0; row < 3; ++row) { - result[row] = 0.0f; - int col; - for (col = 0; col < 3; ++col) { - result[row] += scale[row][col] * arg[col]; - } - // fourth column: arg has an implicit w value of 1.0f. - result[row] += scale[row][col]; - } -} - -/** - * @brief Scale an affine transformation matrix by a rotation, defined by a - * rotation vector. scale <- rotation * scale - * - * @param scale[in,out] The affine transformation matrix to be rotated - * @param rotation[in] The rotation vector defining the rotation - */ -void affine_rotate(float scale[3][4], float rotation[3]) -{ - // Rotate the scale factor matrix in-place - float rmatrix[3][3]; - Rv2Rot(rotation, rmatrix); - - float ret[3][4]; - for (int row = 0; row < 3; ++row) { - for (int col = 0; col < 4; ++col) { - ret[row][col] = 0.0f; - for (int i = 0; i < 3; ++i) { - ret[row][col] += rmatrix[row][i] * scale[i][col]; - } - } - } - // copy output to argument - for (int row = 0; row < 3; ++row) { - for (int col = 0; col < 4; ++col) { - scale[row][col] = ret[row][col]; - } - } -} - -/** - * @brief Downsample the analog data - * @return none - * - * Tried to make as much of the filtering fixed point when possible. Need to account - * for offset for each sample before the multiplication if filter not a boxcar. Could - * precompute fixed offset as sum[fir_coeffs[i]] * ACCEL_OFFSET. Puts data into global - * data structures @ref accel_data and @ref gyro_data. - * - * The accel_data values are converted into a coordinate system where X is forwards along - * the fuselage, Y is along right the wing, and Z is down. - */ -void adc_callback(float * downsampled_data) -{ - AHRSSettingsData settings; - AHRSSettingsGet(&settings); - -#if 0 - // Get the Y data. Third byte in. Convert to m/s - float accel_filtered[3]; - accel_filtered[1] = 0; - for (i = 0; i < adc_oversampling; i++) - accel_filtered[1] += valid_data_buffer[0 + i * PIOS_ADC_NUM_PINS] * fir_coeffs[i]; - accel_filtered[1] /= (float) fir_coeffs[adc_oversampling]; - // Get the X data which projects forward/backwards. Fifth byte in. Convert to m/s - accel_filtered[0] = 0; - for (i = 0; i < adc_oversampling; i++) - accel_filtered[0] += valid_data_buffer[2 + i * PIOS_ADC_NUM_PINS] * fir_coeffs[i]; - accel_filtered[0] /= (float) fir_coeffs[adc_oversampling]; - - // Get the Z data. Third byte in. Convert to m/s - accel_filtered[2] = 0; - for (i = 0; i < adc_oversampling; i++) - accel_filtered[2] += valid_data_buffer[4 + i * PIOS_ADC_NUM_PINS] * fir_coeffs[i]; - accel_filtered[2] /= (float) fir_coeffs[adc_oversampling]; - - float accel_scaled[3]; - calibration(accel_scaled, accel_data.calibration.scale, accel_filtered); - accel_data.filtered.x = accel_scaled[0]; - accel_data.filtered.y = accel_scaled[1]; - accel_data.filtered.z = accel_scaled[2]; -#else - float accel[3], gyro[3]; - - float raw_accel[3] = { - downsampled_data[ACCEL_RAW_X_IDX], - downsampled_data[ACCEL_RAW_Y_IDX], - -downsampled_data[ACCEL_RAW_Z_IDX] - }; - - // Accel data is (y,x,z) in first third and fifth byte. Convert to m/s^2 - calibration(accel, accel_data.calibration.scale, raw_accel); - - // Gyro data is (x,y,z) in second, fifth and seventh byte. Convert to rad/s - gyro[0] = ( ( downsampled_data[GYRO_RAW_X_IDX] + gyro_data.calibration.tempcompfactor[0] * downsampled_data[GYRO_TEMP_RAW_XY_IDX] ) * gyro_data.calibration.scale[0]) + gyro_data.calibration.bias[0]; - gyro[1] = ( ( downsampled_data[GYRO_RAW_Y_IDX] + gyro_data.calibration.tempcompfactor[1] * downsampled_data[GYRO_TEMP_RAW_XY_IDX] ) * gyro_data.calibration.scale[1]) + gyro_data.calibration.bias[1]; - gyro[2] = ( ( downsampled_data[GYRO_RAW_Z_IDX] + gyro_data.calibration.tempcompfactor[2] * downsampled_data[GYRO_TEMP_RAW_Z_IDX] ) * gyro_data.calibration.scale[2]) + gyro_data.calibration.bias[2]; - -#endif -#if 0 - static float gravity_tracking[3] = {0,0,0}; - const float tau = 0.9999; - gravity_tracking[0] = tau * gravity_tracking[0] + (1-tau) * accel[0]; - gravity_tracking[1] = tau * gravity_tracking[1] + (1-tau) * accel[1]; - gravity_tracking[2] = tau * gravity_tracking[2] + (1-tau) * (accel[2] + 9.81); - if(settings.BiasCorrectedRaw == AHRSSETTINGS_BIASCORRECTEDRAW_TRUE) { - accel[0] -= gravity_tracking[0]; - accel[1] -= gravity_tracking[1]; - accel[2] -= gravity_tracking[2]; - } -#endif - if(fifoBuf_getFree(&adc_fifo_buffer) >= (sizeof(accel) + sizeof(gyro))) { - fifoBuf_putData(&adc_fifo_buffer, (uint8_t *) &accel[0], sizeof(accel)); - fifoBuf_putData(&adc_fifo_buffer, (uint8_t *) &gyro[0], sizeof(gyro)); - } else { - ekf_too_slow++; - } - - AttitudeRawData raw; - - raw.gyrotemp[0] = downsampled_data[GYRO_TEMP_RAW_XY_IDX]; - raw.gyrotemp[1] = downsampled_data[GYRO_TEMP_RAW_Z_IDX]; - - raw.gyros[0] = gyro[0] * RAD_TO_DEG; - raw.gyros[1] = gyro[1] * RAD_TO_DEG; - raw.gyros[2] = gyro[2] * RAD_TO_DEG; - - raw.accels[0] = accel[0]; - raw.accels[1] = accel[1]; - raw.accels[2] = accel[2]; - - raw.magnetometers[0] = mag_data.scaled.axis[0]; - raw.magnetometers[1] = mag_data.scaled.axis[1]; - raw.magnetometers[2] = mag_data.scaled.axis[2]; - - if (settings.BiasCorrectedRaw == AHRSSETTINGS_BIASCORRECTEDRAW_TRUE) - { - raw.gyros[0] -= Nav.gyro_bias[0] * RAD_TO_DEG; - raw.gyros[1] -= Nav.gyro_bias[1] * RAD_TO_DEG; - raw.gyros[2] -= Nav.gyro_bias[2] * RAD_TO_DEG; - - raw.accels[0] -= Nav.accel_bias[0]; - raw.accels[1] -= Nav.accel_bias[1]; - raw.accels[2] -= Nav.accel_bias[2]; - } - - AttitudeRawSet(&raw); - - total_conversion_blocks++; -} - -#if defined(PIOS_INCLUDE_HMC5843) && defined(PIOS_INCLUDE_I2C) -/** - * @brief Get the mag data from the I2C sensor and load into structure - * @return none - * - * This function also considers if the home location is set and has a valid - * magnetic field before updating the mag data to prevent data being used that - * cannot be interpreted. In addition the mag data is not used for the first - * five seconds to allow the filter to start to converge - */ -void process_mag_data() -{ - // Get magnetic readings - // For now don't use mags until the magnetic field is set AND until 5 seconds - // after initialization otherwise it seems to have problems - // TODO: Follow up this initialization issue - HomeLocationData home; - HomeLocationGet(&home); - if (PIOS_HMC5843_NewDataAvailable()) { - PIOS_HMC5843_ReadMag(mag_data.raw.axis); - - // Swap the axis here to acount for orientation of mag chip (notice 0 and 1 swapped in raw) - mag_data.scaled.axis[0] = (mag_data.raw.axis[MAG_RAW_X_IDX] * mag_data.calibration.scale[0]) + mag_data.calibration.bias[0]; - mag_data.scaled.axis[1] = (mag_data.raw.axis[MAG_RAW_Y_IDX] * mag_data.calibration.scale[1]) + mag_data.calibration.bias[1]; - mag_data.scaled.axis[2] = (mag_data.raw.axis[MAG_RAW_Z_IDX] * mag_data.calibration.scale[2]) + mag_data.calibration.bias[2]; - - // Only use if magnetic length reasonable - float Blen = sqrt(pow(mag_data.scaled.axis[0],2) + pow(mag_data.scaled.axis[1],2) + pow(mag_data.scaled.axis[2],2)); - - mag_data.updated = (home.Set == HOMELOCATION_SET_TRUE) && - ((home.Be[0] != 0) || (home.Be[1] != 0) || (home.Be[2] != 0)) && - ((mag_data.raw.axis[MAG_RAW_X_IDX] != 0) || (mag_data.raw.axis[MAG_RAW_Y_IDX] != 0) || (mag_data.raw.axis[MAG_RAW_Z_IDX] != 0)) && - ((Blen < mag_len * (1 + INSGPS_MAGTOL)) && (Blen > mag_len * (1 - INSGPS_MAGTOL))); - } -} -#else -void process_mag_data() { } -#endif - -/** - * @brief Assumes board is not moving computes biases and variances of sensors - * @returns None - * - * All data is stored in global structures. This function should be called from OP when - * aircraft is in stable state and then the data stored to SD card. - * - * After this function the bias for each sensor will be the mean value. This doesn't make - * sense for the z accel so make sure 6 point calibration is also run and those values set - * after these read. - */ -#define NBIAS 100 -#define NVAR 500 -void calibrate_sensors() -{ - int i,j; - float accel_bias[3] = {0, 0, 0}; - float gyro_bias[3] = {0, 0, 0}; - float mag_bias[3] = {0, 0, 0}; - - - for (i = 0, j = 0; i < NBIAS; i++) { - - get_accel_gyro_data(); - - gyro_bias[0] += gyro_data.filtered.x / NBIAS; - gyro_bias[1] += gyro_data.filtered.y / NBIAS; - gyro_bias[2] += gyro_data.filtered.z / NBIAS; - accel_bias[0] += accel_data.filtered.x / NBIAS; - accel_bias[1] += accel_data.filtered.y / NBIAS; - accel_bias[2] += accel_data.filtered.z / NBIAS; - -#if defined(PIOS_INCLUDE_HMC5843) && defined(PIOS_INCLUDE_I2C) - if(PIOS_HMC5843_NewDataAvailable()) { - j ++; - PIOS_HMC5843_ReadMag(mag_data.raw.axis); - mag_data.scaled.axis[0] = (mag_data.raw.axis[MAG_RAW_X_IDX] * mag_data.calibration.scale[0]) + mag_data.calibration.bias[0]; - mag_data.scaled.axis[1] = (mag_data.raw.axis[MAG_RAW_Y_IDX] * mag_data.calibration.scale[1]) + mag_data.calibration.bias[1]; - mag_data.scaled.axis[2] = (mag_data.raw.axis[MAG_RAW_Z_IDX] * mag_data.calibration.scale[2]) + mag_data.calibration.bias[2]; - mag_bias[0] += mag_data.scaled.axis[0]; - mag_bias[1] += mag_data.scaled.axis[1]; - mag_bias[2] += mag_data.scaled.axis[2]; - } -#endif - - } - mag_bias[0] /= j; - mag_bias[1] /= j; - mag_bias[2] /= j; - - gyro_data.calibration.variance[0] = 0; - gyro_data.calibration.variance[1] = 0; - gyro_data.calibration.variance[2] = 0; - mag_data.calibration.variance[0] = 0; - mag_data.calibration.variance[1] = 0; - mag_data.calibration.variance[2] = 0; - accel_data.calibration.variance[0] = 0; - accel_data.calibration.variance[1] = 0; - accel_data.calibration.variance[2] = 0; - - for (i = 0, j = 0; j < NVAR; j++) { - get_accel_gyro_data(); - - gyro_data.calibration.variance[0] += pow(gyro_data.filtered.x-gyro_bias[0],2) / NVAR; - gyro_data.calibration.variance[1] += pow(gyro_data.filtered.y-gyro_bias[1],2) / NVAR; - gyro_data.calibration.variance[2] += pow(gyro_data.filtered.z-gyro_bias[2],2) / NVAR; - accel_data.calibration.variance[0] += pow(accel_data.filtered.x-accel_bias[0],2) / NVAR; - accel_data.calibration.variance[1] += pow(accel_data.filtered.y-accel_bias[1],2) / NVAR; - accel_data.calibration.variance[2] += pow(accel_data.filtered.z-accel_bias[2],2) / NVAR; - -#if defined(PIOS_INCLUDE_HMC5843) && defined(PIOS_INCLUDE_I2C) - if(PIOS_HMC5843_NewDataAvailable()) { - j ++; - PIOS_HMC5843_ReadMag(mag_data.raw.axis); - mag_data.scaled.axis[0] = (mag_data.raw.axis[MAG_RAW_X_IDX] * mag_data.calibration.scale[0]) + mag_data.calibration.bias[0]; - mag_data.scaled.axis[1] = (mag_data.raw.axis[MAG_RAW_Y_IDX] * mag_data.calibration.scale[1]) + mag_data.calibration.bias[1]; - mag_data.scaled.axis[2] = (mag_data.raw.axis[MAG_RAW_Z_IDX] * mag_data.calibration.scale[2]) + mag_data.calibration.bias[2]; - mag_data.calibration.variance[0] += pow(mag_data.scaled.axis[0]-mag_bias[0],2); - mag_data.calibration.variance[1] += pow(mag_data.scaled.axis[1]-mag_bias[1],2); - mag_data.calibration.variance[2] += pow(mag_data.scaled.axis[2]-mag_bias[2],2); - } -#endif - - } - - mag_data.calibration.variance[0] /= j; - mag_data.calibration.variance[1] /= j; - mag_data.calibration.variance[2] /= j; - - gyro_data.calibration.bias[0] -= gyro_bias[0]; - gyro_data.calibration.bias[1] -= gyro_bias[1]; - gyro_data.calibration.bias[2] -= gyro_bias[2]; -} - -/** - * @brief Populate fields with initial values - */ -void reset_values() -{ - accel_data.calibration.scale[0][1] = 0; - accel_data.calibration.scale[1][0] = 0; - accel_data.calibration.scale[0][2] = 0; - accel_data.calibration.scale[2][0] = 0; - accel_data.calibration.scale[1][2] = 0; - accel_data.calibration.scale[2][1] = 0; - - accel_data.calibration.scale[0][0] = 0.0359; - accel_data.calibration.scale[1][1] = 0.0359; - accel_data.calibration.scale[2][2] = 0.0359; - accel_data.calibration.scale[0][3] = -73.5; - accel_data.calibration.scale[1][3] = -73.5; - accel_data.calibration.scale[2][3] = -73.5; - - accel_data.calibration.variance[0] = 1e-4; - accel_data.calibration.variance[1] = 1e-4; - accel_data.calibration.variance[2] = 1e-4; - - gyro_data.calibration.scale[0] = -0.014; - gyro_data.calibration.scale[1] = 0.014; - gyro_data.calibration.scale[2] = -0.014; - gyro_data.calibration.bias[0] = -24; - gyro_data.calibration.bias[1] = -24; - gyro_data.calibration.bias[2] = -24; - gyro_data.calibration.variance[0] = 1; - gyro_data.calibration.variance[1] = 1; - gyro_data.calibration.variance[2] = 1; - mag_data.calibration.scale[0] = 1; - mag_data.calibration.scale[1] = 1; - mag_data.calibration.scale[2] = 1; - mag_data.calibration.bias[0] = 0; - mag_data.calibration.bias[1] = 0; - mag_data.calibration.bias[2] = 0; - mag_data.calibration.variance[0] = 50; - mag_data.calibration.variance[1] = 50; - mag_data.calibration.variance[2] = 50; -} - - -void send_attitude(void) -{ - AttitudeActualData attitude; - AHRSSettingsData settings; - AHRSSettingsGet(&settings); - - attitude.q1 = attitude_data.quaternion.q1; - attitude.q2 = attitude_data.quaternion.q2; - attitude.q3 = attitude_data.quaternion.q3; - attitude.q4 = attitude_data.quaternion.q4; - float rpy[3]; - Quaternion2RPY(&attitude_data.quaternion.q1, rpy); - attitude.Roll = rpy[0] + settings.RollBias; - attitude.Pitch = rpy[1] + settings.PitchBias; - attitude.Yaw = rpy[2] + settings.YawBias; - if(attitude.Yaw > 360) - attitude.Yaw -= 360; - AttitudeActualSet(&attitude); -} - -void send_velocity(void) -{ - VelocityActualData velocityActual; - VelocityActualGet(&velocityActual); - - // convert into cm - velocityActual.North = Nav.Vel[0] * 100; - velocityActual.East = Nav.Vel[1] * 100; - velocityActual.Down = Nav.Vel[2] * 100; - - VelocityActualSet(&velocityActual); -} - -void send_position(void) -{ - PositionActualData positionActual; - PositionActualGet(&positionActual); - - // convert into cm - positionActual.North = Nav.Pos[0] * 100; - positionActual.East = Nav.Pos[1] * 100; - positionActual.Down = Nav.Pos[2] * 100; - - PositionActualSet(&positionActual); -} - -void send_calibration(void) -{ - AHRSCalibrationData cal; - AHRSCalibrationGet(&cal); - for(int ct=0; ct<3; ct++) - { - cal.accel_var[ct] = accel_data.calibration.variance[ct]; - cal.gyro_bias[ct] = gyro_data.calibration.bias[ct]; - cal.gyro_var[ct] = gyro_data.calibration.variance[ct]; - cal.mag_var[ct] = mag_data.calibration.variance[ct]; - } - cal.measure_var = AHRSCALIBRATION_MEASURE_VAR_SET; - AHRSCalibrationSet(&cal); -} - -/** - * @brief AHRS calibration callback - * - * Called when the OP board sets the calibration - */ -void calibration_callback(AhrsObjHandle obj) -{ - AHRSCalibrationData cal; - AHRSCalibrationGet(&cal); - if(cal.measure_var == AHRSCALIBRATION_MEASURE_VAR_SET){ - - accel_data.calibration.scale[0][1] = cal.accel_ortho[0]; - accel_data.calibration.scale[1][0] = cal.accel_ortho[0]; - - accel_data.calibration.scale[0][2] = cal.accel_ortho[1]; - accel_data.calibration.scale[2][0] = cal.accel_ortho[1]; - - accel_data.calibration.scale[1][2] = cal.accel_ortho[2]; - accel_data.calibration.scale[2][1] = cal.accel_ortho[2]; - -#if 0 - // TODO: Enable after v1.0 feature freeze. - float rotation[3] = { cal.accel_rotation[0], - cal.accel_rotation[1], - cal.accel_rotation[2], - }; - - affine_rotate(accel_data.calibration.scale, rotation); -#endif - - for(int ct=0; ct<3; ct++) - { - accel_data.calibration.scale[ct][ct] = cal.accel_scale[ct]; - accel_data.calibration.scale[ct][3] = cal.accel_bias[ct]; - accel_data.calibration.variance[ct] = cal.accel_var[ct]; - - gyro_data.calibration.scale[ct] = cal.gyro_scale[ct]; - gyro_data.calibration.bias[ct] = cal.gyro_bias[ct]; - gyro_data.calibration.variance[ct] = cal.gyro_var[ct]; -#if 1 - gyro_data.calibration.tempcompfactor[ct] = cal.gyro_tempcompfactor[ct]; -#endif - mag_data.calibration.bias[ct] = cal.mag_bias[ct]; - mag_data.calibration.scale[ct] = cal.mag_scale[ct]; - mag_data.calibration.variance[ct] = cal.mag_var[ct]; - } - // Note: We need the divided by 1000^2 since we scale mags to have a norm of 1000 and they are scaled to - // one in code - float mag_var[3] = {mag_data.calibration.variance[0] / INSGPS_MAGLEN / INSGPS_MAGLEN, - mag_data.calibration.variance[1] / INSGPS_MAGLEN / INSGPS_MAGLEN, - mag_data.calibration.variance[2] / INSGPS_MAGLEN / INSGPS_MAGLEN}; - INSSetMagVar(mag_var); - INSSetAccelVar(accel_data.calibration.variance); - INSSetGyroVar(gyro_data.calibration.variance); - } - else if(cal.measure_var == AHRSCALIBRATION_MEASURE_VAR_MEASURE) { - calibrate_sensors(); - send_calibration(); - } - - INSSetPosVelVar(cal.pos_var, cal.vel_var); - -} - -void gps_callback(AhrsObjHandle obj) -{ - GPSPositionData pos; - GPSPositionGet(&pos); - HomeLocationData home; - HomeLocationGet(&home); - - // convert from cm back to meters - double LLA[3] = {(double) pos.Latitude / 1e7, (double) pos.Longitude / 1e7, (double) (pos.GeoidSeparation + pos.Altitude)}; - // put in local NED frame - double ECEF[3] = {(double) (home.ECEF[0] / 100), (double) (home.ECEF[1] / 100), (double) (home.ECEF[2] / 100)}; - LLA2Base(LLA, ECEF, (float (*)[3]) home.RNE, gps_data.NED); - - gps_data.heading = pos.Heading; - gps_data.groundspeed = pos.Groundspeed; - gps_data.quality = 1; /* currently unused */ - gps_data.updated = true; - - // if poor don't use this update - if((ahrs_algorithm != AHRSSETTINGS_ALGORITHM_INSGPS_OUTDOOR) || - (pos.Satellites < INSGPS_GPS_MINSAT) || - (pos.PDOP >= INSGPS_GPS_MINPDOP) || - (home.Set == FALSE) || - ((home.ECEF[0] == 0) && (home.ECEF[1] == 0) && (home.ECEF[2] == 0))) - { - gps_data.quality = 0; - gps_data.updated = false; - } - -} - -void altitude_callback(AhrsObjHandle obj) -{ - BaroAltitudeData alt; - BaroAltitudeGet(&alt); - altitude_data.altitude = alt.Altitude; - altitude_data.updated = true; -} - -void settings_callback(AhrsObjHandle obj) -{ - AHRSSettingsData settings; - AHRSSettingsGet(&settings); - - ahrs_algorithm = settings.Algorithm; - - if(settings.Downsampling != adc_oversampling) { - adc_oversampling = settings.Downsampling; - PIOS_ADC_Config(adc_oversampling); - } -} - -void homelocation_callback(AhrsObjHandle obj) -{ - HomeLocationData data; - HomeLocationGet(&data); - - mag_len = sqrt(pow(data.Be[0],2) + pow(data.Be[1],2) + pow(data.Be[2],2)); - float Be[3] = {data.Be[0] / mag_len, data.Be[1] / mag_len, data.Be[2] / mag_len}; - - INSSetMagNorth(Be); -} - -void firmwareiapobj_callback(AhrsObjHandle obj) -{ - const struct pios_board_info * bdinfo = &pios_board_info_blob; - - FirmwareIAPObjData firmwareIAPObj; - FirmwareIAPObjGet(&firmwareIAPObj); - if(firmwareIAPObj.ArmReset==0) - reset_count=0; - if(firmwareIAPObj.ArmReset==1) - { - - if((firmwareIAPObj.BoardType==bdinfo->board_type) || (firmwareIAPObj.BoardType==0xFF)) - { - - ++reset_count; - if(reset_count>2) - { - PIOS_IAP_SetRequest1(); - PIOS_IAP_SetRequest2(); - PIOS_SYS_Reset(); - } - } - } - else if(firmwareIAPObj.BoardType==bdinfo->board_type && firmwareIAPObj.crc!=PIOS_BL_HELPER_CRC_Memory_Calc()) - { - PIOS_BL_HELPER_FLASH_Read_Description(firmwareIAPObj.Description,bdinfo->desc_size); - firmwareIAPObj.crc=PIOS_BL_HELPER_CRC_Memory_Calc(); - firmwareIAPObj.BoardRevision=bdinfo->board_rev; - FirmwareIAPObjSet(&firmwareIAPObj); - } -} - -/** - * @} - */ - diff --git a/flight/AHRS/inc/ahrs.h b/flight/AHRS/inc/ahrs.h deleted file mode 100644 index 99c0656e6..000000000 --- a/flight/AHRS/inc/ahrs.h +++ /dev/null @@ -1,115 +0,0 @@ -/** - ****************************************************************************** - * - * @file ahrs.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main AHRS header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef AHRS_H -#define AHRS_H - -/* PIOS Includes */ -#include - -struct mag_sensor { - uint8_t id[4]; - uint8_t updated; - struct { - int16_t axis[3]; - } raw; - struct { - float axis[3]; - } scaled; - struct { - float bias[3]; - float scale[3]; - float variance[3]; - } calibration; -}; - -//! Contains the data from the accelerometer -struct accel_sensor { - struct { - uint16_t x; - uint16_t y; - uint16_t z; - } raw; - struct { - float x; - float y; - float z; - } filtered; - struct { - float scale[3][4]; - float variance[3]; - } calibration; -}; - -//! Contains the data from the gyro -struct gyro_sensor { - struct { - uint16_t x; - uint16_t y; - uint16_t z; - } raw; - struct { - float x; - float y; - float z; - } filtered; - struct { - float bias[3]; - float scale[3]; - float variance[3]; - float tempcompfactor[3]; - } calibration; - struct { - uint16_t xy; - uint16_t z; - } temp; -}; - -//! Conains the current estimate of the attitude -struct attitude_solution { - struct { - float q1; - float q2; - float q3; - float q4; - } quaternion; -}; - -//! Contains data from the altitude sensor -struct altitude_sensor { - float altitude; - bool updated; -}; - -//! Contains data from the GPS (via the SPI link) -struct gps_sensor { - float NED[3]; - float heading; - float groundspeed; - float quality; - bool updated; -}; - -#endif /* AHRS_H */ diff --git a/flight/AHRS/inc/ahrs_fsm.h b/flight/AHRS/inc/ahrs_fsm.h deleted file mode 100644 index dd9d24b21..000000000 --- a/flight/AHRS/inc/ahrs_fsm.h +++ /dev/null @@ -1,94 +0,0 @@ - /** - ****************************************************************************** - * - * @file ahrs_fsm.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef AHRS_FSM_H -#define AHRS_FSM_H - -#include "pios_opahrs_proto.h" - -enum lfsm_state { - LFSM_STATE_FAULTED = 0, /* Must be zero so undefined transitions land here */ - LFSM_STATE_STOPPED, - LFSM_STATE_STOPPING, - LFSM_STATE_INACTIVE, - LFSM_STATE_USER_BUSY, - LFSM_STATE_USER_BUSY_RX_PENDING, - LFSM_STATE_USER_BUSY_TX_PENDING, - LFSM_STATE_USER_BUSY_RXTX_PENDING, - LFSM_STATE_USER_RX_PENDING, - LFSM_STATE_USER_TX_PENDING, - LFSM_STATE_USER_RXTX_PENDING, - LFSM_STATE_USER_RX_ACTIVE, - LFSM_STATE_USER_TX_ACTIVE, - LFSM_STATE_USER_RXTX_ACTIVE, - - LFSM_STATE_NUM_STATES /* Must be last */ -}; - -enum lfsm_event { - LFSM_EVENT_INIT_LINK, - LFSM_EVENT_STOP, - LFSM_EVENT_USER_SET_RX, - LFSM_EVENT_USER_SET_TX, - LFSM_EVENT_USER_DONE, - LFSM_EVENT_RX_LINK, - LFSM_EVENT_RX_USER, - LFSM_EVENT_RX_UNKNOWN, - - LFSM_EVENT_NUM_EVENTS /* Must be last */ -}; - -struct lfsm_link_stats { - uint32_t rx_badcrc; - uint32_t rx_badmagic_head; - uint32_t rx_badmagic_tail; - uint32_t rx_link; - uint32_t rx_user; - uint32_t tx_user; - uint32_t rx_badtype; - uint32_t rx_badver; -}; - -extern void lfsm_init(void); -extern void lfsm_inject_event(enum lfsm_event event); - -extern void lfsm_irq_callback(uint8_t crc_ok, uint8_t crc_val); - -extern void lfsm_get_link_stats(struct lfsm_link_stats *stats); -extern enum lfsm_state lfsm_get_state(void); - -extern void lfsm_set_link_proto_v0(struct opahrs_msg_v0 *link_tx, - struct opahrs_msg_v0 *link_rx); -extern void lfsm_user_set_rx_v0(struct opahrs_msg_v0 *user_rx); -extern void lfsm_user_set_tx_v0(struct opahrs_msg_v0 *user_tx); - -extern void lfsm_set_link_proto_v1(struct opahrs_msg_v1 *link_tx, - struct opahrs_msg_v1 *link_rx); -extern void lfsm_user_set_rx_v1(struct opahrs_msg_v1 *user_rx); -extern void lfsm_user_set_tx_v1(struct opahrs_msg_v1 *user_tx); - -extern void lfsm_user_done(void); - -#endif /* AHRS_FSM_H */ diff --git a/flight/AHRS/pios_board.c b/flight/AHRS/pios_board.c deleted file mode 100644 index 2eb6ab668..000000000 --- a/flight/AHRS/pios_board.c +++ /dev/null @@ -1,118 +0,0 @@ -/** - ****************************************************************************** - * - * @file pios_board.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board specific static initializers for hardware for the AHRS board. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Pull in the board-specific static HW definitions. - * Including .c files is a bit ugly but this allows all of - * the HW definitions to be const and static to limit their - * scope. - * - * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE - */ -#include "board_hw_defs.c" - -#include - -#define PIOS_COM_AUX_TX_BUF_LEN 192 -static uint8_t pios_com_aux_tx_buffer[PIOS_COM_AUX_TX_BUF_LEN]; - -uint32_t pios_com_aux_id; -uint8_t adc_fifo_buf[sizeof(float) * 6 * 4] __attribute__ ((aligned(4))); // align to 32-bit to try and provide speed improvement - -/** - * PIOS_Board_Init() - * initializes all the core subsystems on this specific hardware - * called from System/openpilot.c - */ -void PIOS_Board_Init(void) { - /* Brings up System using CMSIS functions, enables the LEDs. */ - PIOS_SYS_Init(); - -#if defined(PIOS_INCLUDE_LED) - PIOS_LED_Init(&pios_led_cfg); -#endif /* PIOS_INCLUDE_LED */ - -#if defined(PIOS_LED_HEARTBEAT) - PIOS_LED_On(PIOS_LED_HEARTBEAT); -#endif /* PIOS_LED_HEARTBEAT */ - - /* Delay system */ - PIOS_DELAY_Init(); - - /* Communication system */ -#if !defined(PIOS_ENABLE_DEBUG_PINS) -#if defined(PIOS_INCLUDE_COM) - { - uint32_t pios_usart_aux_id; - if (PIOS_USART_Init(&pios_usart_aux_id, &pios_usart_aux_cfg)) { - PIOS_DEBUG_Assert(0); - } - if (PIOS_COM_Init(&pios_com_aux_id, &pios_usart_com_driver, pios_usart_aux_id, - NULL, 0, - pios_com_aux_tx_buffer, sizeof(pios_com_aux_tx_buffer))) { - PIOS_DEBUG_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ -#endif - - /* IAP System Setup */ - PIOS_IAP_Init(); - - /* ADC system */ - PIOS_ADC_Init(); - extern uint8_t adc_oversampling; - PIOS_ADC_Config(adc_oversampling); - extern void adc_callback(float *); - PIOS_ADC_SetCallback(adc_callback); - - /* ADC buffer */ - extern t_fifo_buffer adc_fifo_buffer; - fifoBuf_init(&adc_fifo_buffer, adc_fifo_buf, sizeof(adc_fifo_buf)); - - /* Setup the Accelerometer FS (Full-Scale) GPIO */ - PIOS_GPIO_Enable(0); - SET_ACCEL_6G; - -#if defined(PIOS_INCLUDE_HMC5843) && defined(PIOS_INCLUDE_I2C) - /* Magnetic sensor system */ - if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) { - PIOS_DEBUG_Assert(0); - } - PIOS_HMC5843_Init(); -#endif - -#if defined(PIOS_INCLUDE_SPI) -#include "ahrs_spi_comm.h" - AhrsInitComms(); - - /* Set up the SPI interface to the OP board */ - if (PIOS_SPI_Init(&pios_spi_op_id, &pios_spi_op_cfg)) { - PIOS_DEBUG_Assert(0); - } - - AhrsConnect(pios_spi_op_id); -#endif -} - diff --git a/flight/AHRS/test.c b/flight/AHRS/test.c deleted file mode 100644 index 6ad7707ec..000000000 --- a/flight/AHRS/test.c +++ /dev/null @@ -1,37 +0,0 @@ -#include "inc/insgps.h" -#include "stdio.h" -#include "math.h" - -extern struct NavStruct Nav; -extern float X[13]; - -int main() -{ - float gyro[3] = { 2.47, -0.25, 7.71 }, accel[3] = { - -1.02, 0.70, -10.11}, dT = 0.04, mags[3] = { - -50, -180, -376}; - float Pos[3] = { 0, 0, 0 }, Vel[3] = { - 0, 0, 0}, BaroAlt = 2.66, Speed = 4.4, Heading = 0; - float yaw; - int i, j; - - INSGPSInit(); - - for (i = 0; i < 10000000; i++) { - INSPrediction(gyro, accel, dT); - //MagCorrection(mags); - FullCorrection(mags, Pos, Vel, BaroAlt); - yaw = - atan2((float)2 * - (Nav.q[0] * Nav.q[3] + Nav.q[1] * Nav.q[2]), - (float)(1 - - 2 * (Nav.q[2] * Nav.q[2] + - Nav.q[3] * Nav.q[3]))) * 180 / M_PI; - - printf("%0.3f ", yaw); - for (j = 0; j < 13; j++) - printf("%f ", X[j]); - printf("\r\n"); - } - return 0; -} diff --git a/flight/Bootloaders/AHRS/ahrs_slave_test.c b/flight/Bootloaders/AHRS/ahrs_slave_test.c deleted file mode 100644 index d26957f1c..000000000 --- a/flight/Bootloaders/AHRS/ahrs_slave_test.c +++ /dev/null @@ -1,34 +0,0 @@ -#include "ahrs_bl.h" -#include "ahrs_spi_program.h" - -uint8_t buf[256]; - -bool StartProgramming(void) { - PIOS_COM_SendFormattedString(PIOS_COM_AUX, "Started programming\r\n"); - return (true); -} - -bool WriteData(uint32_t offset, uint8_t *buffer, uint32_t size) { - if (size > SPI_MAX_PROGRAM_DATA_SIZE) { - PIOS_COM_SendFormattedString(PIOS_COM_AUX, "oversize: %d\r\n", size); - return (false); - } - PIOS_COM_SendFormattedString(PIOS_COM_AUX, "Wrote %d bytes to %d\r\n", - size, offset); - memcpy(buf, buffer, size); - PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); - return (true); -} - -bool ReadData(uint32_t offset, uint8_t *buffer, uint32_t size) { - if (size > SPI_MAX_PROGRAM_DATA_SIZE) { - PIOS_COM_SendFormattedString(PIOS_COM_AUX, "oversize: %d\r\n", size); - return (false); - } - PIOS_COM_SendFormattedString(PIOS_COM_AUX, "Read %d bytes from %d\r\n", - size, offset); - memcpy(buffer, buf, size); - PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); - return (true); -} - diff --git a/flight/Bootloaders/AHRS/ahrs_spi_program.c b/flight/Bootloaders/AHRS/ahrs_spi_program.c deleted file mode 100644 index c29e9c609..000000000 --- a/flight/Bootloaders/AHRS/ahrs_spi_program.c +++ /dev/null @@ -1,65 +0,0 @@ -#include -#include "ahrs_spi_program.h" - -// Static CRC polynomial table -static uint32_t crcTable[256] = { 0x00000000, 0x77073096, 0xEE0E612C, - 0x990951BA, 0x076DC419, 0x706AF48F, 0xE963A535, 0x9E6495A3, 0x0EDB8832, - 0x79DCB8A4, 0xE0D5E91E, 0x97D2D988, 0x09B64C2B, 0x7EB17CBD, 0xE7B82D07, - 0x90BF1D91, 0x1DB71064, 0x6AB020F2, 0xF3B97148, 0x84BE41DE, 0x1ADAD47D, - 0x6DDDE4EB, 0xF4D4B551, 0x83D385C7, 0x136C9856, 0x646BA8C0, 0xFD62F97A, - 0x8A65C9EC, 0x14015C4F, 0x63066CD9, 0xFA0F3D63, 0x8D080DF5, 0x3B6E20C8, - 0x4C69105E, 0xD56041E4, 0xA2677172, 0x3C03E4D1, 0x4B04D447, 0xD20D85FD, - 0xA50AB56B, 0x35B5A8FA, 0x42B2986C, 0xDBBBC9D6, 0xACBCF940, 0x32D86CE3, - 0x45DF5C75, 0xDCD60DCF, 0xABD13D59, 0x26D930AC, 0x51DE003A, 0xC8D75180, - 0xBFD06116, 0x21B4F4B5, 0x56B3C423, 0xCFBA9599, 0xB8BDA50F, 0x2802B89E, - 0x5F058808, 0xC60CD9B2, 0xB10BE924, 0x2F6F7C87, 0x58684C11, 0xC1611DAB, - 0xB6662D3D, - - 0x76DC4190, 0x01DB7106, 0x98D220BC, 0xEFD5102A, 0x71B18589, 0x06B6B51F, - 0x9FBFE4A5, 0xE8B8D433, 0x7807C9A2, 0x0F00F934, 0x9609A88E, 0xE10E9818, - 0x7F6A0DBB, 0x086D3D2D, 0x91646C97, 0xE6635C01, 0x6B6B51F4, 0x1C6C6162, - 0x856530D8, 0xF262004E, 0x6C0695ED, 0x1B01A57B, 0x8208F4C1, 0xF50FC457, - 0x65B0D9C6, 0x12B7E950, 0x8BBEB8EA, 0xFCB9887C, 0x62DD1DDF, 0x15DA2D49, - 0x8CD37CF3, 0xFBD44C65, 0x4DB26158, 0x3AB551CE, 0xA3BC0074, 0xD4BB30E2, - 0x4ADFA541, 0x3DD895D7, 0xA4D1C46D, 0xD3D6F4FB, 0x4369E96A, 0x346ED9FC, - 0xAD678846, 0xDA60B8D0, 0x44042D73, 0x33031DE5, 0xAA0A4C5F, 0xDD0D7CC9, - 0x5005713C, 0x270241AA, 0xBE0B1010, 0xC90C2086, 0x5768B525, 0x206F85B3, - 0xB966D409, 0xCE61E49F, 0x5EDEF90E, 0x29D9C998, 0xB0D09822, 0xC7D7A8B4, - 0x59B33D17, 0x2EB40D81, 0xB7BD5C3B, 0xC0BA6CAD, - - 0xEDB88320, 0x9ABFB3B6, 0x03B6E20C, 0x74B1D29A, 0xEAD54739, 0x9DD277AF, - 0x04DB2615, 0x73DC1683, 0xE3630B12, 0x94643B84, 0x0D6D6A3E, 0x7A6A5AA8, - 0xE40ECF0B, 0x9309FF9D, 0x0A00AE27, 0x7D079EB1, 0xF00F9344, 0x8708A3D2, - 0x1E01F268, 0x6906C2FE, 0xF762575D, 0x806567CB, 0x196C3671, 0x6E6B06E7, - 0xFED41B76, 0x89D32BE0, 0x10DA7A5A, 0x67DD4ACC, 0xF9B9DF6F, 0x8EBEEFF9, - 0x17B7BE43, 0x60B08ED5, 0xD6D6A3E8, 0xA1D1937E, 0x38D8C2C4, 0x4FDFF252, - 0xD1BB67F1, 0xA6BC5767, 0x3FB506DD, 0x48B2364B, 0xD80D2BDA, 0xAF0A1B4C, - 0x36034AF6, 0x41047A60, 0xDF60EFC3, 0xA867DF55, 0x316E8EEF, 0x4669BE79, - 0xCB61B38C, 0xBC66831A, 0x256FD2A0, 0x5268E236, 0xCC0C7795, 0xBB0B4703, - 0x220216B9, 0x5505262F, 0xC5BA3BBE, 0xB2BD0B28, 0x2BB45A92, 0x5CB36A04, - 0xC2D7FFA7, 0xB5D0CF31, 0x2CD99E8B, 0x5BDEAE1D, - - 0x9B64C2B0, 0xEC63F226, 0x756AA39C, 0x026D930A, 0x9C0906A9, 0xEB0E363F, - 0x72076785, 0x05005713, 0x95BF4A82, 0xE2B87A14, 0x7BB12BAE, 0x0CB61B38, - 0x92D28E9B, 0xE5D5BE0D, 0x7CDCEFB7, 0x0BDBDF21, 0x86D3D2D4, 0xF1D4E242, - 0x68DDB3F8, 0x1FDA836E, 0x81BE16CD, 0xF6B9265B, 0x6FB077E1, 0x18B74777, - 0x88085AE6, 0xFF0F6A70, 0x66063BCA, 0x11010B5C, 0x8F659EFF, 0xF862AE69, - 0x616BFFD3, 0x166CCF45, 0xA00AE278, 0xD70DD2EE, 0x4E048354, 0x3903B3C2, - 0xA7672661, 0xD06016F7, 0x4969474D, 0x3E6E77DB, 0xAED16A4A, 0xD9D65ADC, - 0x40DF0B66, 0x37D83BF0, 0xA9BCAE53, 0xDEBB9EC5, 0x47B2CF7F, 0x30B5FFE9, - 0xBDBDF21C, 0xCABAC28A, 0x53B39330, 0x24B4A3A6, 0xBAD03605, 0xCDD70693, - 0x54DE5729, 0x23D967BF, 0xB3667A2E, 0xC4614AB8, 0x5D681B02, 0x2A6F2B94, - 0xB40BBE37, 0xC30C8EA1, 0x5A05DF1B, 0x2D02EF8D, }; - -/**generate CRC32 from a program packet - this is slightly overkill but we want to be sure - */ -uint32_t GenerateCRC(AhrsProgramPacket * packet) { - uint8_t * ptr = (uint8_t *) packet; - int size = ((int) &packet->crc) - (int) packet; - uint32_t crc = 0xFFFFFFFF; - for (int ct = 0; ct < size; ct++) { - crc = ((crc) >> 8) ^ crcTable[(*ptr++) ^ ((crc) & 0x000000FF)]; - } - return (~crc); -} diff --git a/flight/Bootloaders/AHRS/ahrs_spi_program_master.c b/flight/Bootloaders/AHRS/ahrs_spi_program_master.c deleted file mode 100644 index 8227771c0..000000000 --- a/flight/Bootloaders/AHRS/ahrs_spi_program_master.c +++ /dev/null @@ -1,131 +0,0 @@ -/** - ****************************************************************************** - * - * @file ahrs_spi_program_master.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief AHRS programming over SPI link - master(OpenPilot) end. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "ahrs_spi_program_master.h" -#include "ahrs_spi_program.h" -#include "pios_spi.h" - -PROGERR TransferPacket(uint32_t spi_id, AhrsProgramPacket *txBuf, - AhrsProgramPacket *rxBuf); - -#define MAX_CONNECT_TRIES 500 //half a second -bool AhrsProgramConnect(uint32_t spi_id) { - AhrsProgramPacket rxBuf; - AhrsProgramPacket txBuf; - memset(&rxBuf, 0, sizeof(AhrsProgramPacket)); - memcpy(&txBuf, SPI_PROGRAM_REQUEST, SPI_PROGRAM_REQUEST_LENGTH); - for (int ct = 0; ct < MAX_CONNECT_TRIES; ct++) { - PIOS_SPI_RC_PinSet(spi_id, 0); - uint32_t res = PIOS_SPI_TransferBlock(spi_id, (uint8_t *) &txBuf, - (uint8_t *) &rxBuf, SPI_PROGRAM_REQUEST_LENGTH + 1, NULL); - PIOS_SPI_RC_PinSet(spi_id, 1); - if (res == 0 && memcmp(&rxBuf, SPI_PROGRAM_ACK, - SPI_PROGRAM_REQUEST_LENGTH) == 0) { - return (true); - } - - vTaskDelay(1 / portTICK_RATE_MS); - } - return (false); -} - -PROGERR AhrsProgramWrite(uint32_t spi_id, uint32_t address, void * data, - uint32_t size) { - AhrsProgramPacket rxBuf; - AhrsProgramPacket txBuf; - memset(&rxBuf, 0, sizeof(AhrsProgramPacket)); - memcpy(txBuf.data, data, size); - txBuf.size = size; - txBuf.type = PROGRAM_WRITE; - txBuf.address = address; - PROGERR ret = TransferPacket(spi_id, &txBuf, &rxBuf); - if (ret != PROGRAM_ERR_OK) { - return (ret); - } - return (PROGRAM_ERR_OK); -} - -PROGERR AhrsProgramRead(uint32_t spi_id, uint32_t address, void * data, - uint32_t size) { - AhrsProgramPacket rxBuf; - AhrsProgramPacket txBuf; - memset(&rxBuf, 0, sizeof(AhrsProgramPacket)); - txBuf.size = size; - txBuf.type = PROGRAM_READ; - txBuf.address = address; - PROGERR ret = TransferPacket(spi_id, &txBuf, &rxBuf); - if (ret != PROGRAM_ERR_OK) { - return (ret); - } - memcpy(data, rxBuf.data, size); - return (PROGRAM_ERR_OK); -} - -PROGERR AhrsProgramReboot(uint32_t spi_id) { - AhrsProgramPacket rxBuf; - AhrsProgramPacket txBuf; - memset(&rxBuf, 0, sizeof(AhrsProgramPacket)); - txBuf.type = PROGRAM_REBOOT; - memcpy(txBuf.data, REBOOT_CONFIRMATION, REBOOT_CONFIRMATION_LENGTH); - PROGERR ret = TransferPacket(spi_id, &txBuf, &rxBuf); - //If AHRS has rebooted we will get comms errors - if (ret == PROGRAM_ERR_LINK) { - return (PROGRAM_ERR_OK); - } - return (PROGRAM_ERR_FUNCTION); -} - -PROGERR TransferPacket(uint32_t spi_id, AhrsProgramPacket *txBuf, - AhrsProgramPacket *rxBuf) { - static uint32_t pktId = 0; - pktId++; - txBuf->packetId = pktId; - txBuf->crc = GenerateCRC(txBuf); - int ct = 0; - for (; ct < MAX_CONNECT_TRIES; ct++) { - PIOS_SPI_RC_PinSet(spi_id, 0); - uint32_t res = PIOS_SPI_TransferBlock(spi_id, (uint8_t *) txBuf, - (uint8_t *) rxBuf, sizeof(AhrsProgramPacket), NULL); - PIOS_SPI_RC_PinSet(spi_id, 1); - if (res == 0) { - if (rxBuf->type != PROGRAM_NULL && rxBuf->crc == GenerateCRC(rxBuf) - && rxBuf->packetId == pktId) { - break; - } - } - - vTaskDelay(1 / portTICK_RATE_MS); - } - if (ct == MAX_CONNECT_TRIES) { - return (PROGRAM_ERR_LINK); - } - if (rxBuf->type != PROGRAM_ACK) { - return (PROGRAM_ERR_FUNCTION); - } - return (PROGRAM_ERR_OK); -} - diff --git a/flight/Bootloaders/AHRS/ahrs_spi_program_slave.c b/flight/Bootloaders/AHRS/ahrs_spi_program_slave.c deleted file mode 100644 index 8fc3de482..000000000 --- a/flight/Bootloaders/AHRS/ahrs_spi_program_slave.c +++ /dev/null @@ -1,137 +0,0 @@ -/** - ****************************************************************************** - * - * @file ahrs_spi_program_slave.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief AHRS programming over SPI link - slave(AHRS) end. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include -#include - -#include "pios_opahrs_proto.h" -#include "pios_spi.h" -#include "STM32103CB_AHRS.h" - -#include "ahrs_bl.h" -#include "ahrs_spi_program_slave.h" -#include "ahrs_spi_program.h" - -static AhrsProgramPacket txBuf; -static AhrsProgramPacket rxBuf; -static bool done = false; - -static void ProcessPacket(); - -#define WAIT_IF_RECEIVING() while(!(GPIOB->IDR & GPIO_Pin_12)){}; //NSS must be high -//Number of crc failures to allow before giving up -#define PROGRAM_PACKET_TRIES 4 - -void AhrsProgramReceive(uint32_t spi_id) { - done = false; - memset(&txBuf, 0, sizeof(AhrsProgramPacket)); - //wait for a program request - int count = PROGRAM_PACKET_TRIES; - while (1) { - WAIT_IF_RECEIVING(); - while ((PIOS_SPI_Busy(spi_id) != 0)) { - }; - memset(&rxBuf, 'a', sizeof(AhrsProgramPacket)); - int32_t res = PIOS_SPI_TransferBlock(spi_id, NULL, (uint8_t*) &rxBuf, - SPI_PROGRAM_REQUEST_LENGTH + 1, NULL); - - if (res == 0 && memcmp(&rxBuf, SPI_PROGRAM_REQUEST, - SPI_PROGRAM_REQUEST_LENGTH) == 0) { - break; - } - if (count-- == 0) { - return; - } - } - - if (!StartProgramming()) { - //Couldn't erase FLASH. Nothing we can do. - return; - } - - //send ack - memcpy(&txBuf, SPI_PROGRAM_ACK, SPI_PROGRAM_REQUEST_LENGTH); - WAIT_IF_RECEIVING(); - while (0 != PIOS_SPI_TransferBlock(spi_id, (uint8_t*) &txBuf, NULL, - SPI_PROGRAM_REQUEST_LENGTH + 1, NULL)) { - }; - - txBuf.type = PROGRAM_NULL; - - while (!done) { - WAIT_IF_RECEIVING(); - if (0 == PIOS_SPI_TransferBlock(spi_id, (uint8_t*) &txBuf, - (uint8_t*) &rxBuf, sizeof(AhrsProgramPacket), NULL)) { - - uint32_t crc = GenerateCRC(&rxBuf); - if (crc != rxBuf.crc || txBuf.packetId == rxBuf.packetId) { - continue; - } - ProcessPacket(); - txBuf.packetId = rxBuf.packetId; - txBuf.crc = GenerateCRC(&txBuf); - } - } -} - -void ProcessPacket() { - switch (rxBuf.type) { - case PROGRAM_NULL: - txBuf.type = PROGRAM_NULL; - break; - - case PROGRAM_WRITE: - if (WriteData(rxBuf.address, rxBuf.data, rxBuf.size)) { - txBuf.type = PROGRAM_ACK; - txBuf.size = rxBuf.size; - } else { - txBuf.type = PROGRAM_ERR; - } - break; - - case PROGRAM_READ: - if (ReadData(rxBuf.address, txBuf.data, rxBuf.size)) { - txBuf.type = PROGRAM_ACK; - txBuf.size = rxBuf.size; - } else { - txBuf.type = PROGRAM_ERR; - } - break; - - case PROGRAM_REBOOT: - if (0 == memcmp(rxBuf.data, REBOOT_CONFIRMATION, - REBOOT_CONFIRMATION_LENGTH)) { - done = true; - txBuf.type = PROGRAM_ACK; - } else { - txBuf.type = PROGRAM_ERR; - } - break; - - default: - txBuf.type = PROGRAM_ERR; - } -} diff --git a/flight/Bootloaders/AHRS/bl_fsm.c b/flight/Bootloaders/AHRS/bl_fsm.c deleted file mode 100644 index 10e26a46e..000000000 --- a/flight/Bootloaders/AHRS/bl_fsm.c +++ /dev/null @@ -1,591 +0,0 @@ -#include /* uint*_t */ -#include /* NULL */ - -#include "bl_fsm.h" - -#include "pios_opahrs_proto.h" - -#include "pios.h" - -struct lfsm_context { - enum lfsm_state curr_state; - enum opahrs_msg_link_state link_state; - enum opahrs_msg_type user_payload_type; - uint32_t user_payload_len; - - uint32_t errors; - - uint8_t * rx; - uint8_t * tx; - - uint8_t * link_rx; - uint8_t * link_tx; - - uint8_t * user_rx; - uint8_t * user_tx; - - struct lfsm_link_stats stats; -}; - -static struct lfsm_context context = { 0 }; - -static void lfsm_update_link_tx(struct lfsm_context * context); -static void lfsm_init_rx(struct lfsm_context * context); - -static uint32_t PIOS_SPI_OP; -void lfsm_attach(uint32_t spi_id) { - PIOS_SPI_OP = spi_id; -} - -/* - * - * Link Finite State Machine - * - */ - -struct lfsm_transition { - void (*entry_fn)(struct lfsm_context * context); - enum lfsm_state next_state[LFSM_EVENT_NUM_EVENTS]; -}; - -static void go_faulted(struct lfsm_context * context); -static void go_stopped(struct lfsm_context * context); -static void go_stopping(struct lfsm_context * context); -static void go_inactive(struct lfsm_context * context); -static void go_user_busy(struct lfsm_context * context); -static void go_user_busy_rx_pending(struct lfsm_context * context); -static void go_user_busy_tx_pending(struct lfsm_context * context); -static void go_user_busy_rxtx_pending(struct lfsm_context * context); -static void go_user_rx_pending(struct lfsm_context * context); -static void go_user_tx_pending(struct lfsm_context * context); -static void go_user_rxtx_pending(struct lfsm_context * context); -static void go_user_rx_active(struct lfsm_context * context); -static void go_user_tx_active(struct lfsm_context * context); -static void go_user_rxtx_active(struct lfsm_context * context); - -const static struct lfsm_transition lfsm_transitions[LFSM_STATE_NUM_STATES] = { - [LFSM_STATE_FAULTED] = { - .entry_fn = go_faulted, - }, [LFSM_STATE_STOPPED] = { - .entry_fn = go_stopped, - .next_state = { - [LFSM_EVENT_INIT_LINK] = LFSM_STATE_INACTIVE, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_STOPPED, - }, - }, [LFSM_STATE_STOPPING] = { - .entry_fn = go_stopping, - .next_state = { - [LFSM_EVENT_RX_LINK] = LFSM_STATE_STOPPED, - [LFSM_EVENT_RX_USER] = LFSM_STATE_STOPPED, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_STOPPED, - }, - }, [LFSM_STATE_INACTIVE] = { - .entry_fn = go_inactive, - .next_state = { - [LFSM_EVENT_STOP] = LFSM_STATE_STOPPING, - [LFSM_EVENT_USER_SET_RX] = LFSM_STATE_USER_BUSY_RX_PENDING, - [LFSM_EVENT_USER_SET_TX] = LFSM_STATE_USER_BUSY_TX_PENDING, - [LFSM_EVENT_RX_LINK] = LFSM_STATE_INACTIVE, - [LFSM_EVENT_RX_USER] = LFSM_STATE_INACTIVE, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_INACTIVE, - }, - }, [LFSM_STATE_USER_BUSY] = { - .entry_fn = go_user_busy, - .next_state = { - [LFSM_EVENT_STOP] = LFSM_STATE_STOPPING, - [LFSM_EVENT_USER_SET_RX] = LFSM_STATE_USER_BUSY_RX_PENDING, - [LFSM_EVENT_USER_SET_TX] = LFSM_STATE_USER_BUSY_TX_PENDING, - [LFSM_EVENT_USER_DONE] = LFSM_STATE_INACTIVE, - [LFSM_EVENT_RX_LINK] = LFSM_STATE_USER_BUSY, - [LFSM_EVENT_RX_USER] = LFSM_STATE_USER_BUSY, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_USER_BUSY, - }, - }, [LFSM_STATE_USER_BUSY_RX_PENDING] = { - .entry_fn = go_user_busy_rx_pending, - .next_state = { - [LFSM_EVENT_USER_SET_TX] = LFSM_STATE_USER_BUSY_RXTX_PENDING, - [LFSM_EVENT_USER_DONE] = LFSM_STATE_USER_RX_PENDING, - [LFSM_EVENT_RX_LINK] = LFSM_STATE_USER_BUSY_RX_PENDING, - [LFSM_EVENT_RX_USER] = LFSM_STATE_USER_BUSY_RX_PENDING, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_USER_BUSY_RX_PENDING, - }, - }, [LFSM_STATE_USER_BUSY_TX_PENDING] = { - .entry_fn = go_user_busy_tx_pending, - .next_state = { - [LFSM_EVENT_USER_SET_RX] = LFSM_STATE_USER_BUSY_RXTX_PENDING, - [LFSM_EVENT_USER_DONE] = LFSM_STATE_USER_TX_PENDING, - [LFSM_EVENT_RX_LINK] = LFSM_STATE_USER_BUSY_TX_PENDING, - [LFSM_EVENT_RX_USER] = LFSM_STATE_USER_BUSY_TX_PENDING, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_USER_BUSY_TX_PENDING, - }, - }, [LFSM_STATE_USER_BUSY_RXTX_PENDING] = { - .entry_fn = go_user_busy_rxtx_pending, - .next_state = { - [LFSM_EVENT_USER_DONE] = LFSM_STATE_USER_RXTX_PENDING, - [LFSM_EVENT_RX_LINK] = LFSM_STATE_USER_BUSY_RXTX_PENDING, - [LFSM_EVENT_RX_USER] = LFSM_STATE_USER_BUSY_RXTX_PENDING, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_USER_BUSY_RXTX_PENDING, - }, - }, [LFSM_STATE_USER_RX_PENDING] = { - .entry_fn = go_user_rx_pending, - .next_state = { - [LFSM_EVENT_RX_LINK] = LFSM_STATE_USER_RX_ACTIVE, - [LFSM_EVENT_RX_USER] = LFSM_STATE_USER_RX_ACTIVE, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_USER_RX_ACTIVE, - }, - }, [LFSM_STATE_USER_TX_PENDING] = { - .entry_fn = go_user_tx_pending, - .next_state = { - [LFSM_EVENT_RX_LINK] = LFSM_STATE_USER_TX_ACTIVE, - [LFSM_EVENT_RX_USER] = LFSM_STATE_USER_TX_ACTIVE, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_USER_TX_ACTIVE, - }, - }, [LFSM_STATE_USER_RXTX_PENDING] = { - .entry_fn = go_user_rxtx_pending, - .next_state = { - [LFSM_EVENT_RX_LINK] = LFSM_STATE_USER_RXTX_ACTIVE, - [LFSM_EVENT_RX_USER] = LFSM_STATE_USER_RXTX_ACTIVE, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_USER_RXTX_ACTIVE, - }, - }, [LFSM_STATE_USER_RX_ACTIVE] = { - .entry_fn = go_user_rx_active, - .next_state = { - [LFSM_EVENT_RX_LINK] = LFSM_STATE_USER_RX_ACTIVE, - [LFSM_EVENT_RX_USER] = LFSM_STATE_USER_BUSY, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_USER_RX_ACTIVE, - }, - }, [LFSM_STATE_USER_TX_ACTIVE] = { - .entry_fn = go_user_tx_active, - .next_state = { - [LFSM_EVENT_RX_LINK] = LFSM_STATE_INACTIVE, - [LFSM_EVENT_RX_USER] = LFSM_STATE_INACTIVE, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_INACTIVE, - }, - }, [LFSM_STATE_USER_RXTX_ACTIVE] = { - .entry_fn = go_user_rxtx_active, - .next_state = { - [LFSM_EVENT_RX_LINK] = LFSM_STATE_USER_RX_ACTIVE, - [LFSM_EVENT_RX_USER] = LFSM_STATE_USER_BUSY, - [LFSM_EVENT_RX_UNKNOWN] = LFSM_STATE_USER_RX_ACTIVE, - }, - }, }; - -/* - * FSM State Entry Functions - */ - -static void go_faulted(struct lfsm_context * context) { - PIOS_DEBUG_Assert(0); -} - -static void go_stopped(struct lfsm_context * context) { -#if 0 - PIOS_SPI_Stop(PIOS_SPI_OP); -#endif -} - -static void go_stopping(struct lfsm_context * context) { - context->link_tx = NULL; - context->tx = NULL; -} - -static void go_inactive(struct lfsm_context * context) { - context->link_state = OPAHRS_MSG_LINK_STATE_INACTIVE; - lfsm_update_link_tx(context); - - context->user_rx = NULL; - context->user_tx = NULL; - - context->rx = context->link_rx; - context->tx = context->link_tx; - - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -static void go_user_busy(struct lfsm_context * context) { - /* Sanity checks */ - PIOS_DEBUG_Assert(context->user_rx); - - context->user_rx = NULL; - context->user_tx = NULL; - - context->link_state = OPAHRS_MSG_LINK_STATE_BUSY; - lfsm_update_link_tx(context); - - context->rx = context->link_rx; - context->tx = context->link_tx; - - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -static void go_user_busy_rx_pending(struct lfsm_context * context) { - /* Sanity checks */ - PIOS_DEBUG_Assert(context->user_rx); - - context->link_state = OPAHRS_MSG_LINK_STATE_BUSY; - lfsm_update_link_tx(context); - - context->rx = context->link_rx; - context->tx = context->link_tx; - - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -static void go_user_busy_tx_pending(struct lfsm_context * context) { - /* Sanity checks */ - PIOS_DEBUG_Assert(context->user_tx); - - context->link_state = OPAHRS_MSG_LINK_STATE_BUSY; - lfsm_update_link_tx(context); - - context->rx = context->link_rx; - context->tx = context->link_tx; - - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -static void go_user_busy_rxtx_pending(struct lfsm_context * context) { - /* Sanity checks */ - PIOS_DEBUG_Assert(context->user_rx); PIOS_DEBUG_Assert(context->user_tx); - - context->link_state = OPAHRS_MSG_LINK_STATE_BUSY; - lfsm_update_link_tx(context); - - context->rx = context->link_rx; - context->tx = context->link_tx; - - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -static void go_user_rx_pending(struct lfsm_context * context) { - /* Sanity checks */ - PIOS_DEBUG_Assert(context->user_rx); - - context->link_state = OPAHRS_MSG_LINK_STATE_BUSY; - lfsm_update_link_tx(context); - - context->rx = context->link_rx; - context->tx = context->link_tx; - - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -static void go_user_tx_pending(struct lfsm_context * context) { - /* Sanity checks */ - PIOS_DEBUG_Assert(context->user_tx); - - context->link_state = OPAHRS_MSG_LINK_STATE_BUSY; - lfsm_update_link_tx(context); - - context->rx = context->link_rx; - context->tx = context->link_tx; - - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -static void go_user_rxtx_pending(struct lfsm_context * context) { - /* Sanity checks */ - PIOS_DEBUG_Assert(context->user_rx); PIOS_DEBUG_Assert(context->user_tx); - - context->link_state = OPAHRS_MSG_LINK_STATE_BUSY; - lfsm_update_link_tx(context); - - context->rx = context->link_rx; - context->tx = context->link_tx; - - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -static void go_user_rx_active(struct lfsm_context * context) { - /* Sanity checks */ - PIOS_DEBUG_Assert(context->user_rx); - - context->rx = context->user_rx; - context->tx = context->link_tx; - context->link_state = OPAHRS_MSG_LINK_STATE_READY; - - lfsm_update_link_tx(context); - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -static void go_user_tx_active(struct lfsm_context * context) { - /* Sanity checks */ - PIOS_DEBUG_Assert(context->user_tx); - - context->link_state = OPAHRS_MSG_LINK_STATE_BUSY; - context->rx = context->link_rx; - context->tx = context->user_tx; - - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -static void go_user_rxtx_active(struct lfsm_context * context) { - /* Sanity checks */ - PIOS_DEBUG_Assert(context->user_rx); PIOS_DEBUG_Assert(context->user_tx); - - context->link_state = OPAHRS_MSG_LINK_STATE_READY; - context->rx = context->user_rx; - context->tx = context->user_tx; - - lfsm_init_rx(context); - PIOS_SPI_TransferBlock(PIOS_SPI_OP, context->tx, context->rx, - context->user_payload_len, lfsm_irq_callback); -} - -/* - * - * Misc Helper Functions - * - */ - -static void lfsm_update_link_tx_v0(struct opahrs_msg_v0 * msg, - enum opahrs_msg_link_state state, uint16_t errors) { - opahrs_msg_v0_init_link_tx(msg, OPAHRS_MSG_LINK_TAG_NOP); - - msg->payload.link.state = state; - msg->payload.link.errors = errors; -} - -static void lfsm_update_link_tx_v1(struct opahrs_msg_v1 * msg, - enum opahrs_msg_link_state state, uint16_t errors) { - opahrs_msg_v1_init_link_tx(msg, OPAHRS_MSG_LINK_TAG_NOP); - - msg->payload.link.state = state; - msg->payload.link.errors = errors; -} - -static void lfsm_update_link_tx(struct lfsm_context * context) { - PIOS_DEBUG_Assert(context->link_tx); - - switch (context->user_payload_type) { - case OPAHRS_MSG_TYPE_USER_V0: - lfsm_update_link_tx_v0((struct opahrs_msg_v0 *) context->link_tx, - context->link_state, context->errors); - break; - case OPAHRS_MSG_TYPE_USER_V1: - lfsm_update_link_tx_v1((struct opahrs_msg_v1 *) context->link_tx, - context->link_state, context->errors); - break; - case OPAHRS_MSG_TYPE_LINK: - PIOS_DEBUG_Assert(0); - } -} - -static void lfsm_init_rx(struct lfsm_context * context) { - PIOS_DEBUG_Assert(context->rx); - - switch (context->user_payload_type) { - case OPAHRS_MSG_TYPE_USER_V0: - opahrs_msg_v0_init_rx((struct opahrs_msg_v0 *) context->rx); - break; - case OPAHRS_MSG_TYPE_USER_V1: - opahrs_msg_v1_init_rx((struct opahrs_msg_v1 *) context->rx); - break; - case OPAHRS_MSG_TYPE_LINK: - PIOS_DEBUG_Assert(0); - } -} - -/* - * - * External API - * - */ - -void lfsm_inject_event(enum lfsm_event event) { - PIOS_IRQ_Disable(); - - /* - * Move to the next state - * - * This is done prior to calling the new state's entry function to - * guarantee that the entry function never depends on the previous - * state. This way, it cannot ever know what the previous state was. - */ - context.curr_state = lfsm_transitions[context.curr_state].next_state[event]; - - /* Call the entry function (if any) for the next state. */ - if (lfsm_transitions[context.curr_state].entry_fn) { - lfsm_transitions[context.curr_state].entry_fn(&context); - } - PIOS_IRQ_Enable(); -} - -void lfsm_init(void) { - context.curr_state = LFSM_STATE_STOPPED; - go_stopped(&context); -} - -void lfsm_set_link_proto_v0(struct opahrs_msg_v0 * link_tx, - struct opahrs_msg_v0 * link_rx) { - PIOS_DEBUG_Assert(link_tx); - - context.link_tx = (uint8_t *) link_tx; - context.link_rx = (uint8_t *) link_rx; - context.user_payload_type = OPAHRS_MSG_TYPE_USER_V0; - context.user_payload_len = sizeof(*link_tx); - - lfsm_update_link_tx_v0(link_tx, context.link_state, context.errors); - - lfsm_inject_event(LFSM_EVENT_INIT_LINK); -} - -void lfsm_set_link_proto_v1(struct opahrs_msg_v1 * link_tx, - struct opahrs_msg_v1 * link_rx) { - PIOS_DEBUG_Assert(link_tx); - - context.link_tx = (uint8_t *) link_tx; - context.link_rx = (uint8_t *) link_rx; - context.user_payload_type = OPAHRS_MSG_TYPE_USER_V1; - context.user_payload_len = sizeof(*link_tx); - - lfsm_update_link_tx_v1(link_tx, context.link_state, context.errors); - - lfsm_inject_event(LFSM_EVENT_INIT_LINK); -} - -void lfsm_user_set_tx_v0(struct opahrs_msg_v0 * user_tx) { - PIOS_DEBUG_Assert(user_tx); - - PIOS_DEBUG_Assert(context.user_payload_type == OPAHRS_MSG_TYPE_USER_V0); - context.user_tx = (uint8_t *) user_tx; - - lfsm_inject_event(LFSM_EVENT_USER_SET_TX); -} - -void lfsm_user_set_rx_v0(struct opahrs_msg_v0 * user_rx) { - PIOS_DEBUG_Assert(user_rx); PIOS_DEBUG_Assert(context.user_payload_type == OPAHRS_MSG_TYPE_USER_V0); - - context.user_rx = (uint8_t *) user_rx; - - lfsm_inject_event(LFSM_EVENT_USER_SET_RX); -} - -void lfsm_user_set_tx_v1(struct opahrs_msg_v1 * user_tx) { - PIOS_DEBUG_Assert(user_tx); PIOS_DEBUG_Assert(context.user_payload_type == OPAHRS_MSG_TYPE_USER_V1); - - context.user_tx = (uint8_t *) user_tx; - - lfsm_inject_event(LFSM_EVENT_USER_SET_TX); -} - -void lfsm_user_set_rx_v1(struct opahrs_msg_v1 * user_rx) { - PIOS_DEBUG_Assert(user_rx); PIOS_DEBUG_Assert(context.user_payload_type == OPAHRS_MSG_TYPE_USER_V1); - - context.user_rx = (uint8_t *) user_rx; - - lfsm_inject_event(LFSM_EVENT_USER_SET_RX); -} - -void lfsm_user_done(void) { - lfsm_inject_event(LFSM_EVENT_USER_DONE); -} - -void lfsm_stop(void) { - lfsm_inject_event(LFSM_EVENT_STOP); -} - -void lfsm_get_link_stats(struct lfsm_link_stats * stats) { - PIOS_DEBUG_Assert(stats); - - *stats = context.stats; -} - -enum lfsm_state lfsm_get_state(void) { - return context.curr_state; -} - -/* - * - * ISR Callback - * - */ - -void lfsm_irq_callback(uint8_t crc_ok, uint8_t crc_val) { - if (!crc_ok) { - context.stats.rx_badcrc++; - lfsm_inject_event(LFSM_EVENT_RX_UNKNOWN); - return; - } - - if (!context.rx) { - /* No way to know what we just received, assume invalid */ - lfsm_inject_event(LFSM_EVENT_RX_UNKNOWN); - return; - } - - /* Recover the head and tail pointers from the message */ - struct opahrs_msg_link_head * head = 0; - struct opahrs_msg_link_tail * tail = 0; - - switch (context.user_payload_type) { - case OPAHRS_MSG_TYPE_USER_V0: - head = &((struct opahrs_msg_v0 *) context.rx)->head; - tail = &((struct opahrs_msg_v0 *) context.rx)->tail; - break; - case OPAHRS_MSG_TYPE_USER_V1: - head = &((struct opahrs_msg_v1 *) context.rx)->head; - tail = &((struct opahrs_msg_v1 *) context.rx)->tail; - break; - case OPAHRS_MSG_TYPE_LINK: - /* Should never be rx'ing before the link protocol version is known */ - PIOS_DEBUG_Assert(0); - break; - } - - /* Check for bad magic */ - if ((head->magic != OPAHRS_MSG_MAGIC_HEAD) || (tail->magic - != OPAHRS_MSG_MAGIC_TAIL)) { - if (head->magic != OPAHRS_MSG_MAGIC_HEAD) { - context.stats.rx_badmagic_head++; - } - if (tail->magic != OPAHRS_MSG_MAGIC_TAIL) { - context.stats.rx_badmagic_tail++; - } - lfsm_inject_event(LFSM_EVENT_RX_UNKNOWN); - return; - } - - /* Good magic, find out what type of payload we've got */ - switch (head->type) { - case OPAHRS_MSG_TYPE_LINK: - context.stats.rx_link++; - lfsm_inject_event(LFSM_EVENT_RX_LINK); - break; - case OPAHRS_MSG_TYPE_USER_V0: - case OPAHRS_MSG_TYPE_USER_V1: - if (head->type == context.user_payload_type) { - context.stats.rx_user++; - lfsm_inject_event(LFSM_EVENT_RX_USER); - } else { - /* Mismatched user payload type */ - context.stats.rx_badver++; - lfsm_inject_event(LFSM_EVENT_RX_UNKNOWN); - } - break; - default: - /* Unidentifiable payload type */ - context.stats.rx_badtype++; - lfsm_inject_event(LFSM_EVENT_RX_UNKNOWN); - } -} diff --git a/flight/Bootloaders/AHRS/inc/ahrs_spi_program.h b/flight/Bootloaders/AHRS/inc/ahrs_spi_program.h deleted file mode 100644 index 024d1b061..000000000 --- a/flight/Bootloaders/AHRS/inc/ahrs_spi_program.h +++ /dev/null @@ -1,65 +0,0 @@ -#ifndef AHRS_SPI_PROGRAM_H -#define AHRS_SPI_PROGRAM_H - -/* Special packets to enter programming mode. - Note: these must both be SPI_PROGRAM_REQUEST_LENGTH long. - Pad with spaces if needed. - */ -#define SPI_PROGRAM_REQUEST "AHRS START PROGRAMMING " -#define SPI_PROGRAM_ACK "AHRS PROGRAMMING STARTED" -#define SPI_PROGRAM_REQUEST_LENGTH 24 - -/**Proposed programming protocol: - In the master: - 1) Send a AhrsProgramPacket containing the relevant data. - Note crc is a CRC32 as the CRC8 used in hardware can be fooled. - 2) Keep sending PROGRAM_NULL packets and wait for an ack. - Time out if we waited too long. - 3) Compare ack packet with transmitted packet. The data - should be the bitwise inverse of the data transmitted. - packetId should correspond to the transmitted packet. - 4) repeat for next packet until finished - 5) Repeat using verify packets - Returned data should be exactly as read from memory - - In the slave: - 1) Wait for an AhrsProgramPacket - 2) Check CRC then write to memory - 3) Bitwise invert data and add it to the return packet - 4) Copy packetId from received packet - 5) Transmit packet. - 6) repeat until we receive a read packet - 7) read memory as requested until we receive a reboot packet - Reboot packets had better have some sort of magic number in the data, - just to be absolutely sure - - */ - -typedef enum { - PROGRAM_NULL, - PROGRAM_WRITE, - PROGRAM_READ, - PROGRAM_ACK, - PROGRAM_REBOOT, - PROGRAM_ERR -} ProgramType; -#define SPI_MAX_PROGRAM_DATA_SIZE (14 * 4) //USB comms uses 14x 32 bit words -#define REBOOT_CONFIRMATION "AHRS REBOOT" -#define REBOOT_CONFIRMATION_LENGTH 11 - -/** Proposed program packet defintion - */ - -typedef struct { - ProgramType type; - uint32_t packetId; //Transmission packet ID - uint32_t address; //base address to place data - uint32_t size; //Size of data (0 to SPI_MAX_PROGRAM_DATA_SIZE) - uint8_t data[SPI_MAX_PROGRAM_DATA_SIZE]; - uint32_t crc; //CRC32 - hardware CRC8 can be fooled - uint8_t dummy; //for some reason comms trashes the last byte sent -} AhrsProgramPacket; - -uint32_t GenerateCRC(AhrsProgramPacket * packet); - -#endif diff --git a/flight/Bootloaders/AHRS/inc/ahrs_spi_program_master.h b/flight/Bootloaders/AHRS/inc/ahrs_spi_program_master.h deleted file mode 100644 index 87a3f9ac7..000000000 --- a/flight/Bootloaders/AHRS/inc/ahrs_spi_program_master.h +++ /dev/null @@ -1,66 +0,0 @@ -/** - ****************************************************************************** - * - * @file ahrs_spi_program_master.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief AHRS programming over SPI link - master(OpenPilot) end. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef AHRS_PROGRAM_MASTER_H -#define AHRS_PROGRAM_MASTER_H - -typedef enum { - PROGRAM_ERR_OK, //OK - PROGRAM_ERR_LINK, //comms error - PROGRAM_ERR_FUNCTION, -//function failed -} PROGERR; - -/** Connect to AHRS and request programming mode - * returns: false if failed. - */ -bool AhrsProgramConnect(uint32_t spi_id); - -/** Write data to AHRS - * size must be between 1 and SPI_MAX_PROGRAM_DATA_SIZE - * returns: error status - */ - -PROGERR AhrsProgramWrite(uint32_t spi_id, uint32_t address, void * data, - uint32_t size); - -/** Read data from AHRS - * size must be between 1 and SPI_MAX_PROGRAM_DATA_SIZE - * returns: error status - */ - -PROGERR AhrsProgramRead(uint32_t spi_id, uint32_t address, void * data, - uint32_t size); - -/** reboot AHRS - * returns: error status - */ - -PROGERR AhrsProgramReboot(uint32_t spi_id); - -//TODO: Implement programming protocol - -#endif //AHRS_PROGRAM_MASTER_H diff --git a/flight/Bootloaders/AHRS/inc/bl_fsm.h b/flight/Bootloaders/AHRS/inc/bl_fsm.h deleted file mode 100644 index 7c443edb7..000000000 --- a/flight/Bootloaders/AHRS/inc/bl_fsm.h +++ /dev/null @@ -1,97 +0,0 @@ -/** - ****************************************************************************** - * - * @file ahrs_fsm.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef BL_FSM_H -#define BL_FSM_H - -#include "pios_opahrs_proto.h" - -enum lfsm_state { - LFSM_STATE_FAULTED = 0, /* Must be zero so undefined transitions land here */ - LFSM_STATE_STOPPED, - LFSM_STATE_STOPPING, - LFSM_STATE_INACTIVE, - LFSM_STATE_USER_BUSY, - LFSM_STATE_USER_BUSY_RX_PENDING, - LFSM_STATE_USER_BUSY_TX_PENDING, - LFSM_STATE_USER_BUSY_RXTX_PENDING, - LFSM_STATE_USER_RX_PENDING, - LFSM_STATE_USER_TX_PENDING, - LFSM_STATE_USER_RXTX_PENDING, - LFSM_STATE_USER_RX_ACTIVE, - LFSM_STATE_USER_TX_ACTIVE, - LFSM_STATE_USER_RXTX_ACTIVE, - - LFSM_STATE_NUM_STATES -/* Must be last */ -}; - -enum lfsm_event { - LFSM_EVENT_INIT_LINK, - LFSM_EVENT_STOP, - LFSM_EVENT_USER_SET_RX, - LFSM_EVENT_USER_SET_TX, - LFSM_EVENT_USER_DONE, - LFSM_EVENT_RX_LINK, - LFSM_EVENT_RX_USER, - LFSM_EVENT_RX_UNKNOWN, - - LFSM_EVENT_NUM_EVENTS -/* Must be last */ -}; - -struct lfsm_link_stats { - uint32_t rx_badcrc; - uint32_t rx_badmagic_head; - uint32_t rx_badmagic_tail; - uint32_t rx_link; - uint32_t rx_user; - uint32_t tx_user; - uint32_t rx_badtype; - uint32_t rx_badver; -}; - -extern void lfsm_attach(uint32_t spi_id); -extern void lfsm_init(void); -extern void lfsm_inject_event(enum lfsm_event event); - -extern void lfsm_irq_callback(uint8_t crc_ok, uint8_t crc_val); - -extern void lfsm_get_link_stats(struct lfsm_link_stats * stats); -extern enum lfsm_state lfsm_get_state(void); - -extern void lfsm_set_link_proto_v0(struct opahrs_msg_v0 * link_tx, - struct opahrs_msg_v0 * link_rx); -extern void lfsm_user_set_rx_v0(struct opahrs_msg_v0 * user_rx); -extern void lfsm_user_set_tx_v0(struct opahrs_msg_v0 * user_tx); - -extern void lfsm_set_link_proto_v1(struct opahrs_msg_v1 * link_tx, - struct opahrs_msg_v1 * link_rx); -extern void lfsm_user_set_rx_v1(struct opahrs_msg_v1 * user_rx); -extern void lfsm_user_set_tx_v1(struct opahrs_msg_v1 * user_tx); - -extern void lfsm_user_done(void); - -#endif /* BL_FSM_H */ diff --git a/flight/Bootloaders/AHRS/main.c b/flight/Bootloaders/AHRS/main.c deleted file mode 100644 index 756d12566..000000000 --- a/flight/Bootloaders/AHRS/main.c +++ /dev/null @@ -1,268 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup AHRS BOOTLOADER - * @brief The AHRS Modules perform - * - * @{ - * @addtogroup AHRS_BOOTLOADER_Main - * @brief Main function which does the hardware dependent stuff - * @{ - * - * - * @file main.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* OpenPilot Includes */ -#include "ahrs_bl.h" -#include -#include "pios_opahrs_proto.h" -#include "bl_fsm.h" /* lfsm_state */ -#include "stm32f10x_flash.h" - -extern void PIOS_Board_Init(void); - -#define NSS_HOLD_STATE ((GPIOB->IDR & GPIO_Pin_12) ? 0 : 1) -enum bootloader_status boot_status; -/* Private typedef -----------------------------------------------------------*/ -typedef void -(*pFunction)(void); -pFunction Jump_To_Application; -uint32_t JumpAddress; -/* Function Prototypes */ -void -process_spi_request(void); -void -jump_to_app(); -uint8_t jumpFW = FALSE; -uint32_t Fw_crc; -/** - * @brief Bootloader Main function - */ -int main() { - - uint8_t GO_dfu = false; - /* Brings up System using CMSIS functions, enables the LEDs. */ - PIOS_SYS_Init(); - /* Enable Prefetch Buffer */ - FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable); - - /* Flash 2 wait state */ - FLASH_SetLatency(FLASH_Latency_2); - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE); - /* Delay system */ - PIOS_DELAY_Init(); - - for (uint32_t t = 0; t < 10000000; ++t) { - if (NSS_HOLD_STATE == 1) - GO_dfu = TRUE; - else { - GO_dfu = FALSE; - break; - } - } - - PIOS_IAP_Init(); - GO_dfu = GO_dfu | PIOS_IAP_CheckRequest();// OR with app boot request - if (GO_dfu == FALSE) { - jump_to_app(); - } - if (PIOS_IAP_CheckRequest()) { - PIOS_DELAY_WaitmS(1000); - PIOS_IAP_ClearRequest(); - } - PIOS_Board_Init(); - boot_status = idle; - Fw_crc = PIOS_BL_HELPER_CRC_Memory_Calc(); - PIOS_LED_On(PIOS_LED_HEARTBEAT); - while (1) { - process_spi_request(); - } - return 0; -} - -static struct opahrs_msg_v0 link_tx_v0; -static struct opahrs_msg_v0 link_rx_v0; -static struct opahrs_msg_v0 user_tx_v0; -static struct opahrs_msg_v0 user_rx_v0; -void process_spi_request(void) { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - bool msg_to_process = FALSE; - - PIOS_IRQ_Disable(); - /* Figure out if we're in an interesting stable state */ - switch (lfsm_get_state()) { - case LFSM_STATE_USER_BUSY: - msg_to_process = TRUE; - break; - case LFSM_STATE_INACTIVE: - /* Queue up a receive buffer */ - lfsm_user_set_rx_v0(&user_rx_v0); - lfsm_user_done(); - break; - case LFSM_STATE_STOPPED: - /* Get things going */ - lfsm_set_link_proto_v0(&link_tx_v0, &link_rx_v0); - break; - default: - /* Not a stable state */ - break; - } - PIOS_IRQ_Enable(); - - if (!msg_to_process) { - /* Nothing to do */ - //PIOS_COM_SendFormattedString(PIOS_COM_AUX, "."); - return; - } - - if (user_rx_v0.tail.magic != OPAHRS_MSG_MAGIC_TAIL) { - return; - } - - switch (user_rx_v0.payload.user.t) { - - case OPAHRS_MSG_V0_REQ_FWUP_VERIFY: - opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_FWUP_STATUS); - Fw_crc = PIOS_BL_HELPER_CRC_Memory_Calc(); - lfsm_user_set_tx_v0(&user_tx_v0); - boot_status = idle; - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - user_tx_v0.payload.user.v.rsp.fwup_status.status = boot_status; - break; - case OPAHRS_MSG_V0_REQ_RESET: - PIOS_DELAY_WaitmS(user_rx_v0.payload.user.v.req.reset.reset_delay_in_ms); - PIOS_SYS_Reset(); - break; - case OPAHRS_MSG_V0_REQ_VERSIONS: - opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_VERSIONS); - user_tx_v0.payload.user.v.rsp.versions.bl_version = BOOTLOADER_VERSION; - user_tx_v0.payload.user.v.rsp.versions.hw_version = (BOARD_TYPE << 8) - | BOARD_REVISION; - user_tx_v0.payload.user.v.rsp.versions.fw_crc = Fw_crc; - lfsm_user_set_tx_v0(&user_tx_v0); - break; - case OPAHRS_MSG_V0_REQ_MEM_MAP: - opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_MEM_MAP); - user_tx_v0.payload.user.v.rsp.mem_map.density = bdinfo->hw_type; - user_tx_v0.payload.user.v.rsp.mem_map.rw_flags = (BOARD_READABLE - | (BOARD_WRITABLE << 1)); - user_tx_v0.payload.user.v.rsp.mem_map.size_of_code_memory - = bdinfo->fw_size; - user_tx_v0.payload.user.v.rsp.mem_map.size_of_description - = bdinfo->desc_size; - user_tx_v0.payload.user.v.rsp.mem_map.start_of_user_code - = bdinfo->fw_base; - lfsm_user_set_tx_v0(&user_tx_v0); - break; - case OPAHRS_MSG_V0_REQ_SERIAL: - opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_SERIAL); - PIOS_SYS_SerialNumberGet( - (char *) &(user_tx_v0.payload.user.v.rsp.serial.serial_bcd)); - lfsm_user_set_tx_v0(&user_tx_v0); - break; - case OPAHRS_MSG_V0_REQ_FWUP_STATUS: - opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_FWUP_STATUS); - user_tx_v0.payload.user.v.rsp.fwup_status.status = boot_status; - lfsm_user_set_tx_v0(&user_tx_v0); - break; - case OPAHRS_MSG_V0_REQ_FWUP_DATA: - PIOS_LED_On(PIOS_LED_HEARTBEAT); - opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_FWUP_STATUS); - if (!(user_rx_v0.payload.user.v.req.fwup_data.adress - < bdinfo->fw_base)) { - for (uint8_t x = 0; x - < user_rx_v0.payload.user.v.req.fwup_data.size; ++x) { - if (FLASH_ProgramWord( - (user_rx_v0.payload.user.v.req.fwup_data.adress - + ((uint32_t)(x * 4))), - user_rx_v0.payload.user.v.req.fwup_data.data[x]) - != FLASH_COMPLETE) { - boot_status = write_error; - break; - } - } - } else { - boot_status = outside_dev_capabilities; - } - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - user_tx_v0.payload.user.v.rsp.fwup_status.status = boot_status; - lfsm_user_set_tx_v0(&user_tx_v0); - break; - case OPAHRS_MSG_V0_REQ_FWDN_DATA: - opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_FWDN_DATA); - uint32_t adr = user_rx_v0.payload.user.v.req.fwdn_data.adress; - for (uint8_t x = 0; x < 4; ++x) { - user_tx_v0.payload.user.v.rsp.fw_dn.data[x] - = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); - } - lfsm_user_set_tx_v0(&user_tx_v0); - break; - case OPAHRS_MSG_V0_REQ_FWUP_START: - FLASH_Unlock(); - opahrs_msg_v0_init_user_tx(&user_tx_v0, OPAHRS_MSG_V0_RSP_FWUP_STATUS); - user_tx_v0.payload.user.v.rsp.fwup_status.status = boot_status; - lfsm_user_set_tx_v0(&user_tx_v0); - PIOS_LED_On(PIOS_LED_HEARTBEAT); - if (PIOS_BL_HELPER_FLASH_Start() == TRUE) { - boot_status = started; - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else { - boot_status = start_failed; - break; - } - - break; - case OPAHRS_MSG_V0_REQ_BOOT: - PIOS_DELAY_WaitmS(user_rx_v0.payload.user.v.req.boot.boot_delay_in_ms); - FLASH_Lock(); - jump_to_app(); - break; - default: - break; - } - - /* Finished processing the received message, requeue it */ - lfsm_user_set_rx_v0(&user_rx_v0); - lfsm_user_done(); - return; -} -void jump_to_app() { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - - PIOS_LED_On(PIOS_LED_HEARTBEAT); - if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ - FLASH_Lock(); - RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); - RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); - - JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); - Jump_To_Application = (pFunction) JumpAddress; - /* Initialize user application's Stack Pointer */ - __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); - Jump_To_Application(); - } else { - boot_status = jump_failed; - return; - } -} diff --git a/flight/Bootloaders/BootloaderUpdater/main.c b/flight/Bootloaders/BootloaderUpdater/main.c index 0d475a395..b7348dac4 100644 --- a/flight/Bootloaders/BootloaderUpdater/main.c +++ b/flight/Bootloaders/BootloaderUpdater/main.c @@ -28,12 +28,13 @@ /* Bootloader Includes */ #include #include +#include "pios_board_info.h" #define MAX_WRI_RETRYS 3 /* Prototype of PIOS_Board_Init() function */ extern void PIOS_Board_Init(void); extern void FLASH_Download(); -void error(void); +void error(int); /* The ADDRESSES of the _binary_* symbols are the important * data. This is non-intuitive for _binary_size where you @@ -50,12 +51,40 @@ int main() { PIOS_SYS_Init(); PIOS_Board_Init(); + PIOS_LED_On(PIOS_LED_HEARTBEAT); + PIOS_DELAY_WaitmS(3000); + PIOS_LED_Off(PIOS_LED_HEARTBEAT); /// Self overwrite check uint32_t base_address = SCB->VTOR; if ((0x08000000 + embedded_image_size) > base_address) - error(); + error(PIOS_LED_HEARTBEAT); /// + + /* + * Make sure the bootloader we're carrying is for the same + * board type and board revision as the one we're running on. + * + * Assume the bootloader in flash and the bootloader contained in + * the updater both carry a board_info_blob at the end of the image. + */ + + /* Calculate how far the board_info_blob is from the beginning of the bootloader */ + uint32_t board_info_blob_offset = (uint32_t)&pios_board_info_blob - (uint32_t)0x08000000; + + /* Use the same offset into our embedded bootloader image */ + struct pios_board_info * new_board_info_blob = (struct pios_board_info *) + ((uint32_t)embedded_image_start + board_info_blob_offset); + + /* Compare the two board info blobs to make sure they're for the same HW revision */ + if ((pios_board_info_blob.magic != new_board_info_blob->magic) || + (pios_board_info_blob.board_type != new_board_info_blob->board_type) || + (pios_board_info_blob.board_rev != new_board_info_blob->board_rev)) { + error(PIOS_LED_HEARTBEAT); + } + + /* Embedded bootloader looks like it's the right one for this HW, proceed... */ + FLASH_Unlock(); /// Bootloader memory space erase @@ -79,7 +108,7 @@ int main() { } if (fail == true) - error(); + error(PIOS_LED_HEARTBEAT); /// @@ -87,6 +116,7 @@ int main() { /// Bootloader programing for (uint32_t offset = 0; offset < embedded_image_size/sizeof(uint32_t); ++offset) { bool result = false; + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); for (uint8_t retry = 0; retry < MAX_WRI_RETRYS; ++retry) { if (result == false) { result = (FLASH_ProgramWord(0x08000000 + (offset * 4), embedded_image_start[offset]) @@ -94,9 +124,15 @@ int main() { } } if (result == false) - error(); + error(PIOS_LED_HEARTBEAT); } /// + for (uint8_t x = 0; x < 3; ++x) { + PIOS_LED_On(PIOS_LED_HEARTBEAT); + PIOS_DELAY_WaitmS(1000); + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + PIOS_DELAY_WaitmS(1000); + } /// Invalidate the bootloader updater so we won't run /// the update again on the next power cycle. @@ -109,7 +145,11 @@ int main() { } -void error(void) { +void error(int led) { for (;;) { + PIOS_LED_On(led); + PIOS_DELAY_WaitmS(500); + PIOS_LED_Off(led); + PIOS_DELAY_WaitmS(500); } } diff --git a/flight/Bootloaders/BootloaderUpdater/pios_board.c b/flight/Bootloaders/BootloaderUpdater/pios_board.c index d19a2ba13..0b7cb9efc 100644 --- a/flight/Bootloaders/BootloaderUpdater/pios_board.c +++ b/flight/Bootloaders/BootloaderUpdater/pios_board.c @@ -35,6 +35,8 @@ #include void PIOS_Board_Init(void) { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + /* Enable Prefetch Buffer */ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable); @@ -42,13 +44,15 @@ void PIOS_Board_Init(void) { FLASH_SetLatency(FLASH_Latency_2); /* Delay system */ - PIOS_DELAY_Init(); - - /* Initialize the PiOS library */ - PIOS_GPIO_Init(); + PIOS_DELAY_Init(); + /* LEDs */ #if defined(PIOS_INCLUDE_LED) - PIOS_LED_Init(&pios_led_cfg); + const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev); + PIOS_Assert(led_cfg); + PIOS_LED_Init(led_cfg); #endif /* PIOS_INCLUDE_LED */ + /* Initialize the PiOS library */ + PIOS_GPIO_Init(); } diff --git a/flight/Bootloaders/CopterControl/Makefile b/flight/Bootloaders/CopterControl/Makefile index be7e98190..8c22d37a7 100644 --- a/flight/Bootloaders/CopterControl/Makefile +++ b/flight/Bootloaders/CopterControl/Makefile @@ -104,6 +104,8 @@ SRC += $(PIOSSTM32F10X)/pios_usart.c SRC += $(PIOSSTM32F10X)/pios_irq.c SRC += $(PIOSSTM32F10X)/pios_debug.c SRC += $(PIOSSTM32F10X)/pios_gpio.c +SRC += $(PIOSSTM32F10X)/pios_iap.c +SRC += $(PIOSSTM32F10X)/pios_bl_helper.c # PIOS USB related files (seperated to make code maintenance more easy) SRC += $(PIOSSTM32F10X)/pios_usb.c @@ -113,12 +115,11 @@ SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c SRC += $(OPSYSTEM)/pios_usb_board_data.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c +SRC += $(PIOSCOMMON)/pios_usb_util.c ## PIOS Hardware (Common) SRC += $(PIOSCOMMON)/pios_board_info.c SRC += $(PIOSCOMMON)/pios_com_msg.c -SRC += $(PIOSCOMMON)/pios_bl_helper.c -SRC += $(PIOSCOMMON)/pios_iap.c SRC += $(PIOSCOMMON)/printf-stdarg.c ## Libraries for flight calculations @@ -414,7 +415,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/CopterControl/inc/pios_usb_board_data.h b/flight/Bootloaders/CopterControl/inc/pios_usb_board_data.h index f1accee17..addb24f19 100644 --- a/flight/Bootloaders/CopterControl/inc/pios_usb_board_data.h +++ b/flight/Bootloaders/CopterControl/inc/pios_usb_board_data.h @@ -39,6 +39,7 @@ #define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_COPTERCONTROL #define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_COPTERCONTROL, USB_OP_BOARD_MODE_BL) +#define PIOS_USB_BOARD_SN_SUFFIX "+BL" /* * The bootloader uses a simplified report structure diff --git a/flight/Bootloaders/CopterControl/main.c b/flight/Bootloaders/CopterControl/main.c index 17733bbef..77c02f18b 100644 --- a/flight/Bootloaders/CopterControl/main.c +++ b/flight/Bootloaders/CopterControl/main.c @@ -70,14 +70,13 @@ uint8_t processRX(); void jump_to_app(); int main() { - PIOS_SYS_Init(); - if (BSL_HOLD_STATE == 0) - USB_connected = TRUE; - + PIOS_SYS_Init(); + PIOS_Board_Init(); PIOS_IAP_Init(); + + USB_connected = PIOS_USB_CableConnected(0); if (PIOS_IAP_CheckRequest() == TRUE) { - PIOS_Board_Init(); PIOS_DELAY_WaitmS(1000); User_DFU_request = TRUE; PIOS_IAP_ClearRequest(); diff --git a/flight/Bootloaders/CopterControl/pios_board.c b/flight/Bootloaders/CopterControl/pios_board.c index c5bd761ea..4104c4028 100644 --- a/flight/Bootloaders/CopterControl/pios_board.c +++ b/flight/Bootloaders/CopterControl/pios_board.c @@ -31,7 +31,7 @@ * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE */ #include "board_hw_defs.c" - +#include #include uint32_t pios_com_telem_usb_id; @@ -59,8 +59,12 @@ void PIOS_Board_Init(void) { /* Initialize the PiOS library */ PIOS_GPIO_Init(); + const struct pios_board_info * bdinfo = &pios_board_info_blob; + #if defined(PIOS_INCLUDE_LED) - PIOS_LED_Init(&pios_led_cfg); + const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev); + PIOS_Assert(led_cfg); + PIOS_LED_Init(led_cfg); #endif /* PIOS_INCLUDE_LED */ #if defined(PIOS_INCLUDE_USB) @@ -71,8 +75,15 @@ void PIOS_Board_Init(void) { PIOS_USB_DESC_HID_ONLY_Init(); uint32_t pios_usb_id; - if (PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg)) { - PIOS_Assert(0); + switch(bdinfo->board_rev) { + case BOARD_REVISION_CC: + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc); + break; + case BOARD_REVISION_CC3D: + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc3d); + break; + default: + PIOS_Assert(0); } #if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG) uint32_t pios_usb_hid_id; @@ -90,3 +101,7 @@ void PIOS_Board_Init(void) { board_init_complete = true; } + +void PIOS_ADC_DMA_Handler() +{ +} diff --git a/flight/Bootloaders/CopterControl/pios_usb_board_data.c b/flight/Bootloaders/CopterControl/pios_usb_board_data.c index 4f02ce424..1993320d4 100644 --- a/flight/Bootloaders/CopterControl/pios_usb_board_data.c +++ b/flight/Bootloaders/CopterControl/pios_usb_board_data.c @@ -31,6 +31,7 @@ #include "pios_usb_board_data.h" /* struct usb_*, USB_* */ #include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ #include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +#include "pios_usb_util.h" /* PIOS_USB_UTIL_AsciiToUtf8 */ static const uint8_t usb_product_id[28] = { sizeof(usb_product_id), @@ -50,40 +51,15 @@ static const uint8_t usb_product_id[28] = { 'l', 0, }; -static uint8_t usb_serial_number[52] = { +static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN*2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1)*2] = { sizeof(usb_serial_number), USB_DESC_TYPE_STRING, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0 }; static const struct usb_string_langid usb_lang_id = { .bLength = sizeof(usb_lang_id), .bDescriptorType = USB_DESC_TYPE_STRING, - .bLangID = htousbs(USB_LANGID_ENGLISH_UK), + .bLangID = htousbs(USB_LANGID_ENGLISH_US), }; static const uint8_t usb_vendor_id[28] = { @@ -107,11 +83,13 @@ static const uint8_t usb_vendor_id[28] = { int32_t PIOS_USB_BOARD_DATA_Init(void) { /* Load device serial number into serial number string */ - uint8_t sn[25]; + uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1]; PIOS_SYS_SerialNumberGet((char *)sn); - for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) { - usb_serial_number[2 + 2 * i] = sn[i]; - } + + /* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */ + uint8_t * utf8 = &(usb_serial_number[2]); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1); PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); diff --git a/flight/Bootloaders/OpenPilot/Makefile b/flight/Bootloaders/OpenPilot/Makefile deleted file mode 100644 index 071b20fec..000000000 --- a/flight/Bootloaders/OpenPilot/Makefile +++ /dev/null @@ -1,491 +0,0 @@ - ##### - # Project: OpenPilot - # - # - # Makefile for OpenPilot project build PiOS and the AP. - # - # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. - # - # - # This program is free software; you can redistribute it and/or modify - # it under the terms of the GNU General Public License as published by - # the Free Software Foundation; either version 3 of the License, or - # (at your option) any later version. - # - # This program is distributed in the hope that it will be useful, but - # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - # for more details. - # - # You should have received a copy of the GNU General Public License along - # with this program; if not, write to the Free Software Foundation, Inc., - # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - ##### - -WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../../) -include $(TOP)/make/firmware-defs.mk -include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk - -# Target file name (without extension). -TARGET := bl_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - -# Set developer code and compile options -# Set to YES to compile for debugging -DEBUG ?= NO - -# Set to YES to use the Servo output pins for debugging via scope or logic analyser -ENABLE_DEBUG_PINS ?= NO - -# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs -ENABLE_AUX_UART ?= NO - -# Set to YES when using Code Sourcery toolchain -CODE_SOURCERY ?= NO - -# Remove command is different for Code Sourcery on Windows -ifeq ($(CODE_SOURCERY), YES) -REMOVE_CMD = cs-rm -else -REMOVE_CMD = rm -endif - -FLASH_TOOL = OPENOCD - -# Paths -OPSYSTEM = . -OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ./UAVTalk -OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ./UAVObjects -OPUAVOBJINC = $(OPUAVOBJ)/inc -OPTESTS = ./Tests -OPMODULEDIR = ./Modules -FLIGHTLIB = ../../Libraries -FLIGHTLIBINC = ../../Libraries/inc -PIOS = ../../PiOS -PIOSINC = $(PIOS)/inc -PIOSSTM32F10X = $(PIOS)/STM32F10x -PIOSCOMMON = $(PIOS)/Common -PIOSBOARDS = $(PIOS)/Boards -APPLIBDIR = $(PIOSSTM32F10X)/Libraries -STMLIBDIR = $(APPLIBDIR) -STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver -STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver -STMSPDSRCDIR = $(STMSPDDIR)/src -STMSPDINCDIR = $(STMSPDDIR)/inc -STMUSBSRCDIR = $(STMUSBDIR)/src -STMUSBINCDIR = $(STMUSBDIR)/inc -CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 -DOSFSDIR = $(APPLIBDIR)/dosfs -MSDDIR = $(APPLIBDIR)/msd -RTOSDIR = $(APPLIBDIR)/FreeRTOS -RTOSSRCDIR = $(RTOSDIR)/Source -RTOSINCDIR = $(RTOSSRCDIR)/include -DOXYGENDIR = ../Doc/Doxygen -HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME) - -# List C source files here. (C dependencies are automatically generated.) -# use file-extension c for "c-only"-files - -## OPENPILOT_BL CORE: -SRC += $(OPSYSTEM)/main.c -SRC += $(OPSYSTEM)/pios_board.c -SRC += $(OPSYSTEM)/op_dfu.c -SRC += $(FLIGHTLIB)/stopwatch.c -SRC += $(OPSYSTEM)/ssp.c - - -## PIOS Hardware (STM32F10x) -SRC += $(PIOSSTM32F10X)/pios_sys.c -SRC += $(PIOSSTM32F10X)/pios_led.c -SRC += $(PIOSSTM32F10X)/pios_delay.c -SRC += $(PIOSSTM32F10X)/pios_usart.c -SRC += $(PIOSSTM32F10X)/pios_irq.c -SRC += $(PIOSSTM32F10X)/pios_spi.c -SRC += $(PIOSSTM32F10X)/pios_debug.c -SRC += $(PIOSSTM32F10X)/pios_gpio.c - -# PIOS USB related files (seperated to make code maintenance more easy) -SRC += $(PIOSSTM32F10X)/pios_usb.c -SRC += $(PIOSSTM32F10X)/pios_usbhook.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c -SRC += $(OPSYSTEM)/pios_usb_board_data.c -SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c - -## PIOS Hardware (Common) -SRC += $(PIOSCOMMON)/pios_board_info.c -SRC += $(PIOSCOMMON)/pios_com_msg.c -SRC += $(PIOSCOMMON)/pios_com.c -SRC += $(PIOSCOMMON)/pios_opahrs_v0.c -SRC += $(PIOSCOMMON)/pios_bl_helper.c -SRC += $(PIOSCOMMON)/pios_iap.c -SRC += $(PIOSCOMMON)/pios_opahrs_proto.c -SRC += $(PIOSCOMMON)/printf-stdarg.c - -## Libraries for flight calculations -SRC += $(FLIGHTLIB)/fifo_buffer.c - -## CMSIS for STM32 -SRC += $(CMSISDIR)/core_cm3.c -SRC += $(CMSISDIR)/system_stm32f10x.c - -## Used parts of the STM-Library -SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c -SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c -SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c -SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c -SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c -SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c -SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c -SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c -SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c -SRC += $(STMSPDSRCDIR)/misc.c - -## STM32 USB Library -SRC += $(STMUSBSRCDIR)/usb_core.c -SRC += $(STMUSBSRCDIR)/usb_init.c -SRC += $(STMUSBSRCDIR)/usb_int.c -SRC += $(STMUSBSRCDIR)/usb_mem.c -SRC += $(STMUSBSRCDIR)/usb_regs.c -SRC += $(STMUSBSRCDIR)/usb_sil.c - -# List C source files here which must be compiled in ARM-Mode (no -mthumb). -# use file-extension c for "c-only"-files -## just for testing, timer.c could be compiled in thumb-mode too -SRCARM = - -# List C++ source files here. -# use file-extension .cpp for C++-files (not .C) -CPPSRC = - -# List C++ source files here which must be compiled in ARM-Mode. -# use file-extension .cpp for C++-files (not .C) -#CPPSRCARM = $(TARGET).cpp -CPPSRCARM = - -# List Assembler source files here. -# Make them always end in a capital .S. Files ending in a lowercase .s -# will not be considered source files but generated files (assembler -# output from the compiler), and will be deleted upon "make clean"! -# Even though the DOS/Win* filesystem matches both .s and .S the same, -# it will preserve the spelling of the filenames, and gcc itself does -# care about how the name is spelled on its command-line. -ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S - -# List Assembler source files here which must be assembled in ARM-Mode.. -ASRCARM = - -# List any extra directories to look for include files here. -# Each directory must be seperated by a space. -EXTRAINCDIRS = $(OPSYSTEM) -EXTRAINCDIRS += $(OPSYSTEMINC) -EXTRAINCDIRS += $(OPUAVTALK) -EXTRAINCDIRS += $(OPUAVTALKINC) -EXTRAINCDIRS += $(OPUAVOBJ) -EXTRAINCDIRS += $(OPUAVOBJINC) -EXTRAINCDIRS += $(PIOS) -EXTRAINCDIRS += $(PIOSINC) -EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(PIOSSTM32F10X) -EXTRAINCDIRS += $(PIOSCOMMON) -EXTRAINCDIRS += $(PIOSBOARDS) -EXTRAINCDIRS += $(STMSPDINCDIR) -EXTRAINCDIRS += $(STMUSBINCDIR) -EXTRAINCDIRS += $(CMSISDIR) -EXTRAINCDIRS += $(DOSFSDIR) -EXTRAINCDIRS += $(MSDDIR) -EXTRAINCDIRS += $(RTOSINCDIR) -EXTRAINCDIRS += $(APPLIBDIR) -EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3 -EXTRAINCDIRS += $(HWDEFSINC) - - - -# List any extra directories to look for library files here. -# Also add directories where the linker should search for -# includes from linker-script to the list -# Each directory must be seperated by a space. -EXTRA_LIBDIRS = - -# Extra Libraries -# Each library-name must be seperated by a space. -# i.e. to link with libxyz.a, libabc.a and libefsl.a: -# EXTRA_LIBS = xyz abc efsl -# for newlib-lpc (file: libnewlibc-lpc.a): -# EXTRA_LIBS = newlib-lpc -EXTRA_LIBS = - -# Path to Linker-Scripts -LINKERSCRIPTPATH = $(PIOSSTM32F10X) - -# Optimization level, can be [0, 1, 2, 3, s]. -# 0 = turn off optimization. s = optimize for size. -# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) - -ifeq ($(DEBUG),YES) -OPT = 0 -else -OPT = s -endif - -# Output format. (can be ihex or binary or both) -# binary to create a load-image in raw-binary format i.e. for SAM-BA, -# ihex to create a load-image in Intel hex format -#LOADFORMAT = ihex -#LOADFORMAT = binary -LOADFORMAT = both - -# Debugging format. -DEBUGF = dwarf-2 - -# Place project-specific -D (define) and/or -# -U options for C here. -CDEFS = -DSTM32F10X_$(MODEL) -CDEFS += -DUSE_STDPERIPH_DRIVER -CDEFS += -DUSE_$(BOARD) -ifeq ($(ENABLE_DEBUG_PINS), YES) -CDEFS += -DPIOS_ENABLE_DEBUG_PINS -endif -ifeq ($(ENABLE_AUX_UART), YES) -CDEFS += -DPIOS_ENABLE_AUX_UART -endif - -# Provide (only) the bootloader with board-specific defines -BLONLY_CDEFS += -DBOARD_TYPE=$(BOARD_TYPE) -BLONLY_CDEFS += -DBOARD_REVISION=$(BOARD_REVISION) -BLONLY_CDEFS += -DHW_TYPE=$(HW_TYPE) -BLONLY_CDEFS += -DBOOTLOADER_VERSION=$(BOOTLOADER_VERSION) -BLONLY_CDEFS += -DFW_BANK_BASE=$(FW_BANK_BASE) -BLONLY_CDEFS += -DFW_BANK_SIZE=$(FW_BANK_SIZE) -BLONLY_CDEFS += -DFW_DESC_SIZE=$(FW_DESC_SIZE) - -# Place project-specific -D and/or -U options for -# Assembler with preprocessor here. -#ADEFS = -DUSE_IRQ_ASM_WRAPPER -ADEFS = -D__ASSEMBLY__ - -# Compiler flag to set the C Standard level. -# c89 - "ANSI" C -# gnu89 - c89 plus GCC extensions -# c99 - ISO C99 standard (not yet fully implemented) -# gnu99 - c99 plus GCC extensions -CSTANDARD = -std=gnu99 - -#----- - -# Compiler flags. - -# -g*: generate debugging information -# -O*: optimization level -# -f...: tuning, see GCC manual and avr-libc documentation -# -Wall...: warning level -# -Wa,...: tell GCC to pass this to the assembler. -# -adhlns...: create assembler listing -# -# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) - -ifeq ($(DEBUG),YES) -CFLAGS += -DDEBUG -endif - -CFLAGS += -g$(DEBUGF) -CFLAGS += -O$(OPT) -ifeq ($(DEBUG),NO) -CFLAGS += -ffunction-sections -endif - -CFLAGS += -mcpu=$(MCU) -CFLAGS += $(CDEFS) -CFLAGS += $(BLONLY_CDEFS) -CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. - -CFLAGS += -mapcs-frame -CFLAGS += -fomit-frame-pointer -ifeq ($(CODE_SOURCERY), YES) -CFLAGS += -fpromote-loop-indices -endif - -CFLAGS += -Wall -CFLAGS += -Werror -CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) -# Compiler flags to generate dependency files: -CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d - -# flags only for C -#CONLYFLAGS += -Wnested-externs -CONLYFLAGS += $(CSTANDARD) - -# Assembler flags. -# -Wa,...: tell GCC to pass this to the assembler. -# -ahlns: create listing -ASFLAGS = -mcpu=$(MCU) -I. -x assembler-with-cpp -ASFLAGS += $(ADEFS) -ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) -ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) - -MATH_LIB = -lm - -# Linker flags. -# -Wl,...: tell GCC to pass this to linker. -# -Map: create map file -# --cref: add cross reference to map file -LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections -ifeq ($(DEBUG),NO) -LDFLAGS += -Wl,-static -endif -LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) -LDFLAGS += -lc -LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) -LDFLAGS += $(MATH_LIB) -LDFLAGS += -lc -lgcc - -# Set linker-script name depending on selected submodel name -LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_memory.ld -LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_BL_sections.ld - -# Define programs and commands. -REMOVE = $(REMOVE_CMD) -f - -# List of all source files. -ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) -# List of all source files without directory and file-extension. -ALLSRCBASE = $(notdir $(basename $(ALLSRC))) - -# Define all object files. -ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) - -# Define all listing files (used for make clean). -LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) -# Define all depedency-files (used for make clean). -DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) - -# Default target. -all: build - -ifeq ($(LOADFORMAT),ihex) -build: elf hex sym -else -ifeq ($(LOADFORMAT),binary) -build: elf bin sym -else -ifeq ($(LOADFORMAT),both) -build: elf hex bin sym -else -$(error "$(MSG_FORMATERROR) $(FORMAT)") -endif -endif -endif - -${OUTDIR}/InitMods.c: Makefile - @echo $(MSG_MODINIT) $(call toprel, $@) - @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c - -# Link: create ELF output file from object files. -$(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ))) - -# Assemble: create object files from assembler source files. -$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) - -# Assemble: create object files from assembler source files. ARM-only -$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) - -# Compile: create object files from C source files. -$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) - -# Compile: create object files from C source files. ARM-only -$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) - -# Compile: create object files from C++ source files. -$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) - -# Compile: create object files from C++ source files. ARM-only -$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) - -# Compile: create assembler files from C source files. ARM/Thumb -$(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC)) - -# Compile: create assembler files from C source files. ARM only -$(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) - -$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin - -# Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG))) - -.PHONY: elf lss sym hex bin bino -elf: $(OUTDIR)/$(TARGET).elf -lss: $(OUTDIR)/$(TARGET).lss -sym: $(OUTDIR)/$(TARGET).sym -hex: $(OUTDIR)/$(TARGET).hex -bin: $(OUTDIR)/$(TARGET).bin -bino: $(OUTDIR)/$(TARGET).bin.o - -# Display sizes of sections. -$(eval $(call SIZE_TEMPLATE, $(OUTDIR)/$(TARGET).elf)) - -# Generate Doxygen documents -docs: - doxygen $(DOXYGENDIR)/doxygen.cfg - -# Install: install binary file with prefix/suffix into install directory -install: $(OUTDIR)/$(TARGET).bin -ifneq ($(INSTALL_DIR),) - @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) mkdir -p $(INSTALL_DIR) - $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin -else - $(error INSTALL_DIR must be specified for $@) -endif - -# Target: clean project. -clean: clean_list - -clean_list : - @echo $(MSG_CLEANING) - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).map - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).elf - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).hex - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).sym - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).lss - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin.o - $(V1) $(REMOVE) $(ALLOBJ) - $(V1) $(REMOVE) $(LSTFILES) - $(V1) $(REMOVE) $(DEPFILES) - $(V1) $(REMOVE) $(SRC:.c=.s) - $(V1) $(REMOVE) $(SRCARM:.c=.s) - $(V1) $(REMOVE) $(CPPSRC:.cpp=.s) - $(V1) $(REMOVE) $(CPPSRCARM:.cpp=.s) - - -# Create output files directory -# all known MS Windows OS define the ComSpec environment variable -ifdef ComSpec -$(shell md $(subst /,\\,$(OUTDIR)) 2>NUL) -else -$(shell mkdir -p $(OUTDIR) 2>/dev/null) -endif - -# Include the dependency files. -ifdef ComSpec --include $(shell md $(subst /,\\,$(OUTDIR))\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) -else --include $(shell mkdir -p $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) -endif - -# Listing of phony targets. -.PHONY : all build clean clean_list install diff --git a/flight/Bootloaders/OpenPilot/inc/pios_config.h b/flight/Bootloaders/OpenPilot/inc/pios_config.h deleted file mode 100644 index 932c1a913..000000000 --- a/flight/Bootloaders/OpenPilot/inc/pios_config.h +++ /dev/null @@ -1,58 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @{ - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * Central compile time config for the project. - * In particular, pios_config.h is where you define which PiOS libraries - * and features are included in the firmware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H -#define PIOS_INCLUDE_BL_HELPER -#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SPI -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_USART -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_OPAHRS -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_COM_MSG -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_IAP -//#define DEBUG_SSP - -/* Defaults for Logging */ -#define LOG_FILENAME "PIOS.LOG" -#define STARTUP_LOG_ENABLED 1 - -#endif /* PIOS_CONFIG_H */ -/** - * @} - * @} - */ diff --git a/flight/Bootloaders/OpenPilot/inc/ssp.h b/flight/Bootloaders/OpenPilot/inc/ssp.h deleted file mode 100644 index ed700e052..000000000 --- a/flight/Bootloaders/OpenPilot/inc/ssp.h +++ /dev/null @@ -1,117 +0,0 @@ -/******************************************************************* - * - * NAME: ssp.h - * - * - *******************************************************************/ -#ifndef SSP_H -#define SSP_H -/** INCLUDE FILES **/ -#include - -/** LOCAL DEFINITIONS **/ -#ifndef TRUE -#define TRUE 1 -#endif - -#ifndef FALSE -#define FALSE 0 -#endif - -#define SSP_TX_IDLE 0 // not expecting a ACK packet (no current transmissions in progress) -#define SSP_TX_WAITING 1 // waiting for a valid ACK to arrive -#define SSP_TX_TIMEOUT 2 // failed to receive a valid ACK in the timeout period, after retrying. -#define SSP_TX_ACKED 3 // valid ACK received before timeout period. -#define SSP_TX_BUFOVERRUN 4 // amount of data to send execeds the transmission buffer sizeof -#define SSP_TX_BUSY 5 // Attempted to start a transmission while a transmission was already in progress. -//#define SSP_TX_FAIL - failure... - -#define SSP_RX_IDLE 0 -#define SSP_RX_RECEIVING 1 -#define SSP_RX_COMPLETE 2 - -// types of packet that can be received -#define SSP_RX_DATA 5 -#define SSP_RX_ACK 6 -#define SSP_RX_SYNCH 7 - -typedef enum decodeState_ { - decode_len1_e = 0, - decode_seqNo_e, - decode_data_e, - decode_crc1_e, - decode_crc2_e, - decode_idle_e -} DecodeState_t; - -typedef enum ReceiveState { - state_escaped_e = 0, state_unescaped_e -} ReceiveState_t; - -typedef struct { - uint8_t *pbuff; - uint16_t length; - uint16_t crc; - uint8_t seqNo; -} Packet_t; - -typedef struct { - - uint8_t *rxBuf; // Buffer used to store rcv data - uint16_t rxBufSize; // rcv buffer size. - uint8_t *txBuf; // Length of data in buffer - uint16_t txBufSize; // CRC for data in Packet buff - uint16_t max_retry; // Maximum number of retrys for a single transmit. - int32_t timeoutLen; // how long to wait for each retry to succeed - void (*pfCallBack)(uint8_t *, uint16_t); // call back function that is called when a full packet has been received - int16_t (*pfSerialRead)(void); // function to call to read a byte from serial hardware - void (*pfSerialWrite)( uint8_t); // function used to write a byte to serial hardware for transmission - uint32_t (*pfGetTime)(void); // function returns time in number of seconds that has elapsed from a given reference point -} PortConfig_t; - -typedef struct Port_tag { - void (*pfCallBack)(uint8_t *, uint16_t); // call back function that is called when a full packet has been received - int16_t (*pfSerialRead)(void); // function to read a character from the serial input stream - void (*pfSerialWrite)( uint8_t); // function to write a byte to be sent out the serial port - uint32_t (*pfGetTime)(void); // function returns time in number of seconds that has elapsed from a given reference point - uint8_t retryCount; // how many times have we tried to transmit the 'send' packet - uint8_t maxRetryCount; // max. times to try to transmit the 'send' packet - int32_t timeoutLen; // how long to wait for each retry to succeed - int32_t timeout; // current timeout. when 'time' reaches this point we have timed out - uint8_t txSeqNo; // current 'send' packet sequence number - uint16_t rxBufPos; // current buffer position in the receive packet - uint16_t rxBufLen; // number of 'data' bytes in the buffer - uint8_t rxSeqNo; // current 'receive' packet number - uint16_t rxBufSize; // size of the receive buffer. - uint16_t txBufSize; // size of the transmit buffer. - uint8_t *txBuf; // transmit buffer. REquired to store a copy of packet data in case a retry is needed. - uint8_t *rxBuf; // receive buffer. Used to store data as a packet is received. - uint16_t sendSynch; // flag to indicate that we should send a synchronize packet to the host - // this is required when switching from the application to the bootloader - // and vice-versa. This fixes the firwmare download timeout. - // when this flag is set to true, the next time we send a packet we will first - // send a synchronize packet. - ReceiveState_t InputState; - DecodeState_t DecodeState; - uint16_t SendState; - uint16_t crc; - uint32_t RxError; - uint32_t TxError; - uint16_t flags; -} Port_t; - -/** Public Data **/ - -/** PUBLIC FUNCTIONS **/ -int16_t ssp_ReceiveProcess(Port_t *thisport); -int16_t ssp_SendProcess(Port_t *thisport); -uint16_t ssp_SendString(Port_t *thisport, char *str); -int16_t ssp_SendData(Port_t *thisport, const uint8_t * data, - const uint16_t length); -void ssp_Init(Port_t *thisport, const PortConfig_t* const info); -int16_t ssp_ReceiveByte(Port_t *thisport); -uint16_t ssp_Synchronise(Port_t *thisport); - -/** EXTERNAL FUNCTIONS **/ - -#endif diff --git a/flight/Bootloaders/OpenPilot/main.c b/flight/Bootloaders/OpenPilot/main.c deleted file mode 100644 index da39e2521..000000000 --- a/flight/Bootloaders/OpenPilot/main.c +++ /dev/null @@ -1,284 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @brief These files contain the code to the OpenPilot MB Bootloader. - * - * @{ - * @file main.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This is the file with the main function of the OpenPilot BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -/* Bootloader Includes */ -#include -#include -#include "pios_opahrs.h" -#include "stopwatch.h" -#include "op_dfu.h" -#include "usb_lib.h" -#include "pios_iap.h" -#include "ssp.h" -#include "fifo_buffer.h" -#include "pios_com_msg.h" -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void FLASH_Download(); -#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) - -/* Private typedef -----------------------------------------------------------*/ -typedef void (*pFunction)(void); -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -pFunction Jump_To_Application; -uint32_t JumpAddress; - -/// LEDs PWM -uint32_t period1 = 50; // *100 uS -> 5 mS -uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS -uint32_t period2 = 50; // *100 uS -> 5 mS -uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS - - -//////////////////////////////////////// -uint8_t tempcount = 0; - -/// SSP SECTION -/// SSP TIME SOURCE -#define SSP_TIMER TIM7 -uint32_t ssp_time = 0; -#define MAX_PACKET_DATA_LEN 255 -#define MAX_PACKET_BUF_SIZE (1+1+MAX_PACKET_DATA_LEN+2) -#define UART_BUFFER_SIZE 1024 -uint8_t rx_buffer[UART_BUFFER_SIZE] __attribute__ ((aligned(4))); -// align to 32-bit to try and provide speed improvement; -// master buffers... -uint8_t SSP_TxBuf[MAX_PACKET_BUF_SIZE]; -uint8_t SSP_RxBuf[MAX_PACKET_BUF_SIZE]; -void SSP_CallBack(uint8_t *buf, uint16_t len); -int16_t SSP_SerialRead(void); -void SSP_SerialWrite( uint8_t); -uint32_t SSP_GetTime(void); -PortConfig_t SSP_PortConfig = { .rxBuf = SSP_RxBuf, - .rxBufSize = MAX_PACKET_DATA_LEN, .txBuf = SSP_TxBuf, - .txBufSize = MAX_PACKET_DATA_LEN, .max_retry = 10, .timeoutLen = 1000, - .pfCallBack = SSP_CallBack, .pfSerialRead = SSP_SerialRead, - .pfSerialWrite = SSP_SerialWrite, .pfGetTime = SSP_GetTime, }; -Port_t ssp_port; -t_fifo_buffer ssp_buffer; - -/* Extern variables ----------------------------------------------------------*/ -DFUStates DeviceState; -DFUPort ProgPort; -int16_t status = 0; -uint8_t JumpToApp = FALSE; -uint8_t GO_dfu = FALSE; -uint8_t USB_connected = FALSE; -uint8_t User_DFU_request = FALSE; -static uint8_t mReceive_Buffer[63]; -/* Private function prototypes -----------------------------------------------*/ -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); -uint8_t processRX(); -void jump_to_app(); -uint32_t sspTimeSource(); - -#define LED_PWM_TIMER TIM6 -int main() { - PIOS_SYS_Init(); - if (BSL_HOLD_STATE == 0) - USB_connected = TRUE; - - PIOS_IAP_Init(); - - if (PIOS_IAP_CheckRequest() == TRUE) { - PIOS_Board_Init(); - PIOS_DELAY_WaitmS(1000); - User_DFU_request = TRUE; - PIOS_IAP_ClearRequest(); - } - - GO_dfu = (USB_connected == TRUE) || (User_DFU_request == TRUE); - - if (GO_dfu == TRUE) { - if (USB_connected) - ProgPort = Usb; - else - ProgPort = Serial; - PIOS_Board_Init(); - if (User_DFU_request == TRUE) - DeviceState = DFUidle; - else - DeviceState = BLidle; - STOPWATCH_Init(100, LED_PWM_TIMER); - if (ProgPort == Serial) { - fifoBuf_init(&ssp_buffer, rx_buffer, UART_BUFFER_SIZE); - STOPWATCH_Init(100, SSP_TIMER);//nao devia ser 1000? - STOPWATCH_Reset(SSP_TIMER); - ssp_Init(&ssp_port, &SSP_PortConfig); - } - PIOS_OPAHRS_ForceSlaveSelected(true); - } else - JumpToApp = TRUE; - - STOPWATCH_Reset(LED_PWM_TIMER); - while (TRUE) { - if (ProgPort == Serial) { - ssp_ReceiveProcess(&ssp_port); - status = ssp_SendProcess(&ssp_port); - while ((status != SSP_TX_IDLE) && (status != SSP_TX_ACKED)) { - ssp_ReceiveProcess(&ssp_port); - status = ssp_SendProcess(&ssp_port); - } - } - if (JumpToApp == TRUE) - jump_to_app(); - //pwm_period = 50; // *100 uS -> 5 mS - //pwm_sweep_steps =100; // * 5 mS -> 500 mS - - switch (DeviceState) { - case Last_operation_Success: - case uploadingStarting: - case DFUidle: - period1 = 50; - sweep_steps1 = 100; - PIOS_LED_Off(PIOS_LED_ALARM); - period2 = 0; - break; - case uploading: - period1 = 50; - sweep_steps1 = 100; - period2 = 25; - sweep_steps2 = 50; - break; - case downloading: - period1 = 25; - sweep_steps1 = 50; - PIOS_LED_Off(PIOS_LED_ALARM); - period2 = 0; - break; - case BLidle: - period1 = 0; - PIOS_LED_On(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - default://error - period1 = 50; - sweep_steps1 = 100; - period2 = 50; - sweep_steps2 = 100; - } - - if (period1 != 0) { - if (LedPWM(period1, sweep_steps1, STOPWATCH_ValueGet(LED_PWM_TIMER))) - PIOS_LED_On(PIOS_LED_HEARTBEAT); - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else - PIOS_LED_On(PIOS_LED_HEARTBEAT); - - if (period2 != 0) { - if (LedPWM(period2, sweep_steps2, STOPWATCH_ValueGet(LED_PWM_TIMER))) - PIOS_LED_On(PIOS_LED_ALARM); - else - PIOS_LED_Off(PIOS_LED_ALARM); - } else - PIOS_LED_Off(PIOS_LED_ALARM); - - if (STOPWATCH_ValueGet(LED_PWM_TIMER) > 100 * 50 * 100) - STOPWATCH_Reset(LED_PWM_TIMER); - if ((STOPWATCH_ValueGet(LED_PWM_TIMER) > 60000) && (DeviceState - == BLidle)) - JumpToApp = TRUE; - - processRX(); - DataDownload(start); - } -} - -void jump_to_app() { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - - if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ - FLASH_Lock(); - RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); - RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); - _SetCNTR(0); // clear interrupt mask - _SetISTR(0); // clear all requests - JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); - Jump_To_Application = (pFunction) JumpAddress; - /* Initialize user application's Stack Pointer */ - __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); - Jump_To_Application(); - } else { - DeviceState = failed_jump; - return; - } -} -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { - uint32_t pwm_duty = ((count / pwm_period) % pwm_sweep_steps) - / (pwm_sweep_steps / pwm_period); - if ((count % (2 * pwm_period * pwm_sweep_steps)) > pwm_period - * pwm_sweep_steps) - pwm_duty = pwm_period - pwm_duty; // negative direction each 50*100 ticks - return ((count % pwm_period) > pwm_duty) ? 1 : 0; -} - -uint8_t processRX() { - if (ProgPort == Usb) { - if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { - processComand(mReceive_Buffer); - } - } else if (ProgPort == Serial) { - - if (fifoBuf_getUsed(&ssp_buffer) >= 63) { - for (int32_t x = 0; x < 63; ++x) { - mReceive_Buffer[x] = fifoBuf_getByte(&ssp_buffer); - } - processComand(mReceive_Buffer); - } - } - return TRUE; -} - -uint32_t sspTimeSource() { - if (STOPWATCH_ValueGet(SSP_TIMER) > 5000) { - ++ssp_time; - STOPWATCH_Reset(SSP_TIMER); - } - return ssp_time; -} -void SSP_CallBack(uint8_t *buf, uint16_t len) { - fifoBuf_putData(&ssp_buffer, buf, len); -} -int16_t SSP_SerialRead(void) { - uint8_t byte; - if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_RF, &byte, 1, 0) == 1) { - return byte; - } else { - return -1; - } -} -void SSP_SerialWrite(uint8_t value) { - PIOS_COM_SendChar(PIOS_COM_TELEM_RF, value); -} -uint32_t SSP_GetTime(void) { - return sspTimeSource(); -} diff --git a/flight/Bootloaders/OpenPilot/pios_board.c b/flight/Bootloaders/OpenPilot/pios_board.c deleted file mode 100644 index beee6ea7f..000000000 --- a/flight/Bootloaders/OpenPilot/pios_board.c +++ /dev/null @@ -1,128 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @{ - * - * @file pios_board.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board specific static initialisers for hardware for the OpenPilot board. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Pull in the board-specific static HW definitions. - * Including .c files is a bit ugly but this allows all of - * the HW definitions to be const and static to limit their - * scope. - * - * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE - */ -#include "board_hw_defs.c" - -#include - -#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192 -#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192 - -static uint8_t pios_com_telem_rf_rx_buffer[PIOS_COM_TELEM_RF_RX_BUF_LEN]; -static uint8_t pios_com_telem_rf_tx_buffer[PIOS_COM_TELEM_RF_TX_BUF_LEN]; - -uint32_t pios_com_telem_rf_id; -uint32_t pios_com_telem_usb_id; - -#include "pios_opahrs.h" - -/** - * PIOS_Board_Init() - * initializes all the core subsystems on this specific hardware - * called from System/openpilot.c - */ -static bool board_init_complete = false; -void PIOS_Board_Init(void) { - if (board_init_complete) { - return; - } - - /* Enable Prefetch Buffer */ - FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable); - - /* Flash 2 wait state */ - FLASH_SetLatency(FLASH_Latency_2); - - /* Delay system */ - PIOS_DELAY_Init(); - - /* Initialize the PiOS library */ -#if defined(PIOS_INCLUDE_COM) - uint32_t pios_usart_telem_rf_id; - if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) { - PIOS_DEBUG_Assert(0); - } - if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, - pios_usart_telem_rf_id, - pios_com_telem_rf_rx_buffer, sizeof(pios_com_telem_rf_rx_buffer), - pios_com_telem_rf_tx_buffer, sizeof(pios_com_telem_rf_tx_buffer))) { - PIOS_DEBUG_Assert(0); - } -#endif /* PIOS_INCLUDE_COM */ - - PIOS_GPIO_Init(); - -#if defined(PIOS_INCLUDE_LED) - PIOS_LED_Init(&pios_led_cfg); -#endif /* PIOS_INCLUDE_LED */ - -#if defined(PIOS_INCLUDE_USB) - /* Initialize board specific USB data */ - PIOS_USB_BOARD_DATA_Init(); - - /* Activate the HID-only USB configuration */ - PIOS_USB_DESC_HID_ONLY_Init(); - - uint32_t pios_usb_id; - if (PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg)) { - PIOS_Assert(0); - } -#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG) - uint32_t pios_usb_hid_id; - if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) { - PIOS_Assert(0); - } -#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */ - -#endif /* PIOS_INCLUDE_USB */ - - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);//TODO Tirar - - /* Set up the SPI interface to the AHRS */ - if (PIOS_SPI_Init(&pios_spi_ahrs_id, &pios_spi_ahrs_cfg)) { - PIOS_DEBUG_Assert(0); - } - - /* Bind the AHRS comms layer to the AHRS SPI link */ - PIOS_OPAHRS_Attach(pios_spi_ahrs_id); - - board_init_complete = true; -} - -/** - * @} - */ diff --git a/flight/Bootloaders/OpenPilot/ssp.c b/flight/Bootloaders/OpenPilot/ssp.c deleted file mode 100644 index df052bbaf..000000000 --- a/flight/Bootloaders/OpenPilot/ssp.c +++ /dev/null @@ -1,821 +0,0 @@ -/*********************************************************************************************************** - * - * NAME: ssp.c - * DESCRIPTION: simple serial protocol - packet based serial transport layer. - * AUTHOR: Joe Hlebasko - * HISTORY: Created 1/1/2010 - * - * Packet Formats - * Format: - * +------+----+------+---------------------------+--------+ - * | 225 | L1 | S# | App Data (0-254 bytes) | CRC 16 | - * +------+----+------+---------------------------+--------+ - * - * 225 = sync byte, indicates start of a packet - * L1 = 1 byte for size of data payload. (sequence number is part of data payload.) - * S# = 1 byte for sequence number. - * Seq of 0 = seq # synchronise request, forces other end to reset receive sequence number to 1. - * sender of synchronise request will reset the tx seq number to 1 - * Seq # of 1..127 = normal data packets. Sequence number is incremented by for each transmitted - * packet. Rolls over from 127 to 1. - * if most sig. bit is set then the packet is an ACK packet of data packet sequence number of the - * lower 7 bits (1..127) - * App Data may contain 0..254 bytes. The sequence number is consider part of the payload. - * CRC 16 - 16 bits of CRC values of Sequence # and data bytes. - * - * Protocol has two types of packets: data and ack packets. ACK packets have the most sig. bit set in the - * sequence number, this implies that valid sequence numbers are 1..127 - * - * This protocol uses the concept of sequences numbers to determine if a given packet has been received. This - * requires both devices to be able to synchronize sequence numbers. This is accomplished by sending a packet - * length 1 and sequence number = 0. The receive then resets it's transmit sequence number to 1. - * - * ACTIVE_SYNCH is a version that will automatically send a synch request if it receives a synch packet. Only - * one device in the communication should do otherwise you end up with an endless loops of synchronization. - * Right now each side needs to manually issues a synch request. - * - * This protocol is best used in cases where one device is the master and the other is the slave, or a don't - * speak unless spoken to type of approach. - * - * The following are items are required to initialize a port for communications: - * 1. The number attempts for each packet - * 2. time to wait for an ack. - * 3. pointer to buffer to be used for receiving. - * 4. pointer to a buffer to be used for transmission - * 5. length of each buffer (rx and tx) - * 6. Four functions: - * 1. write byte = writes a byte out the serial port (or other comm device) - * 2. read byte = retrieves a byte from the serial port. Returns -1 if a byte is not available - * 3. callback = function to call when a valid data packet has been received. This function is responsible - * to do what needs to be done with the data when it is received. The primary mission of this function - * should be to copy the data to a private buffer out of the working receive buffer to prevent overrun. - * processing should be kept to a minimum. - * 4. get time = function should return the current time. Note that time units are not specified it just - * needs to be some measure of time that increments as time passes by. The timeout values for a given - * port should the units used/returned by the get time function. - * - * All of the state information of a communication port is contained in a Port_t structure. This allows this - * module to operature on multiple communication ports with a single code base. - * - * The ssp_ReceiveProcess and ssp_SendProcess functions need to be called to process data through the - * respective state machines. Typical implementation would have a serial ISR to pull bytes out of the UART - * and place into a circular buffer. The serial read function would then pull bytes out this buffer - * processing. The TX side has the write function placing bytes into a circular buffer with the TX ISR - * pulling bytes out of the buffer and putting into the UART. It is possible to run the receive process from - * the receive ISR but care must be taken on processing data when it is received to avoid holding up the ISR - * and sending ACK packets from the receive ISR. - * - ***********************************************************************************************************/ - -/** INCLUDE FILES **/ - -#include -#include -#include -#include -#include "ssp.h" -/** PRIVATE DEFINITIONS **/ -#define SYNC 225 // Sync character used in Serial Protocol -#define ESC 224 // ESC character used in Serial Protocol -#define ESC_SYNC 1 // ESC_SYNC character used in Serial Protocol -#define ACK_BIT 0x80 // Ack bit, bit 7 of sequence number, 1 = Acknowledge, 0 = -// new packet -// packet location definitions. -#define LENGTH 0 -#define SEQNUM 1 -#define DATA 2 - -// Make larger sized integers from smaller sized integers -#define MAKEWORD16( ub, lb ) ((uint16_t)0x0000 | ((uint16_t)(ub) << 8) | (uint16_t)(lb) ) -#define MAKEWORD32( uw, lw ) ((uint32_t)(0x0UL | ((uint32_t)(uw) << 16) | (uint32_t)(lw)) ) -#define MAKEWORD32B( b3, b2, b1, b0 ) ((uint32_t)((uint32_t)(b3)<< 24) | ((uint32_t)(b2)<<16) | ((uint32_t)(b1)<<8) | ((uint32_t)(b0) ) - -// Used to extract smaller integers from larger sized intergers -#define LOWERBYTE( w ) (uint8_t)((w) & 0x00ff ) -#define UPPERBYTE( w ) (uint8_t)(((w) & 0xff00) >> 8 ) -#define UPPERWORD(lw) (uint16_t)(((lw) & 0xffff0000) >> 16 ) -#define LOWERWORD(lw) (uint16_t)((lw) & 0x0000ffff) - -// Macros to operate on a target and bitmask. -#define CLEARBIT( a, b ) ((a) = (a) & ~(b)) -#define SETBIT( a, b ) ((a) = (a) | (b) ) -#define TOGGLEBIT(a,b) ((a) = (a) ^ (b) ) - -// test bit macros operate using a bit mask. -#define ISBITSET( a, b ) ( ((a) & (b)) == (b) ? TRUE : FALSE ) -#define ISBITCLEAR( a, b) ( (~(a) & (b)) == (b) ? TRUE : FALSE ) - -/** PRIVATE FUNCTIONS **/ -//static void sf_SendSynchPacket( Port_t *thisport ); -static uint16_t sf_crc16(uint16_t crc, uint8_t data); -static void sf_write_byte(Port_t *thisport, uint8_t c); -static void sf_SetSendTimeout(Port_t *thisport); -static uint16_t sf_CheckTimeout(Port_t *thisport); -static int16_t sf_DecodeState(Port_t *thisport, uint8_t c); -static int16_t sf_ReceiveState(Port_t *thisport, uint8_t c); - -static void sf_SendPacket(Port_t *thisport); -static void sf_SendAckPacket(Port_t *thisport, uint8_t seqNumber); -static void sf_MakePacket(uint8_t *buf, const uint8_t * pdata, uint16_t length, - uint8_t seqNo); -static int16_t sf_ReceivePacket(Port_t *thisport); - -/* Flag bit masks...*/ -#define SENT_SYNCH (0x01) -#define ACK_RECEIVED (0x02) -#define ACK_EXPECTED (0x04) - -#define SSP_AWAITING_ACK 0 -#define SSP_ACKED 1 -#define SSP_IDLE 2 - -/** PRIVATE DATA **/ -static const uint16_t CRC_TABLE[] = { 0x0000, 0xC0C1, 0xC181, 0x0140, 0xC301, - 0x03C0, 0x0280, 0xC241, 0xC601, 0x06C0, 0x0780, 0xC741, 0x0500, 0xC5C1, - 0xC481, 0x0440, 0xCC01, 0x0CC0, 0x0D80, 0xCD41, 0x0F00, 0xCFC1, 0xCE81, - 0x0E40, 0x0A00, 0xCAC1, 0xCB81, 0x0B40, 0xC901, 0x09C0, 0x0880, 0xC841, - 0xD801, 0x18C0, 0x1980, 0xD941, 0x1B00, 0xDBC1, 0xDA81, 0x1A40, 0x1E00, - 0xDEC1, 0xDF81, 0x1F40, 0xDD01, 0x1DC0, 0x1C80, 0xDC41, 0x1400, 0xD4C1, - 0xD581, 0x1540, 0xD701, 0x17C0, 0x1680, 0xD641, 0xD201, 0x12C0, 0x1380, - 0xD341, 0x1100, 0xD1C1, 0xD081, 0x1040, 0xF001, 0x30C0, 0x3180, 0xF141, - 0x3300, 0xF3C1, 0xF281, 0x3240, 0x3600, 0xF6C1, 0xF781, 0x3740, 0xF501, - 0x35C0, 0x3480, 0xF441, 0x3C00, 0xFCC1, 0xFD81, 0x3D40, 0xFF01, 0x3FC0, - 0x3E80, 0xFE41, 0xFA01, 0x3AC0, 0x3B80, 0xFB41, 0x3900, 0xF9C1, 0xF881, - 0x3840, 0x2800, 0xE8C1, 0xE981, 0x2940, 0xEB01, 0x2BC0, 0x2A80, 0xEA41, - 0xEE01, 0x2EC0, 0x2F80, 0xEF41, 0x2D00, 0xEDC1, 0xEC81, 0x2C40, 0xE401, - 0x24C0, 0x2580, 0xE541, 0x2700, 0xE7C1, 0xE681, 0x2640, 0x2200, 0xE2C1, - 0xE381, 0x2340, 0xE101, 0x21C0, 0x2080, 0xE041, 0xA001, 0x60C0, 0x6180, - 0xA141, 0x6300, 0xA3C1, 0xA281, 0x6240, 0x6600, 0xA6C1, 0xA781, 0x6740, - 0xA501, 0x65C0, 0x6480, 0xA441, 0x6C00, 0xACC1, 0xAD81, 0x6D40, 0xAF01, - 0x6FC0, 0x6E80, 0xAE41, 0xAA01, 0x6AC0, 0x6B80, 0xAB41, 0x6900, 0xA9C1, - 0xA881, 0x6840, 0x7800, 0xB8C1, 0xB981, 0x7940, 0xBB01, 0x7BC0, 0x7A80, - 0xBA41, 0xBE01, 0x7EC0, 0x7F80, 0xBF41, 0x7D00, 0xBDC1, 0xBC81, 0x7C40, - 0xB401, 0x74C0, 0x7580, 0xB541, 0x7700, 0xB7C1, 0xB681, 0x7640, 0x7200, - 0xB2C1, 0xB381, 0x7340, 0xB101, 0x71C0, 0x7080, 0xB041, 0x5000, 0x90C1, - 0x9181, 0x5140, 0x9301, 0x53C0, 0x5280, 0x9241, 0x9601, 0x56C0, 0x5780, - 0x9741, 0x5500, 0x95C1, 0x9481, 0x5440, 0x9C01, 0x5CC0, 0x5D80, 0x9D41, - 0x5F00, 0x9FC1, 0x9E81, 0x5E40, 0x5A00, 0x9AC1, 0x9B81, 0x5B40, 0x9901, - 0x59C0, 0x5880, 0x9841, 0x8801, 0x48C0, 0x4980, 0x8941, 0x4B00, 0x8BC1, - 0x8A81, 0x4A40, 0x4E00, 0x8EC1, 0x8F81, 0x4F40, 0x8D01, 0x4DC0, 0x4C80, - 0x8C41, 0x4400, 0x84C1, 0x8581, 0x4540, 0x8701, 0x47C0, 0x4680, 0x8641, - 0x8201, 0x42C0, 0x4380, 0x8341, 0x4100, 0x81C1, 0x8081, 0x4040 }; - -/** EXTERNAL DATA **/ - -/** EXTERNAL FUNCTIONS **/ - -/** VERIFICATION FUNCTIONS **/ - -/***********************************************************************************************************/ - -/*! - * \brief Initializes the communication port for use - * \param thisport = pointer to port structure to initialize - * \param info = config struct with default values. - * \return None. - * - * \note - * Must be called before calling the Send or REceive process functions. - */ - -void ssp_Init(Port_t *thisport, const PortConfig_t* const info) { - thisport->pfCallBack = info->pfCallBack; - thisport->pfSerialRead = info->pfSerialRead; - thisport->pfSerialWrite = info->pfSerialWrite; - thisport->pfGetTime = info->pfGetTime; - - thisport->maxRetryCount = info->max_retry; - thisport->timeoutLen = info->timeoutLen; - thisport->txBufSize = info->txBufSize; - thisport->rxBufSize = info->rxBufSize; - thisport->txBuf = info->txBuf; - thisport->rxBuf = info->rxBuf; - thisport->retryCount = 0; - thisport->sendSynch = FALSE; //TRUE; - thisport->rxSeqNo = 255; - thisport->txSeqNo = 255; - thisport->SendState = SSP_IDLE; -} - -/*! - * \brief Runs the send process, checks for receipt of ack, timeouts and resends if needed. - * \param thisport = which port to use - * \return SSP_TX_WAITING - waiting for a valid ACK to arrive - * \return SSP_TX_TIMEOUT - failed to receive a valid ACK in the timeout period, after retrying. - * \return SSP_TX_IDLE - not expecting a ACK packet (no current transmissions in progress) - * \return SSP_TX_ACKED - valid ACK received before timeout period. - * - * \note - * - */ -int16_t ssp_SendProcess(Port_t *thisport) { - int16_t value = SSP_TX_WAITING; - - if (thisport->SendState == SSP_AWAITING_ACK) { - if (sf_CheckTimeout(thisport) == TRUE) { - if (thisport->retryCount < thisport->maxRetryCount) { - // Try again - sf_SendPacket(thisport); - sf_SetSendTimeout(thisport); - value = SSP_TX_WAITING; - } else { - // Give up, # of trys has exceded the limit -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Send Timeout|"); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - value = SSP_TX_TIMEOUT; - CLEARBIT( thisport->flags, ACK_RECEIVED); - thisport->SendState = SSP_IDLE; - } - } else { - value = SSP_TX_WAITING; - } - } else if (thisport->SendState == SSP_ACKED) { - SETBIT( thisport->flags, ACK_RECEIVED); - value = SSP_TX_ACKED; - thisport->SendState = SSP_IDLE; - } else { - thisport->SendState = SSP_IDLE; - value = SSP_TX_IDLE; - } - return value; -} - -/*! - * \brief Runs the receive process. fetches a byte at a time and runs the byte through the protocol receive state machine. - * \param thisport - which port to use. - * \return receive status. - * - * \note - * - */ -int16_t ssp_ReceiveProcess(Port_t *thisport) { - int16_t b; - int16_t packet_status = SSP_RX_IDLE; - - do { - b = thisport->pfSerialRead(); // attempt to read a char from the serial buffer - if (b != -1) { - packet_status = sf_ReceiveState(thisport, b); // process the newly received byte in the receive state machine - } - // keep going until either we received a full packet or there are no more bytes to process - } while (packet_status != SSP_RX_COMPLETE && b != -1); - return packet_status; -} - -/*! - * \brief processes a single byte through the receive state machine. - * \param thisport = which port to use - * \return current receive status - * - * \note - * - */ - -int16_t ssp_ReceiveByte(Port_t *thisport) { - int16_t b; - int16_t packet_status = SSP_RX_IDLE; - - b = thisport->pfSerialRead(); - if (b != -1) { - packet_status = sf_ReceiveState(thisport, b); - } - return packet_status; -} - -/*! - * \brief Sends a data packet and blocks until timeout or ack is received. - * \param thisport = which port to use - * \param data = pointer to data to send - * \param length = number of data bytes to send. Must be less than 254 - * \return true = ack was received within number of retries - * \return false = ack was not received. - * - * \note - * - */ -uint16_t ssp_SendDataBlock(Port_t *thisport, uint8_t *data, uint16_t length) { - int16_t packet_status = SSP_TX_WAITING; - uint16_t retval = FALSE; - - packet_status = ssp_SendData(thisport, data, length); // send the data - while (packet_status == SSP_TX_WAITING) { // check the status - (void) ssp_ReceiveProcess(thisport); // process any bytes received. - packet_status = ssp_SendProcess(thisport); // check the send status - } - if (packet_status == SSP_TX_ACKED) { // figure out what happened to the packet - retval = TRUE; - } else { - retval = FALSE; - } - return retval; -} - -/*! - * \brief sends a chunk of data and does not block - * \param thisport = which port to use - * \param data = pointer to data to send - * \param length = number of bytes to send - * \return SSP_TX_BUFOVERRUN = tried to send too much data - * \return SSP_TX_WAITING = data sent and waiting for an ack to arrive - * \return SSP_TX_BUSY = a packet has already been sent, but not yet acked - * - * \note - * - */ -int16_t ssp_SendData(Port_t *thisport, const uint8_t *data, - const uint16_t length) { - - int16_t value = SSP_TX_WAITING; - - if ((length + 2) > thisport->txBufSize) { - // TRYING to send too much data. - value = SSP_TX_BUFOVERRUN; - } else if (thisport->SendState == SSP_IDLE) { -#ifdef ACTIVE_SYNCH - if( thisport->sendSynch == TRUE ) { - sf_SendSynchPacket(thisport); - } -#endif - -#ifdef SYNCH_SEND - if( length == 0 ) { - // TODO this method could allow a task/user to start a synchronisation step if a zero is mistakenly passed to this function. - // could add a check for a NULL data pointer, or use some sort of static flag that can only be accessed by a static function - // that must be called before calling this function. - // we are attempting to send a synch packet - thisport->txSeqNo = 0; // make this zero to cause the other end to re-synch with us - SETBIT(thisport->flags, SENT_SYNCH); - } else { - // we are sending a data packet - CLEARBIT( thisport->txSeqNo, ACK_BIT ); // make sure we are not sending a ACK packet - thisport->txSeqNo++; // update the sequence number. - if( thisport->txSeqNo > 0x7F) { // check for sequence number rollover - thisport->txSeqNo = 1; // if we do have rollover then reset to 1 not zero, - // zero is reserviced for synchronization requests - } - } - -#else - CLEARBIT( thisport->txSeqNo, ACK_BIT ); // make sure we are not sending a ACK packet - thisport->txSeqNo++; // update the sequence number. - if (thisport->txSeqNo > 0x7F) { // check for sequence number rollover - thisport->txSeqNo = 1; // if we do have rollover then reset to 1 not zero, - // zero is reserved for synchronization requests - } -#endif - CLEARBIT( thisport->flags, ACK_RECEIVED); - thisport->SendState = SSP_AWAITING_ACK; - value = SSP_TX_WAITING; - thisport->retryCount = 0; // zero out the retry counter for this transmission - sf_MakePacket(thisport->txBuf, data, length, thisport->txSeqNo); - sf_SendPacket(thisport); // punch out the packet to the serial port - sf_SetSendTimeout(thisport); // do the timeout values -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Sent DATA PACKET:%d|",thisport->txSeqNo); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - } else { - // error we are already sending a packet. Need to wait for the current packet to be acked or timeout. -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Error sending TX was busy|"); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - value = SSP_TX_BUSY; - } - return value; -} - -/*! - * \brief Attempts to synchronize the sequence numbers with the other end of the connectin. - * \param thisport = which port to use - * \return true = success - * \return false = failed to receive an ACK to our synch request - * - * \note - * A. send a packet with a sequence number equal to zero - * B. if timed out then: - * send synch packet again - * increment try counter - * if number of tries exceed maximum try limit then exit - * C. goto A - */ -uint16_t ssp_Synchronise(Port_t *thisport) { - int16_t packet_status; - uint16_t retval = FALSE; - -#ifndef USE_SENDPACKET_DATA - thisport->txSeqNo = 0; // make this zero to cause the other end to re-synch with us - SETBIT(thisport->flags, SENT_SYNCH); - // TODO - should this be using ssp_SendPacketData()?? - sf_MakePacket(thisport->txBuf, NULL, 0, thisport->txSeqNo); // construct the packet - sf_SendPacket(thisport); - sf_SetSendTimeout(thisport); - thisport->SendState = SSP_AWAITING_ACK; - packet_status = SSP_TX_WAITING; -#else - packet_status = ssp_SendData( thisport, NULL, 0 ); -#endif - while (packet_status == SSP_TX_WAITING) { // we loop until we time out. - (void) ssp_ReceiveProcess(thisport); // do the receive process - packet_status = ssp_SendProcess(thisport); // do the send process - } - thisport->sendSynch = FALSE; - switch (packet_status) { - case SSP_TX_ACKED: - retval = TRUE; - break; - case SSP_TX_BUSY: // intentional fall through. - case SSP_TX_TIMEOUT: // intentional fall through. - case SSP_TX_BUFOVERRUN: - retval = FALSE; - break; - default: - retval = FALSE; - break; - }; - return retval; -} - -/*! - * \brief sends out a preformatted packet for a give port - * \param thisport = which port to use. - * \return none. - * - * \note - * Packet should be formed through the use of sf_MakePacket before calling this function. - */ -static void sf_SendPacket(Port_t *thisport) { - // add 3 to packet data length for: 1 length + 2 CRC (packet overhead) - uint8_t packetLen = thisport->txBuf[LENGTH] + 3; - - // use the raw serial write function so the SYNC byte does not get 'escaped' - thisport->pfSerialWrite(SYNC); - for (uint8_t x = 0; x < packetLen; x++) { - sf_write_byte(thisport, thisport->txBuf[x]); - } - thisport->retryCount++; -} - -/*! - * \brief converts data to transport layer protocol packet format. - * \param txbuf = buffer to use when forming the packet - * \param pdata = pointer to data to use - * \param length = number of bytes to use - * \param seqNo = sequence number of this packet - * \return none. - * - * \note - * 1. This function does not try to interpret ACK or SYNCH packets. This should - * be done by the caller of this function. - * 2. This function will attempt to format all data upto the size of the tx buffer. - * Any extra data beyond that will be ignored. - * 3. TODO: Should this function return an error if data length to be sent is greater th tx buffer size? - * - */ -void sf_MakePacket(uint8_t *txBuf, const uint8_t * pdata, uint16_t length, - uint8_t seqNo) { - uint16_t crc = 0xffff; - uint16_t bufPos = 0; - uint8_t b; - - // add 1 for the seq. number - txBuf[LENGTH] = length + 1; - txBuf[SEQNUM] = seqNo; - crc = sf_crc16(crc, seqNo); - - length = length + 2; // add two for the length and seqno bytes which are added before the loop. - for (bufPos = 2; bufPos < length; bufPos++) { - b = *pdata++; - txBuf[bufPos] = b; - crc = sf_crc16(crc, b); // update CRC value - } - txBuf[bufPos++] = LOWERBYTE(crc); - txBuf[bufPos] = UPPERBYTE(crc); - -} - -/*! - * \brief sends out an ack packet to given sequence number - * \param thisport = which port to use - * \param seqNumber = sequence number of the packet we would like to ack - * \return none. - * - * \note - * - */ - -static void sf_SendAckPacket(Port_t *thisport, uint8_t seqNumber) { -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Sent ACK PACKET:%d|",seqNumber); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - uint8_t AckSeqNumber = SETBIT( seqNumber, ACK_BIT ); - - // create the packet, note we pass AckSequenceNumber directly - sf_MakePacket(thisport->txBuf, NULL, 0, AckSeqNumber); - sf_SendPacket(thisport); - // we don't set the timeout for an ACK because we don't ACK our ACKs in this protocol -} - -/*! - * \brief writes a byte out the output channel. Adds escape byte where needed - * \param thisport = which port to use - * \param c = byte to send - * \return none. - * - * \note - * - */ -static void sf_write_byte(Port_t *thisport, uint8_t c) { - if (c == SYNC) { // check for SYNC byte - thisport->pfSerialWrite(ESC); // since we are not starting a packet we must ESCAPE the SYNCH byte - thisport->pfSerialWrite(ESC_SYNC); // now send the escaped synch char - } else if (c == ESC) { // Check for ESC character - thisport->pfSerialWrite(ESC); // if it is, we need to send it twice - thisport->pfSerialWrite(ESC); - } else { - thisport->pfSerialWrite(c); // otherwise write the byte to serial port - } -} - -/************************************************************************************************************ - * - * NAME: uint16_t ssp_crc16( uint16_t crc, uint16_t data ) - * DESCRIPTION: Uses crc_table to calculate new crc - * ARGUMENTS: - * arg1: crc - * arg2: data - byte to calculate into CRC - * RETURN: New crc - * CREATED: 5/8/02 - * - *************************************************************************************************************/ -/*! - * \brief calculates the new CRC value for 'data' - * \param crc = current CRC value - * \param data = new byte - * \return updated CRC value - * - * \note - * - */ - -static uint16_t sf_crc16(uint16_t crc, uint8_t data) { - return (crc >> 8) ^ CRC_TABLE[(crc ^ data) & 0x00FF]; -} - -/*! - * \brief sets the timeout for the given packet - * \param thisport = which port to use - * \return none. - * - * \note - * - */ - -static void sf_SetSendTimeout(Port_t *thisport) { - uint32_t timeout; - timeout = thisport->pfGetTime() + thisport->timeoutLen; - thisport->timeout = timeout; -} - -/*! - * \brief checks to see if a timeout occured - * \param thisport = which port to use - * \return true = a timeout has occurred - * \return false = has not timed out - * - * \note - * - */ -static uint16_t sf_CheckTimeout(Port_t *thisport) { - uint16_t retval = FALSE; - uint32_t current_time; - - current_time = thisport->pfGetTime(); - if (current_time > thisport->timeout) { - retval = TRUE; - } - return retval; -} - -/**************************************************************************** - * NAME: sf_ReceiveState - * DESC: Implements the receive state handling code for escaped and unescaped data - * ARGS: thisport - which port to operate on - * c - incoming byte - * RETURN: - * CREATED: - * NOTES: - * 1. change from using pointer to functions. - ****************************************************************************/ -/*! - * \brief implements the receive state handling code for escaped and unescaped data - * \param thisport = which port to use - * \param c = byte to process through the receive state machine - * \return receive status - * - * \note - * - */ -static int16_t sf_ReceiveState(Port_t *thisport, uint8_t c) { - int16_t retval = SSP_RX_RECEIVING; - - switch (thisport->InputState) { - case state_unescaped_e: - if (c == SYNC) { - thisport->DecodeState = decode_len1_e; - } else if (c == ESC) { - thisport->InputState = state_escaped_e; - } else { - retval = sf_DecodeState(thisport, c); - } - break; // end of unescaped state. - case state_escaped_e: - thisport->InputState = state_unescaped_e; - if (c == SYNC) { - thisport->DecodeState = decode_len1_e; - } else if (c == ESC_SYNC) { - retval = sf_DecodeState(thisport, SYNC); - } else { - retval = sf_DecodeState(thisport, c); - } - break; // end of the escaped state. - default: - break; - } - return retval; -} - -/**************************************************************************** - * NAME: sf_DecodeState - * DESC: Implements the receive state finite state machine - * ARGS: thisport - which port to operate on - * c - incoming byte - * RETURN: - * CREATED: - * NOTES: - * 1. change from using pointer to functions. - ****************************************************************************/ - -/*! - * \brief implements the receiving decoding state machine - * \param thisport = which port to use - * \param c = byte to process - * \return receive status - * - * \note - * - */ -static int16_t sf_DecodeState(Port_t *thisport, uint8_t c) { - int16_t retval; - switch (thisport->DecodeState) { - case decode_idle_e: - // 'c' is ignored in this state as the only way to leave the idle state is - // recognition of the SYNC byte in the sf_ReceiveState function. - retval = SSP_RX_IDLE; - break; - case decode_len1_e: - thisport->rxBuf[LENGTH] = c; - thisport->rxBufLen = c; - if (thisport->rxBufLen <= thisport->rxBufSize) { - thisport->DecodeState = decode_seqNo_e; - retval = SSP_RX_RECEIVING; - } else { - thisport->DecodeState = decode_idle_e; - retval = SSP_RX_IDLE; - } - break; - case decode_seqNo_e: - thisport->rxBuf[SEQNUM] = c; - thisport->crc = 0xffff; - thisport->rxBufLen--; // subtract 1 for the seq. no. - thisport->rxBufPos = 2; - - thisport->crc = sf_crc16(thisport->crc, c); - if (thisport->rxBufLen > 0) { - thisport->DecodeState = decode_data_e; - } else { - thisport->DecodeState = decode_crc1_e; - } - retval = SSP_RX_RECEIVING; - break; - case decode_data_e: - thisport->rxBuf[(thisport->rxBufPos)++] = c; - thisport->crc = sf_crc16(thisport->crc, c); - if (thisport->rxBufPos == (thisport->rxBufLen + 2)) { - thisport->DecodeState = decode_crc1_e; - } - retval = SSP_RX_RECEIVING; - break; - case decode_crc1_e: - thisport->crc = sf_crc16(thisport->crc, c); - thisport->DecodeState = decode_crc2_e; - retval = SSP_RX_RECEIVING; - break; - case decode_crc2_e: - thisport->DecodeState = decode_idle_e; - // verify the CRC value for the packet - if (sf_crc16(thisport->crc, c) == 0) { - // TODO shouldn't the return value of sf_ReceivePacket() be checked? - sf_ReceivePacket(thisport); - retval = SSP_RX_COMPLETE; - } else { - thisport->RxError++; - retval = SSP_RX_IDLE; - } - break; - default: - thisport->DecodeState = decode_idle_e; // unknown state so reset to idle state and wait for the next start of a packet. - retval = SSP_RX_IDLE; - break; - } - return retval; -} - -/************************************************************************************************************ - * - * NAME: int16_t sf_ReceivePacket( ) - * DESCRIPTION: Receive one packet, assumed that data is in rec.buff[] - * ARGUMENTS: - * RETURN: 0 . no new packet was received, could be ack or same packet - * 1 . new packet received - * SSP_PACKET_? - * SSP_PACKET_COMPLETE - * SSP_PACKET_ACK - * CREATED: 5/8/02 - * - *************************************************************************************************************/ -/*! - * \brief receive one packet. calls the callback function if needed. - * \param thisport = which port to use - * \return true = valid data packet received. - * \return false = otherwise - * - * \note - * - * Created: Oct 7, 2010 12:07:22 AM by joe - */ - -static int16_t sf_ReceivePacket(Port_t *thisport) { - int16_t value = FALSE; - - if (ISBITSET(thisport->rxBuf[SEQNUM], ACK_BIT )) { - // Received an ACK packet, need to check if it matches the previous sent packet - if ((thisport->rxBuf[SEQNUM] & 0x7F) == (thisport->txSeqNo & 0x7f)) { - // It matches the last packet sent by us - SETBIT( thisport->txSeqNo, ACK_BIT ); - thisport->SendState = SSP_ACKED; -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Received ACK:%d|",(thisport->txSeqNo & 0x7F)); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - value = FALSE; - } - // else ignore the ACK packet - } else { - // Received a 'data' packet, figure out what type of packet we received... - if (thisport->rxBuf[SEQNUM] == 0) { -#ifdef DEBUG_SSP - PIOS_COM_SendString(PIOS_COM_TELEM_USB,"Received SYNC Request|"); -#endif - // Synchronize sequence number with host -#ifdef ACTIVE_SYNCH - thisport->sendSynch = TRUE; -#endif - sf_SendAckPacket(thisport, thisport->rxBuf[SEQNUM]); - thisport->rxSeqNo = 0; - value = FALSE; - } else if (thisport->rxBuf[SEQNUM] == thisport->rxSeqNo) { - // Already seen this packet, just ack it, don't act on the packet. - sf_SendAckPacket(thisport, thisport->rxBuf[SEQNUM]); - value = FALSE; - } else { - //New Packet - thisport->rxSeqNo = thisport->rxBuf[SEQNUM]; - // Let the application do something with the data/packet. - if (thisport->pfCallBack != NULL) { -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Received DATA PACKET:%d [0]=%d %d %d|",thisport->rxSeqNo,(uint8_t)thisport->rxBuf[2],(uint8_t)thisport->rxBuf[3],(uint8_t)thisport->rxBuf[4]); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - // skip the first two bytes (length and seq. no.) in the buffer. - thisport->pfCallBack(&(thisport->rxBuf[2]), thisport->rxBufLen); - } - // after we send the ACK, it is possible for the host to send a new packet. - // Thus the application needs to copy the data and reset the receive buffer - // inside of thisport->pfCallBack() - sf_SendAckPacket(thisport, thisport->rxBuf[SEQNUM]); - value = TRUE; - } - } - return value; -} - diff --git a/flight/Bootloaders/OpenPilot/ssp_timer.c b/flight/Bootloaders/OpenPilot/ssp_timer.c deleted file mode 100644 index 3506923e5..000000000 --- a/flight/Bootloaders/OpenPilot/ssp_timer.c +++ /dev/null @@ -1,91 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @{ - * - * @file ssp_timer.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Timer functions to be used with the SSP. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -///////////////////////////////////////////////////////////////////////////// -// Include files -///////////////////////////////////////////////////////////////////////////// - -#include "stm32f10x_tim.h" - -///////////////////////////////////////////////////////////////////////////// -// Local definitions -///////////////////////////////////////////////////////////////////////////// - -#define SSP_TIMER_TIMER_BASE TIM7 -#define SSP_TIMER_TIMER_RCC RCC_APB1Periph_TIM7 - -uint32_t SSP_TIMER_Init(u32 resolution) { - // enable timer clock - if (SSP_TIMER_TIMER_RCC == RCC_APB2Periph_TIM1 || SSP_TIMER_TIMER_RCC - == RCC_APB2Periph_TIM8) - RCC_APB2PeriphClockCmd(SSP_TIMER_TIMER_RCC, ENABLE); - else - RCC_APB1PeriphClockCmd(SSP_TIMER_TIMER_RCC, ENABLE); - - // time base configuration - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - TIM_TimeBaseStructure.TIM_Period = 0xffff; // max period - TIM_TimeBaseStructure.TIM_Prescaler = (72 * resolution) - 1; // uS accuracy @ 72 MHz - TIM_TimeBaseStructure.TIM_ClockDivision = 0; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseInit(SSP_TIMER_TIMER_BASE, &TIM_TimeBaseStructure); - - // enable interrupt request - TIM_ITConfig(SSP_TIMER_TIMER_BASE, TIM_IT_Update, ENABLE); - - // start counter - TIM_Cmd(SSP_TIMER_TIMER_BASE, ENABLE); - - return 0; // no error -} - -///////////////////////////////////////////////////////////////////////////// -//! Resets the SSP_TIMER -//! \return < 0 on errors -///////////////////////////////////////////////////////////////////////////// -uint32_t SSP_TIMER_Reset(void) { - // reset counter - SSP_TIMER_TIMER_BASE->CNT = 1; // set to 1 instead of 0 to avoid new IRQ request - TIM_ClearITPendingBit(SSP_TIMER_TIMER_BASE, TIM_IT_Update); - - return 0; // no error -} - -///////////////////////////////////////////////////////////////////////////// -//! Returns current value of SSP_TIMER -//! \return 1..65535: valid SSP_TIMER value -//! \return 0xffffffff: counter overrun -///////////////////////////////////////////////////////////////////////////// -uint32_t SSP_TIMER_ValueGet(void) { - uint32_t value = SSP_TIMER_TIMER_BASE->CNT; - - if (TIM_GetITStatus(SSP_TIMER_TIMER_BASE, TIM_IT_Update) != RESET) - SSP_TIMER_Reset(); - - return value; -} - diff --git a/flight/Bootloaders/PipXtreme/Makefile b/flight/Bootloaders/PipXtreme/Makefile index a411b6403..5747a0511 100644 --- a/flight/Bootloaders/PipXtreme/Makefile +++ b/flight/Bootloaders/PipXtreme/Makefile @@ -86,6 +86,7 @@ RTOSDIR = $(APPLIBDIR)/FreeRTOS RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include DOXYGENDIR = ../Doc/Doxygen +HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME) # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files @@ -103,6 +104,8 @@ SRC += $(PIOSSTM32F10X)/pios_usart.c SRC += $(PIOSSTM32F10X)/pios_irq.c SRC += $(PIOSSTM32F10X)/pios_debug.c SRC += $(PIOSSTM32F10X)/pios_gpio.c +SRC += $(PIOSSTM32F10X)/pios_iap.c +SRC += $(PIOSSTM32F10X)/pios_bl_helper.c # PIOS USB related files (seperated to make code maintenance more easy) SRC += $(PIOSSTM32F10X)/pios_usb.c @@ -112,12 +115,11 @@ SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c SRC += $(OPSYSTEM)/pios_usb_board_data.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c +SRC += $(PIOSCOMMON)/pios_usb_util.c ## PIOS Hardware (Common) SRC += $(PIOSCOMMON)/pios_board_info.c SRC += $(PIOSCOMMON)/pios_com_msg.c -SRC += $(PIOSCOMMON)/pios_bl_helper.c -SRC += $(PIOSCOMMON)/pios_iap.c SRC += $(PIOSCOMMON)/printf-stdarg.c ## Libraries for flight calculations @@ -198,8 +200,7 @@ EXTRAINCDIRS += $(MSDDIR) EXTRAINCDIRS += $(RTOSINCDIR) EXTRAINCDIRS += $(APPLIBDIR) EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3 - - +EXTRAINCDIRS += $(HWDEFSINC) # List any extra directories to look for library files here. # Also add directories where the linker should search for @@ -416,7 +417,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/PipXtreme/inc/pios_usb_board_data.h b/flight/Bootloaders/PipXtreme/inc/pios_usb_board_data.h index 2e35f2fa4..f959c0e03 100644 --- a/flight/Bootloaders/PipXtreme/inc/pios_usb_board_data.h +++ b/flight/Bootloaders/PipXtreme/inc/pios_usb_board_data.h @@ -39,6 +39,7 @@ #define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_PIPXTREME #define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_PIPXTREME, USB_OP_BOARD_MODE_BL) +#define PIOS_USB_BOARD_SN_SUFFIX "+BL" /* * The bootloader uses a simplified report structure diff --git a/flight/Bootloaders/PipXtreme/main.c b/flight/Bootloaders/PipXtreme/main.c index 908589178..840009b77 100644 --- a/flight/Bootloaders/PipXtreme/main.c +++ b/flight/Bootloaders/PipXtreme/main.c @@ -70,14 +70,13 @@ uint8_t processRX(); void jump_to_app(); int main() { - PIOS_SYS_Init(); - if (BSL_HOLD_STATE == 0) - USB_connected = TRUE; - + PIOS_SYS_Init(); + PIOS_Board_Init(); PIOS_IAP_Init(); + + USB_connected = PIOS_USB_CableConnected(0); if (PIOS_IAP_CheckRequest() == TRUE) { - PIOS_Board_Init(); PIOS_DELAY_WaitmS(1000); User_DFU_request = TRUE; PIOS_IAP_ClearRequest(); diff --git a/flight/Bootloaders/PipXtreme/pios_board.c b/flight/Bootloaders/PipXtreme/pios_board.c index 60ec1db76..893dc35f9 100644 --- a/flight/Bootloaders/PipXtreme/pios_board.c +++ b/flight/Bootloaders/PipXtreme/pios_board.c @@ -23,97 +23,9 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include "board_hw_defs.c" #include -#if defined(PIOS_INCLUDE_LED) - -#include -static const struct pios_led pios_leds[] = { - [PIOS_LED_USB] = { - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Mode = GPIO_Mode_Out_PP, - .GPIO_Speed = GPIO_Speed_50MHz, - }, - }, - }, - [PIOS_LED_LINK] = { - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Mode = GPIO_Mode_Out_PP, - .GPIO_Speed = GPIO_Speed_50MHz, - }, - }, - }, - [PIOS_LED_RX] = { - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Mode = GPIO_Mode_Out_PP, - .GPIO_Speed = GPIO_Speed_50MHz, - }, - }, - }, - [PIOS_LED_TX] = { - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Mode = GPIO_Mode_Out_PP, - .GPIO_Speed = GPIO_Speed_50MHz, - }, - }, - }, -}; - -static const struct pios_led_cfg pios_led_cfg = { - .leds = pios_leds, - .num_leds = NELEMENTS(pios_leds), -}; - -#endif /* PIOS_INCLUDE_LED */ - -#if defined(PIOS_INCLUDE_COM_MSG) - -#include - -#endif /* PIOS_INCLUDE_COM_MSG */ - -#if defined(PIOS_INCLUDE_USB) -#include "pios_usb_priv.h" - -static const struct pios_usb_cfg pios_usb_main_cfg = { - .irq = { - .init = { - .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -#include "pios_usb_board_data_priv.h" -#include "pios_usb_desc_hid_only_priv.h" - -#endif /* PIOS_INCLUDE_USB */ - -#if defined(PIOS_INCLUDE_USB_HID) -#include - -const struct pios_usb_hid_cfg pios_usb_hid_cfg = { - .data_if = 0, - .data_rx_ep = 1, - .data_tx_ep = 1, -}; - -#endif /* PIOS_INCLUDE_USB_HID */ - uint32_t pios_com_telem_usb_id; /** @@ -139,6 +51,10 @@ void PIOS_Board_Init(void) { /* Initialize the PiOS library */ PIOS_GPIO_Init(); +#if defined(PIOS_INCLUDE_LED) + PIOS_LED_Init(&pios_led_cfg); +#endif /* PIOS_INCLUDE_LED */ + #if defined(PIOS_INCLUDE_USB) /* Initialize board specific USB data */ PIOS_USB_BOARD_DATA_Init(); diff --git a/flight/Bootloaders/PipXtreme/pios_usb_board_data.c b/flight/Bootloaders/PipXtreme/pios_usb_board_data.c index 3e41e5ac9..c2e0c8762 100644 --- a/flight/Bootloaders/PipXtreme/pios_usb_board_data.c +++ b/flight/Bootloaders/PipXtreme/pios_usb_board_data.c @@ -31,6 +31,7 @@ #include "pios_usb_board_data.h" /* struct usb_*, USB_* */ #include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ #include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +#include "pios_usb_util.h" /* PIOS_USB_UTIL_AsciiToUtf8 */ static const uint8_t usb_product_id[20] = { sizeof(usb_product_id), @@ -46,40 +47,15 @@ static const uint8_t usb_product_id[20] = { 'e', 0, }; -static uint8_t usb_serial_number[52] = { +static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN*2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1)*2] = { sizeof(usb_serial_number), USB_DESC_TYPE_STRING, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0 }; static const struct usb_string_langid usb_lang_id = { .bLength = sizeof(usb_lang_id), .bDescriptorType = USB_DESC_TYPE_STRING, - .bLangID = htousbs(USB_LANGID_ENGLISH_UK), + .bLangID = htousbs(USB_LANGID_ENGLISH_US), }; static const uint8_t usb_vendor_id[28] = { @@ -103,11 +79,13 @@ static const uint8_t usb_vendor_id[28] = { int32_t PIOS_USB_BOARD_DATA_Init(void) { /* Load device serial number into serial number string */ - uint8_t sn[25]; + uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1]; PIOS_SYS_SerialNumberGet((char *)sn); - for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) { - usb_serial_number[2 + 2 * i] = sn[i]; - } + + /* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */ + uint8_t * utf8 = &(usb_serial_number[2]); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1); PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); diff --git a/flight/Bootloaders/AHRS/Makefile b/flight/Bootloaders/Revolution/Makefile similarity index 78% rename from flight/Bootloaders/AHRS/Makefile rename to flight/Bootloaders/Revolution/Makefile index b4a060373..070d1dfea 100644 --- a/flight/Bootloaders/AHRS/Makefile +++ b/flight/Bootloaders/Revolution/Makefile @@ -1,8 +1,8 @@ ##### - # Project: OpenPilot AHRS_BOOTLOADER + # Project: OpenPilot INS_BOOTLOADER # # - # Makefile for OpenPilot AHRS_BOOTLOADER project + # Makefile for OpenPilot INS project # # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. # @@ -38,7 +38,7 @@ OUTDIR := $(TOP)/build/$(TARGET) DEBUG ?= NO # Set to YES when using Code Sourcery toolchain -CODE_SOURCERY ?= YES +CODE_SOURCERY ?= NO ifeq ($(CODE_SOURCERY), YES) REMOVE_CMD = cs-rm @@ -46,77 +46,41 @@ else REMOVE_CMD = rm endif -FLASH_TOOL = OPENOCD - # Paths -AHRS_BL = ./ -AHRS_BLINC = $(AHRS_BL)/inc +REVO_BL = $(WHEREAMI) +REVO_BLINC = $(REVO_BL)/inc PIOS = ../../PiOS PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = ../Libraries/inc -PIOSSTM32F10X = $(PIOS)/STM32F10x +FLIGHTLIB = ../../Libraries +FLIGHTLIBINC = ../../Libraries/inc +PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards -APPLIBDIR = $(PIOSSTM32F10X)/Libraries +PIOSCOMMONLIB = $(PIOSCOMMON)/Libraries +APPLIBDIR = $(PIOSSTM32F4XX)/Libraries STMLIBDIR = $(APPLIBDIR) -STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver -STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver +STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc -CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME) # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files ## BOOTLOADER: -SRC = main.c +SRC += main.c SRC += pios_board.c -SRC += bl_fsm.c -#SRC += insgps.c -#SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += pios_usb_board_data.c +SRC += op_dfu.c -## PIOS Hardware (STM32F10x) -SRC += $(PIOSSTM32F10X)/pios_sys.c -SRC += $(PIOSSTM32F10X)/pios_led.c -SRC += $(PIOSSTM32F10X)/pios_delay.c -SRC += $(PIOSSTM32F10X)/pios_usart.c -SRC += $(PIOSSTM32F10X)/pios_irq.c -#SRC += $(PIOSSTM32F10X)/pios_i2c.c -SRC += $(PIOSSTM32F10X)/pios_gpio.c -SRC += $(PIOSSTM32F10X)/pios_spi.c +## PIOS Hardware (STM32F4xx) +include $(PIOS)/STM32F4xx/library.mk -## PIOS Hardware (Common) -#SRC += $(PIOSCOMMON)/pios_com.c -#SRC += $(PIOSCOMMON)/pios_hmc5843.c +# PIOS Hardware (Common) SRC += $(PIOSCOMMON)/pios_board_info.c -SRC += $(PIOSCOMMON)/pios_opahrs_proto.c +SRC += $(PIOSCOMMON)/pios_com_msg.c SRC += $(PIOSCOMMON)/printf-stdarg.c -SRC += $(PIOSCOMMON)/pios_bl_helper.c -SRC += $(PIOSCOMMON)/pios_iap.c - -## CMSIS for STM32 -SRC += $(CMSISDIR)/core_cm3.c -SRC += $(CMSISDIR)/system_stm32f10x.c - -## Used parts of the STM-Library -SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c -SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c -SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c -SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c -SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c -SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c -SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c -SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c -SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c -SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c -SRC += $(STMSPDSRCDIR)/misc.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c # List C source files here which must be compiled in ARM-Mode (no -mthumb). # use file-extension c for "c-only"-files @@ -132,29 +96,17 @@ CPPSRC = #CPPSRCARM = $(TARGET).cpp CPPSRCARM = -# List Assembler source files here. -# Make them always end in a capital .S. Files ending in a lowercase .s -# will not be considered source files but generated files (assembler -# output from the compiler), and will be deleted upon "make clean"! -# Even though the DOS/Win* filesystem matches both .s and .S the same, -# it will preserve the spelling of the filenames, and gcc itself does -# care about how the name is spelled on its command-line. -ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S - -# List Assembler source files here which must be assembled in ARM-Mode.. -ASRCARM = - # List any extra directories to look for include files here. # Each directory must be seperated by a space. EXTRAINCDIRS += $(PIOS) EXTRAINCDIRS += $(PIOSINC) EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(PIOSSTM32F10X) +EXTRAINCDIRS += $(PIOSSTM34FXX) EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) EXTRAINCDIRS += $(STMSPDINCDIR) EXTRAINCDIRS += $(CMSISDIR) -EXTRAINCDIRS += $(AHRS_BLINC) +EXTRAINCDIRS += $(REVO_BLINC) EXTRAINCDIRS += $(HWDEFSINC) # List any extra directories to look for library files here. @@ -172,7 +124,7 @@ EXTRA_LIBDIRS = EXTRA_LIBS = # Path to Linker-Scripts -LINKERSCRIPTPATH = $(PIOSSTM32F10X) +LINKERSCRIPTPATH = $(PIOSSTM32FXX) # Optimization level, can be [0, 1, 2, 3, s]. # 0 = turn off optimization. s = optimize for size. @@ -196,7 +148,9 @@ DEBUGF = dwarf-2 # Place project-specific -D (define) and/or # -U options for C here. -CDEFS = -DSTM32F10X_$(MODEL) +CDEFS = -DSTM32F4XX +CDEFS += -DSYSCLK_FREQ=$(SYSCLK_FREQ) +CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ) CDEFS += -DUSE_STDPERIPH_DRIVER CDEFS += -DUSE_$(BOARD) @@ -238,6 +192,11 @@ ifeq ($(DEBUG),YES) CFLAGS = endif +# This is not the best place for these. Really should abstract out +# to the board file or something +CFLAGS += -DSTM32F4XX +CFLAGS += -DMEM_SIZE=1024000000 + CFLAGS += -g$(DEBUGF) CFLAGS += -O$(OPT) ifeq ($(DEBUG),NO) @@ -255,7 +214,7 @@ CFLAGS += -fpromote-loop-indices endif CFLAGS += -Wall -CFLAGS += -Werror +#CFLAGS += -Werror CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) # Compiler flags to generate dependency files: CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d @@ -288,9 +247,8 @@ LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) LDFLAGS += $(MATH_LIB) LDFLAGS += -lc -lgcc -# Set linker-script name depending on selected submodel name -LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_memory.ld -LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_BL_sections.ld +#Linker scripts +LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_BL)) # Define programs and commands. REMOVE = $(REMOVE_CMD) -f @@ -354,8 +312,10 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin +$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) + # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/OpenPilot/inc/common.h b/flight/Bootloaders/Revolution/inc/common.h similarity index 92% rename from flight/Bootloaders/OpenPilot/inc/common.h rename to flight/Bootloaders/Revolution/inc/common.h index 085f07061..9ecff4079 100644 --- a/flight/Bootloaders/OpenPilot/inc/common.h +++ b/flight/Bootloaders/Revolution/inc/common.h @@ -1,7 +1,7 @@ /** ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @brief These files contain the code to the OpenPilot MB Bootloader. + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. * * @{ * @file common.c diff --git a/flight/Bootloaders/OpenPilot/inc/op_dfu.h b/flight/Bootloaders/Revolution/inc/op_dfu.h similarity index 100% rename from flight/Bootloaders/OpenPilot/inc/op_dfu.h rename to flight/Bootloaders/Revolution/inc/op_dfu.h diff --git a/flight/Bootloaders/AHRS/inc/pios_config.h b/flight/Bootloaders/Revolution/inc/pios_config.h similarity index 92% rename from flight/Bootloaders/AHRS/inc/pios_config.h rename to flight/Bootloaders/Revolution/inc/pios_config.h index 82344e2ad..cfe34aaad 100644 --- a/flight/Bootloaders/AHRS/inc/pios_config.h +++ b/flight/Bootloaders/Revolution/inc/pios_config.h @@ -33,9 +33,11 @@ #define PIOS_INCLUDE_LED #define PIOS_INCLUDE_SPI #define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +#define PIOS_INCLUDE_COM_MSG #define PIOS_INCLUDE_BL_HELPER #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_IAP #endif /* PIOS_CONFIG_H */ diff --git a/flight/Bootloaders/OpenPilot/inc/pios_usb_board_data.h b/flight/Bootloaders/Revolution/inc/pios_usb_board_data.h similarity index 94% rename from flight/Bootloaders/OpenPilot/inc/pios_usb_board_data.h rename to flight/Bootloaders/Revolution/inc/pios_usb_board_data.h index ca9c948b0..2c03dc2d0 100644 --- a/flight/Bootloaders/OpenPilot/inc/pios_usb_board_data.h +++ b/flight/Bootloaders/Revolution/inc/pios_usb_board_data.h @@ -37,8 +37,8 @@ #include "pios_usb_defs.h" /* struct usb_* */ -#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_OPENPILOT_MAIN -#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_OPENPILOT_MAIN, USB_OP_BOARD_MODE_BL) +#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_REVOLUTION +#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_REVOLUTION, USB_OP_BOARD_MODE_BL) /* * The bootloader uses a simplified report structure diff --git a/flight/Bootloaders/Revolution/main.c b/flight/Bootloaders/Revolution/main.c new file mode 100644 index 000000000..b64ebc96a --- /dev/null +++ b/flight/Bootloaders/Revolution/main.c @@ -0,0 +1,208 @@ +/** + ****************************************************************************** + * @addtogroup RevolutionBL Revolution BootLoader + * @brief These files contain the code to the Revolution Bootloader. + * + * @{ + * @file main.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This is the file with the main function of the Revolution BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/* Bootloader Includes */ +#include +#include +#include +#include "op_dfu.h" +#include "pios_iap.h" +#include "fifo_buffer.h" +#include "pios_com_msg.h" +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void FLASH_Download(); +#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) + +/* Private typedef -----------------------------------------------------------*/ +typedef void (*pFunction)(void); +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +pFunction Jump_To_Application; +uint32_t JumpAddress; + +/// LEDs PWM +uint32_t period1 = 5000; // 5 mS +uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS +uint32_t period2 = 5000; // 5 mS +uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS + + +//////////////////////////////////////// +uint8_t tempcount = 0; + +/* Extern variables ----------------------------------------------------------*/ +DFUStates DeviceState; +int16_t status = 0; +bool JumpToApp = false; +bool GO_dfu = false; +bool USB_connected = false; +bool User_DFU_request = false; +static uint8_t mReceive_Buffer[63]; +/* Private function prototypes -----------------------------------------------*/ +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); +uint8_t processRX(); +void jump_to_app(); + +int main() { + PIOS_SYS_Init(); + PIOS_Board_Init(); + PIOS_IAP_Init(); + + USB_connected = PIOS_USB_CheckAvailable(0); + + if (PIOS_IAP_CheckRequest() == true) { + PIOS_DELAY_WaitmS(1000); + User_DFU_request = true; + PIOS_IAP_ClearRequest(); + } + + GO_dfu = (USB_connected == true) || (User_DFU_request == true); + + if (GO_dfu == true) { + PIOS_Board_Init(); + if (User_DFU_request == true) + DeviceState = DFUidle; + else + DeviceState = BLidle; + } else + JumpToApp = true; + + uint32_t stopwatch = 0; + uint32_t prev_ticks = PIOS_DELAY_GetuS(); + while (true) { + /* Update the stopwatch */ + uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); + prev_ticks += elapsed_ticks; + stopwatch += elapsed_ticks; + + if (JumpToApp == true) + jump_to_app(); + + switch (DeviceState) { + case Last_operation_Success: + case uploadingStarting: + case DFUidle: + period1 = 5000; + sweep_steps1 = 100; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case uploading: + period1 = 5000; + sweep_steps1 = 100; + period2 = 2500; + sweep_steps2 = 50; + break; + case downloading: + period1 = 2500; + sweep_steps1 = 50; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case BLidle: + period1 = 0; + PIOS_LED_On(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + default://error + period1 = 5000; + sweep_steps1 = 100; + period2 = 5000; + sweep_steps2 = 100; + } + + if (period1 != 0) { + if (LedPWM(period1, sweep_steps1, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_On(PIOS_LED_HEARTBEAT); + + if (period2 != 0) { + if (LedPWM(period2, sweep_steps2, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + + if (stopwatch > 50 * 1000 * 1000) + stopwatch = 0; + if ((stopwatch > 6 * 1000 * 1000) && (DeviceState + == BLidle)) + JumpToApp = true; + + processRX(); + DataDownload(start); + } +} + +void jump_to_app() { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + PIOS_LED_On(PIOS_LED_HEARTBEAT); + if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ + FLASH_Lock(); + RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); + RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); + + PIOS_USBHOOK_Deactivate(); + + JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); + Jump_To_Application = (pFunction) JumpAddress; + /* Initialize user application's Stack Pointer */ + __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); + Jump_To_Application(); + } else { + DeviceState = failed_jump; + return; + } +} +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { + uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ + uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ + + uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ + if (curr_sweep & 1) { + pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ + } + return ((count % pwm_period) > pwm_duty) ? 1 : 0; +} + +uint8_t processRX() { + if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { + processComand(mReceive_Buffer); + } + return true; +} + diff --git a/flight/Bootloaders/OpenPilot/op_dfu.c b/flight/Bootloaders/Revolution/op_dfu.c similarity index 70% rename from flight/Bootloaders/OpenPilot/op_dfu.c rename to flight/Bootloaders/Revolution/op_dfu.c index ef30e4897..3aceedcfb 100644 --- a/flight/Bootloaders/OpenPilot/op_dfu.c +++ b/flight/Bootloaders/Revolution/op_dfu.c @@ -1,7 +1,7 @@ /** ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @brief These files contain the code to the OpenPilot MB Bootloader. + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. * * @{ * @file op_dfu.c @@ -28,12 +28,11 @@ /* Includes ------------------------------------------------------------------*/ #include "pios.h" +#include #include "op_dfu.h" #include "pios_bl_helper.h" #include "pios_com_msg.h" #include -#include "pios_opahrs.h" -#include "ssp.h" //programmable devices Device devicesTable[10]; uint8_t numberOfDevices = 0; @@ -72,8 +71,6 @@ DFUTransfer downType = 0; /* Extern variables ----------------------------------------------------------*/ extern DFUStates DeviceState; extern uint8_t JumpToApp; -extern Port_t ssp_port; -extern DFUPort ProgPort; /* Private function prototypes -----------------------------------------------*/ /* Private functions ---------------------------------------------------------*/ void sendData(uint8_t * buf, uint16_t size); @@ -139,14 +136,14 @@ void processComand(uint8_t *xReceive_Buffer) { Command = Command & 0b00011111; if (EchoReqFlag == 1) { - memcpy(echoBuffer, Buffer, 64); + memcpy(echoBuffer, xReceive_Buffer, 64); } switch (Command) { case EnterDFU: if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) || (DeviceState == DFUidle)) { if (Data0 > 0) - OPDfuIni(TRUE); + OPDfuIni(true); DeviceState = DFUidle; currentProgrammingDestination = devicesTable[Data0].programmingType; currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; @@ -159,7 +156,7 @@ void processComand(uint8_t *xReceive_Buffer) { result = PIOS_BL_HELPER_FLASH_Ini(); break; case Remote_flash_via_spi: - result = TRUE; + result = true; break; default: DeviceState = Last_operation_failed; @@ -184,35 +181,18 @@ void processComand(uint8_t *xReceive_Buffer) { SizeOfLastPacket = Data1; if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) - * 14 * 4 + SizeOfLastPacket * 4) == TRUE) { + * 14 * 4 + SizeOfLastPacket * 4) == true) { DeviceState = outsideDevCapabilities; Aditionals = (uint32_t) Command; } else { uint8_t result = 1; - struct opahrs_msg_v0 rsp; if (TransferType == FW) { switch (currentProgrammingDestination) { case Self_flash: result = PIOS_BL_HELPER_FLASH_Start(); break; case Remote_flash_via_spi: - PIOS_OPAHRS_bl_FwupStart(&rsp); - result = FALSE; - for (int i = 0; i < 5; ++i) { - PIOS_DELAY_WaitmS(1000); - PIOS_OPAHRS_bl_resync(); - if (PIOS_OPAHRS_bl_FwupStatus(&rsp) - == OPAHRS_RESULT_OK) { - if (rsp.payload.user.v.rsp.fwup_status.status - == started) { - result = TRUE; - break; - } else { - result = FALSE; - break; - } - } - } + result = false; break; default: break; @@ -236,8 +216,6 @@ void processComand(uint8_t *xReceive_Buffer) { { numberOfWords = SizeOfLastPacket; } - struct opahrs_msg_v0 rsp; - struct opahrs_msg_v0 req; uint8_t result = 0; switch (currentProgrammingDestination) { case Self_flash: @@ -259,31 +237,7 @@ void processComand(uint8_t *xReceive_Buffer) { } break; case Remote_flash_via_spi: - for (uint8_t x = 0; x < numberOfWords; ++x) { - offset = 4 * x; - Data = xReceive_Buffer[DATA + offset] << 24; - Data += xReceive_Buffer[DATA + 1 + offset] << 16; - Data += xReceive_Buffer[DATA + 2 + offset] << 8; - Data += xReceive_Buffer[DATA + 3 + offset]; - req.payload.user.v.req.fwup_data.data[x] = Data; - } - aux = (baseOfAdressType(TransferType) + (uint32_t)( - Count * 14 * 4)); - req.payload.user.v.req.fwup_data.adress = aux; - req.payload.user.v.req.fwup_data.size = numberOfWords; - if (PIOS_OPAHRS_bl_FwupData(&req, &rsp) - == OPAHRS_RESULT_OK) { - if (rsp.payload.user.v.rsp.fwup_status.status - == write_error) { - result = FALSE; - } else if (rsp.payload.user.v.rsp.fwup_status.status - == outside_dev_capabilities) { - result = TRUE; - DeviceState = outsideDevCapabilities; - } else - result = TRUE; - } else - result = FALSE; + result = false; // No support for this for the PipX break; default: result = 0; @@ -306,7 +260,7 @@ void processComand(uint8_t *xReceive_Buffer) { } break; case Req_Capabilities: - OPDfuIni(TRUE); + OPDfuIni(true); Buffer[0] = 0x01; Buffer[1] = Rep_Capabilities; if (Data0 == 0) { @@ -342,28 +296,12 @@ void processComand(uint8_t *xReceive_Buffer) { sendData(Buffer + 1, 63); break; case JumpFW: - if (numberOfDevices > 1) { - struct opahrs_msg_v0 rsp; - PIOS_OPAHRS_bl_boot(0); - if (PIOS_OPAHRS_bl_FwupStatus(&rsp) == OPAHRS_RESULT_OK) { - DeviceState = failed_jump; - break; - } else { - if (Data == 0x5AFE) { - /* Force board into safe mode */ - PIOS_IAP_WriteBootCount(0xFFFF); - } - FLASH_Lock(); - JumpToApp = 1; - } - } else { - if (Data == 0x5AFE) { - /* Force board into safe mode */ - PIOS_IAP_WriteBootCount(0xFFFF); - } - FLASH_Lock(); - JumpToApp = 1; + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); } + FLASH_Lock(); + JumpToApp = 1; break; case Reset: PIOS_SYS_Reset(); @@ -401,8 +339,8 @@ void processComand(uint8_t *xReceive_Buffer) { downType = Data0; downPacketTotal = Count; downSizeOfLastPacket = Data1; - if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 - + downSizeOfLastPacket) == 1) { + if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 * 4 + + downSizeOfLastPacket * 4) == 1) { DeviceState = outsideDevCapabilities; Aditionals = (uint32_t) Command; @@ -445,8 +383,8 @@ void processComand(uint8_t *xReceive_Buffer) { } if (EchoReqFlag == 1) { - echoBuffer[1] = echoBuffer[1] | EchoAnsFlag; - sendData(echoBuffer + 1, 63); + echoBuffer[0] = echoBuffer[0] | (1 << 6); + sendData(echoBuffer, 63); } return; } @@ -466,41 +404,8 @@ void OPDfuIni(uint8_t discover) { numberOfDevices = 1; devicesTable[0] = dev; if (discover) { - uint8_t found_spi_device = FALSE; - - for (int t = 0; t < 3; ++t) { - if (PIOS_OPAHRS_bl_resync() == OPAHRS_RESULT_OK) { - found_spi_device = TRUE; - dev.FW_Crc = 0; - break; - } - PIOS_DELAY_WaitmS(100); - } - if (found_spi_device == TRUE) { - struct opahrs_msg_v0 rsp; - if (PIOS_OPAHRS_bl_GetVersions(&rsp) == OPAHRS_RESULT_OK) { - dev.programmingType = Remote_flash_via_spi; - dev.BL_Version = rsp.payload.user.v.rsp.versions.bl_version; - dev.FW_Crc = rsp.payload.user.v.rsp.versions.fw_crc; - dev.devID = rsp.payload.user.v.rsp.versions.hw_version; - if (PIOS_OPAHRS_bl_GetMemMap(&rsp) == OPAHRS_RESULT_OK) { - dev.readWriteFlags - = rsp.payload.user.v.rsp.mem_map.rw_flags; - dev.startOfUserCode - = rsp.payload.user.v.rsp.mem_map.start_of_user_code; - dev.sizeOfCode - = rsp.payload.user.v.rsp.mem_map.size_of_code_memory; - dev.sizeOfDescription - = rsp.payload.user.v.rsp.mem_map.size_of_description; - dev.devType = rsp.payload.user.v.rsp.mem_map.density; - numberOfDevices = 2; - devicesTable[1] = dev; - } - } - } else - PIOS_OPAHRS_ForceSlaveSelected(true); + //TODO check other devices trough spi or whatever } - //TODO check other devices trough spi or whatever } uint32_t baseOfAdressType(DFUTransfer type) { switch (type) { @@ -524,26 +429,16 @@ uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { return (size > currentDevice.sizeOfDescription) ? 1 : 0; break; default: - return TRUE; + return true; } } uint32_t CalcFirmCRC() { - struct opahrs_msg_v0 rsp; switch (currentProgrammingDestination) { case Self_flash: return PIOS_BL_HELPER_CRC_Memory_Calc(); break; case Remote_flash_via_spi: - PIOS_OPAHRS_bl_FwupVerify(&rsp); - for (int i = 0; i < 5; ++i) { - PIOS_DELAY_WaitmS(1000); - PIOS_OPAHRS_bl_resync(); - if (PIOS_OPAHRS_bl_GetVersions(&rsp) == OPAHRS_RESULT_OK) { - return rsp.payload.user.v.rsp.versions.fw_crc; - } - } - return 0; break; default: @@ -553,34 +448,21 @@ uint32_t CalcFirmCRC() { } void sendData(uint8_t * buf, uint16_t size) { - if (ProgPort == Usb) { - PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); - } else if (ProgPort == Serial) { - ssp_SendData(&ssp_port, buf, size); - } + PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); } bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { - struct opahrs_msg_v0 rsp; - struct opahrs_msg_v0 req; switch (type) { case Remote_flash_via_spi: - req.payload.user.v.req.fwdn_data.adress = adr; - if (PIOS_OPAHRS_bl_FwDlData(&req, &rsp) == OPAHRS_RESULT_OK) { - for (uint8_t x = 0; x < 4; ++x) { - buffer[x] = rsp.payload.user.v.rsp.fw_dn.data[x]; - } - return TRUE; - } - return FALSE; + return false; // We should not get this for the PipX break; case Self_flash: for (uint8_t x = 0; x < 4; ++x) { buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); } - return TRUE; + return true; break; default: - return FALSE; + return false; } } diff --git a/flight/Bootloaders/AHRS/pios_board.c b/flight/Bootloaders/Revolution/pios_board.c similarity index 68% rename from flight/Bootloaders/AHRS/pios_board.c rename to flight/Bootloaders/Revolution/pios_board.c index 9b9eac875..143124ade 100644 --- a/flight/Bootloaders/AHRS/pios_board.c +++ b/flight/Bootloaders/Revolution/pios_board.c @@ -32,9 +32,10 @@ */ #include "board_hw_defs.c" +#include #include -#include "bl_fsm.h" /* lfsm_* */ +uint32_t pios_com_telem_usb_id; static bool board_init_complete = false; void PIOS_Board_Init() { @@ -42,16 +43,36 @@ void PIOS_Board_Init() { return; } + /* Delay system */ + PIOS_DELAY_Init(); + #if defined(PIOS_INCLUDE_LED) PIOS_LED_Init(&pios_led_cfg); #endif /* PIOS_INCLUDE_LED */ - /* Set up the SPI interface to the OP board */ - if (PIOS_SPI_Init(&pios_spi_op_id, &pios_spi_op_cfg)) { - PIOS_DEBUG_Assert(0); +#if defined(PIOS_INCLUDE_USB) + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + /* Activate the HID-only USB configuration */ + PIOS_USB_DESC_HID_ONLY_Init(); + + uint32_t pios_usb_id; + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); + +#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG) + uint32_t pios_usb_hid_id; + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { + PIOS_Assert(0); } - lfsm_attach(pios_spi_op_id); - lfsm_init(); + if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) { + PIOS_Assert(0); + } +#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */ + + PIOS_USBHOOK_Activate(); + +#endif /* PIOS_INCLUDE_USB */ board_init_complete = true; } diff --git a/flight/Bootloaders/OpenPilot/pios_usb_board_data.c b/flight/Bootloaders/Revolution/pios_usb_board_data.c similarity index 97% rename from flight/Bootloaders/OpenPilot/pios_usb_board_data.c rename to flight/Bootloaders/Revolution/pios_usb_board_data.c index b73419ba4..823496c29 100644 --- a/flight/Bootloaders/OpenPilot/pios_usb_board_data.c +++ b/flight/Bootloaders/Revolution/pios_usb_board_data.c @@ -32,18 +32,19 @@ #include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ #include "pios_usbhook.h" /* PIOS_USBHOOK_* */ -static const uint8_t usb_product_id[20] = { +static const uint8_t usb_product_id[22] = { sizeof(usb_product_id), USB_DESC_TYPE_STRING, - 'O', 0, - 'p', 0, + 'R', 0, 'e', 0, - 'n', 0, - 'P', 0, - 'i', 0, - 'l', 0, + 'v', 0, 'o', 0, + 'l', 0, + 'u', 0, 't', 0, + 'i', 0, + 'o', 0, + 'n', 0, }; static uint8_t usb_serial_number[52] = { diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index e8467ab55..82334e56a 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -39,6 +39,7 @@ DEBUG ?= NO # Include objects that are just nice information to show DIAGNOSTICS ?= NO +DIAG_TASKS ?= NO # Set to YES to build a FW version that will erase all flash memory ERASE_FLASH ?= NO @@ -49,7 +50,7 @@ ENABLE_DEBUG_PINS ?= NO ENABLE_AUX_UART ?= NO # Set to YES when using Code Sourcery toolchain -CODE_SOURCERY ?= YES +CODE_SOURCERY ?= NO # Remove command is different for Code Sourcery on Windows ifeq ($(CODE_SOURCERY), YES) @@ -185,7 +186,8 @@ SRC += $(OPUAVSYNTHDIR)/stabilizationsettings.c SRC += $(OPUAVSYNTHDIR)/actuatorcommand.c SRC += $(OPUAVSYNTHDIR)/actuatordesired.c SRC += $(OPUAVSYNTHDIR)/actuatorsettings.c -SRC += $(OPUAVSYNTHDIR)/attituderaw.c +SRC += $(OPUAVSYNTHDIR)/accels.c +SRC += $(OPUAVSYNTHDIR)/gyros.c SRC += $(OPUAVSYNTHDIR)/attitudeactual.c SRC += $(OPUAVSYNTHDIR)/manualcontrolcommand.c SRC += $(OPUAVSYNTHDIR)/i2cstats.c @@ -227,8 +229,9 @@ SRC += $(PIOSSTM32F10X)/pios_gpio.c SRC += $(PIOSSTM32F10X)/pios_exti.c SRC += $(PIOSSTM32F10X)/pios_rtc.c SRC += $(PIOSSTM32F10X)/pios_wdg.c +SRC += $(PIOSSTM32F10X)/pios_iap.c SRC += $(PIOSSTM32F10X)/pios_tim.c - +SRC += $(PIOSSTM32F10X)/pios_bl_helper.c # PIOS USB related files (separated to make code maintenance more easy) SRC += $(PIOSSTM32F10X)/pios_usb.c @@ -240,17 +243,17 @@ SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c SRC += $(OPSYSTEM)/pios_usb_board_data.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c +SRC += $(PIOSCOMMON)/pios_usb_util.c ## PIOS Hardware (Common) SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_flashfs_objlist.c -SRC += $(PIOSCOMMON)/pios_flash_w25x.c +SRC += $(PIOSCOMMON)/pios_flash_jedec.c SRC += $(PIOSCOMMON)/pios_adxl345.c +SRC += $(PIOSCOMMON)/pios_mpu6000.c SRC += $(PIOSCOMMON)/pios_com.c -SRC += $(PIOSCOMMON)/pios_i2c_esc.c -SRC += $(PIOSCOMMON)/pios_bmp085.c -SRC += $(PIOSCOMMON)/pios_iap.c -SRC += $(PIOSCOMMON)/pios_bl_helper.c +#SRC += $(PIOSCOMMON)/pios_i2c_esc.c +#SRC += $(PIOSCOMMON)/pios_bmp085.c SRC += $(PIOSCOMMON)/pios_rcvr.c SRC += $(PIOSCOMMON)/pios_gcsrcvr.c SRC += $(PIOSCOMMON)/printf-stdarg.c @@ -603,7 +606,7 @@ $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin $(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino opfw elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/CopterControl/System/coptercontrol.c b/flight/CopterControl/System/coptercontrol.c index 3c64141ec..916718ea5 100644 --- a/flight/CopterControl/System/coptercontrol.c +++ b/flight/CopterControl/System/coptercontrol.c @@ -71,7 +71,7 @@ int main() PIOS_Board_Init(); #ifdef ERASE_FLASH - PIOS_Flash_W25X_EraseChip(); + PIOS_Flash_Jedec_EraseChip(); #if defined(PIOS_LED_HEARTBEAT) PIOS_LED_Off(PIOS_LED_HEARTBEAT); #endif /* PIOS_LED_HEARTBEAT */ @@ -84,7 +84,20 @@ int main() /* swap the stack to use the IRQ stack */ Stack_Change(); - /* Start the FreeRTOS scheduler which should never returns.*/ + /* Start the FreeRTOS scheduler, which should never return. + * + * NOTE: OpenPilot runs an operating system (FreeRTOS), which constantly calls + * (schedules) function files (modules). These functions never return from their + * while loops, which explains why each module has a while(1){} segment. Thus, + * the OpenPilot software actually starts at the vTaskStartScheduler() function, + * even though this is somewhat obscure. + * + * In addition, there are many main() functions in the OpenPilot firmware source tree + * This is because each main() refers to a separate hardware platform. Of course, + * C only allows one main(), so only the relevant main() function is compiled when + * making a specific firmware. + * + */ vTaskStartScheduler(); /* If all is well we will never reach here as the scheduler will now be running. */ diff --git a/flight/CopterControl/System/inc/FreeRTOSConfig.h b/flight/CopterControl/System/inc/FreeRTOSConfig.h index 68bb9da0e..996726133 100644 --- a/flight/CopterControl/System/inc/FreeRTOSConfig.h +++ b/flight/CopterControl/System/inc/FreeRTOSConfig.h @@ -31,7 +31,7 @@ #define configTICK_RATE_HZ ( ( portTickType ) 1000 ) #define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) #define configMINIMAL_STACK_SIZE ( ( unsigned short ) 48 ) -#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 54 * 256) ) +#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 53 * 256) ) #define configMAX_TASK_NAME_LEN ( 16 ) #define configUSE_TRACE_FACILITY 0 #define configUSE_16_BIT_TICKS 0 diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/CopterControl/System/inc/pios_config.h index 1d701a1af..e4b70e931 100644 --- a/flight/CopterControl/System/inc/pios_config.h +++ b/flight/CopterControl/System/inc/pios_config.h @@ -36,10 +36,10 @@ /* Enable/Disable PiOS Modules */ #define PIOS_INCLUDE_ADC #define PIOS_INCLUDE_DELAY -#if defined(USE_I2C) -#define PIOS_INCLUDE_I2C -#define PIOS_INCLUDE_I2C_ESC -#endif +//#if defined(USE_I2C) +//#define PIOS_INCLUDE_I2C +//#define PIOS_INCLUDE_I2C_ESC +//#endif #define PIOS_INCLUDE_IRQ #define PIOS_INCLUDE_LED #define PIOS_INCLUDE_IAP @@ -77,8 +77,8 @@ #define PIOS_INCLUDE_ADXL345 #define PIOS_INCLUDE_FLASH - -#define PIOS_INCLUDE_BMP085 +#define PIOS_INCLUDE_MPU6000 +#define PIOS_MPU6000_ACCEL /* A really shitty setting saving implementation */ #define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS diff --git a/flight/CopterControl/System/inc/pios_usb_board_data.h b/flight/CopterControl/System/inc/pios_usb_board_data.h index 9907a4934..2dcb5f845 100644 --- a/flight/CopterControl/System/inc/pios_usb_board_data.h +++ b/flight/CopterControl/System/inc/pios_usb_board_data.h @@ -41,5 +41,6 @@ #define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_COPTERCONTROL #define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_COPTERCONTROL, USB_OP_BOARD_MODE_FW) +#define PIOS_USB_BOARD_SN_SUFFIX "+FW" #endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/CopterControl/System/pios_board.c b/flight/CopterControl/System/pios_board.c index d0b8ce8dc..42d5a4bfe 100644 --- a/flight/CopterControl/System/pios_board.c +++ b/flight/CopterControl/System/pios_board.c @@ -43,6 +43,7 @@ #include #include + /* One slot per selectable receiver group. * eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS * NOTE: No slot in this map for NONE. @@ -66,25 +67,134 @@ uint32_t pios_com_vcp_id; uint32_t pios_com_gps_id; uint32_t pios_com_bridge_id; +/** + * Configuration for MPU6000 chip + */ +#if defined(PIOS_INCLUDE_MPU6000) +#include "pios_mpu6000.h" +static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = { + .vector = PIOS_MPU6000_IRQHandler, + .line = EXTI_Line3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line3, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static const struct pios_mpu6000_cfg pios_mpu6000_cfg = { + .exti_cfg = &pios_exti_mpu6000_cfg, + .Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT, + // Clock at 8 khz, downsampled by 8 for 1khz + .Smpl_rate_div = 15, + .interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD, + .interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY, + .User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN, + .Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK, + .accel_range = PIOS_MPU6000_ACCEL_8G, + .gyro_range = PIOS_MPU6000_SCALE_500_DEG, + .filter = PIOS_MPU6000_LOWPASS_256_HZ +}; +#endif /* PIOS_INCLUDE_MPU6000 */ + +static const struct flashfs_cfg flashfs_w25x_cfg = { + .table_magic = 0x85FB3C35, + .obj_magic = 0x3015AE71, + .obj_table_start = 0x00000010, + .obj_table_end = 0x00001000, + .sector_size = 0x00001000, + .chip_size = 0x00080000, +}; + +static const struct pios_flash_jedec_cfg flash_w25x_cfg = { + .sector_erase = 0x20, + .chip_erase = 0x60 +}; + +static const struct flashfs_cfg flashfs_m25p_cfg = { + .table_magic = 0x85FB3D35, + .obj_magic = 0x3015A371, + .obj_table_start = 0x00000010, + .obj_table_end = 0x00010000, + .sector_size = 0x00010000, + .chip_size = 0x00200000, +}; + +static const struct pios_flash_jedec_cfg flash_m25p_cfg = { + .sector_erase = 0xD8, + .chip_erase = 0xC7 +}; +#include /** * PIOS_Board_Init() * initializes all the core subsystems on this specific hardware * called from System/openpilot.c */ +int32_t init_test; void PIOS_Board_Init(void) { /* Delay system */ PIOS_DELAY_Init(); + const struct pios_board_info * bdinfo = &pios_board_info_blob; + +#if defined(PIOS_INCLUDE_LED) + const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev); + PIOS_Assert(led_cfg); + PIOS_LED_Init(led_cfg); +#endif /* PIOS_INCLUDE_LED */ + +#if defined(PIOS_INCLUDE_SPI) /* Set up the SPI interface to the serial flash */ - if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg)) { - PIOS_Assert(0); + + switch(bdinfo->board_rev) { + case BOARD_REVISION_CC: + if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg_cc)) { + PIOS_Assert(0); + } + break; + case BOARD_REVISION_CC3D: + if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg_cc3d)) { + PIOS_Assert(0); + } + break; + default: + PIOS_Assert(0); } - PIOS_Flash_W25X_Init(pios_spi_flash_accel_id); - PIOS_ADXL345_Attach(pios_spi_flash_accel_id); +#endif - PIOS_FLASHFS_Init(); + switch(bdinfo->board_rev) { + case BOARD_REVISION_CC: + PIOS_Flash_Jedec_Init(pios_spi_flash_accel_id, 1, &flash_w25x_cfg); + PIOS_FLASHFS_Init(&flashfs_w25x_cfg); + break; + case BOARD_REVISION_CC3D: + PIOS_Flash_Jedec_Init(pios_spi_flash_accel_id, 0, &flash_m25p_cfg); + PIOS_FLASHFS_Init(&flashfs_m25p_cfg); + break; + default: + PIOS_DEBUG_Assert(0); + } /* Initialize UAVObject libraries */ EventDispatcherInitialize(); @@ -95,10 +205,6 @@ void PIOS_Board_Init(void) { PIOS_RTC_Init(&pios_rtc_main_cfg); #endif -#if defined(PIOS_INCLUDE_LED) - PIOS_LED_Init(&pios_led_cfg); -#endif /* PIOS_INCLUDE_LED */ - HwSettingsInitialize(); #ifndef ERASE_FLASH @@ -134,35 +240,36 @@ void PIOS_Board_Init(void) { /* Initialize board specific USB data */ PIOS_USB_BOARD_DATA_Init(); + /* Flags to determine if various USB interfaces are advertised */ bool usb_hid_present = false; bool usb_cdc_present = false; - uint8_t hwsettings_usb_devicetype; - HwSettingsUSB_DeviceTypeGet(&hwsettings_usb_devicetype); - - switch (hwsettings_usb_devicetype) { - case HWSETTINGS_USB_DEVICETYPE_HIDONLY: - if (PIOS_USB_DESC_HID_ONLY_Init()) { - PIOS_Assert(0); - } - usb_hid_present = true; - break; - case HWSETTINGS_USB_DEVICETYPE_HIDVCP: - if (PIOS_USB_DESC_HID_CDC_Init()) { - PIOS_Assert(0); - } - usb_hid_present = true; - usb_cdc_present = true; - break; - case HWSETTINGS_USB_DEVICETYPE_VCPONLY: - break; - default: +#if defined(PIOS_INCLUDE_USB_CDC) + if (PIOS_USB_DESC_HID_CDC_Init()) { PIOS_Assert(0); } + usb_hid_present = true; + usb_cdc_present = true; +#else + if (PIOS_USB_DESC_HID_ONLY_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; +#endif uint32_t pios_usb_id; - PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); + + switch(bdinfo->board_rev) { + case BOARD_REVISION_CC: + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc); + break; + case BOARD_REVISION_CC3D: + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc3d); + break; + default: + PIOS_Assert(0); + } #if defined(PIOS_INCLUDE_USB_CDC) @@ -575,8 +682,35 @@ void PIOS_Board_Init(void) { #else PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); #endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */ - - PIOS_ADC_Init(); + + switch(bdinfo->board_rev) { + case BOARD_REVISION_CC: + // Revision 1 with invensense gyros, start the ADC +#if defined(PIOS_INCLUDE_ADC) + PIOS_ADC_Init(&pios_adc_cfg); +#endif +#if defined(PIOS_INCLUDE_ADXL345) + PIOS_ADXL345_Init(pios_spi_flash_accel_id, 0); +#endif + break; + case BOARD_REVISION_CC3D: + // Revision 2 with L3GD20 gyros, start a SPI interface and connect to it + GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE); + +#if defined(PIOS_INCLUDE_MPU6000) + // Set up the SPI interface to the serial flash + if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) { + PIOS_Assert(0); + } + PIOS_MPU6000_Init(pios_spi_gyro_id,0,&pios_mpu6000_cfg); + init_test = PIOS_MPU6000_Test(); +#endif /* PIOS_INCLUDE_MPU6000 */ + + break; + default: + PIOS_Assert(0); + } + PIOS_GPIO_Init(); /* Make sure we have at least one telemetry link configured or else fail initialization */ diff --git a/flight/CopterControl/System/pios_usb_board_data.c b/flight/CopterControl/System/pios_usb_board_data.c index 4f02ce424..1993320d4 100644 --- a/flight/CopterControl/System/pios_usb_board_data.c +++ b/flight/CopterControl/System/pios_usb_board_data.c @@ -31,6 +31,7 @@ #include "pios_usb_board_data.h" /* struct usb_*, USB_* */ #include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ #include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +#include "pios_usb_util.h" /* PIOS_USB_UTIL_AsciiToUtf8 */ static const uint8_t usb_product_id[28] = { sizeof(usb_product_id), @@ -50,40 +51,15 @@ static const uint8_t usb_product_id[28] = { 'l', 0, }; -static uint8_t usb_serial_number[52] = { +static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN*2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1)*2] = { sizeof(usb_serial_number), USB_DESC_TYPE_STRING, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0 }; static const struct usb_string_langid usb_lang_id = { .bLength = sizeof(usb_lang_id), .bDescriptorType = USB_DESC_TYPE_STRING, - .bLangID = htousbs(USB_LANGID_ENGLISH_UK), + .bLangID = htousbs(USB_LANGID_ENGLISH_US), }; static const uint8_t usb_vendor_id[28] = { @@ -107,11 +83,13 @@ static const uint8_t usb_vendor_id[28] = { int32_t PIOS_USB_BOARD_DATA_Init(void) { /* Load device serial number into serial number string */ - uint8_t sn[25]; + uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1]; PIOS_SYS_SerialNumberGet((char *)sn); - for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) { - usb_serial_number[2 + 2 * i] = sn[i]; - } + + /* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */ + uint8_t * utf8 = &(usb_serial_number[2]); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1); PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); diff --git a/flight/Doc/Doxygen/doxygen.cfg b/flight/Doc/Doxygen/doxygen.cfg index 71a779d48..dec54aa81 100644 --- a/flight/Doc/Doxygen/doxygen.cfg +++ b/flight/Doc/Doxygen/doxygen.cfg @@ -574,7 +574,7 @@ WARN_LOGFILE = # directories like "/usr/src/myproject". Separate the files or directories # with spaces. -INPUT = OpenPilot PiOS PiOS/STM32F10x +INPUT = OpenPilot PiOS PiOS/STM32F10x PiOS/STM32F2xx # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is diff --git a/flight/EntireFlash/Makefile b/flight/EntireFlash/Makefile new file mode 100644 index 000000000..c4fda382f --- /dev/null +++ b/flight/EntireFlash/Makefile @@ -0,0 +1,54 @@ +##### +# Makefile for Entire Flash (EF) images +# +# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. +# +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, but +# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +# for more details. +# +# You should have received a copy of the GNU General Public License along +# with this program; if not, write to the Free Software Foundation, Inc., +# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +##### + +WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) +TOP := $(realpath $(WHEREAMI)/../../) +include $(TOP)/make/firmware-defs.mk +include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk + +# Target file name (without extension). +TARGET := ef_$(BOARD_NAME) + +# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) +OUTDIR := $(TOP)/build/$(TARGET) + +.PHONY: bin +bin: $(OUTDIR)/$(TARGET).bin + +FW_PAD = $(shell echo $$[$(FW_BANK_BASE)-$(BL_BANK_BASE)-$(BL_BANK_SIZE)]) +$(OUTDIR)/$(TARGET).pad: + $(V0) @echo " PADDING $@" + $(V1) dd status=noxfer if=/dev/zero count=$(FW_PAD) bs=1 2>/dev/null | tr '\000' '\377' > $@ + +BL_BIN = $(TOP)/build/bl_$(BOARD_NAME)/bl_$(BOARD_NAME).bin +FW_BIN = $(TOP)/build/fw_$(BOARD_NAME)/fw_$(BOARD_NAME).bin +$(OUTDIR)/$(TARGET).bin: $(BL_BIN) $(FW_BIN) $(OUTDIR)/$(TARGET).pad + $(V0) @echo " FLASH IMG $@" + $(V1) cat $(BL_BIN) $(OUTDIR)/$(TARGET).pad $(FW_BIN) > $@ + +.PHONY: dfu +dfu: $(OUTDIR)/$(TARGET).bin + $(V0) @echo " DFU RESCUE $<" + $(V1) ( \ + sudo $(DFU_CMD) -l && \ + sudo $(DFU_CMD) -d 0483:df11 -c 1 -i 0 -a 0 -D $< -s $(BL_BANK_BASE) ; \ + ) + diff --git a/flight/INS/Makefile b/flight/INS/Makefile deleted file mode 100644 index a58f71b9b..000000000 --- a/flight/INS/Makefile +++ /dev/null @@ -1,431 +0,0 @@ - ##### - # Project: OpenPilot INS - # - # - # Makefile for OpenPilot INS project - # - # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011. - # - # - # This program is free software; you can redistribute it and/or modify - # it under the terms of the GNU General Public License as published by - # the Free Software Foundation; either version 3 of the License, or - # (at your option) any later version. - # - # This program is distributed in the hope that it will be useful, but - # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - # for more details. - # - # You should have received a copy of the GNU General Public License along - # with this program; if not, write to the Free Software Foundation, Inc., - # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - ##### - -WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../) -include $(TOP)/make/firmware-defs.mk -include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk - -# Target file name (without extension). -TARGET := fw_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - -# Set developer code and compile options -# Set to YES for debugging -DEBUG ?= YES - -# Set to YES when using Code Sourcery toolchain -CODE_SOURCERY ?= YES - -ifeq ($(CODE_SOURCERY), YES) -REMOVE_CMD = cs-rm -else -REMOVE_CMD = rm -endif - -FLASH_TOOL = OPENOCD - -# Paths -INS = ./ -INSINC = $(INS)/inc -PIOS = ../PiOS -PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = ../Libraries/inc -PIOSSTM32F10X = $(PIOS)/STM32F10x -PIOSCOMMON = $(PIOS)/Common -PIOSBOARDS = $(PIOS)/Boards -APPLIBDIR = $(PIOSSTM32F10X)/Libraries -STMLIBDIR = $(APPLIBDIR) -STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver -STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver -STMSPDSRCDIR = $(STMSPDDIR)/src -STMSPDINCDIR = $(STMSPDDIR)/inc -CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 -OPDIR = ../OpenPilot -OPUAVOBJ = ../UAVObjects -OPUAVOBJINC = $(OPUAVOBJ)/inc -OPSYSINC = $(OPDIR)/System/inc -BOOT = ../Bootloaders/INS -BOOTINC = $(BOOT)/inc -HWDEFSINC = ../board_hw_defs/$(BOARD_NAME) - -OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight - -# List C source files here. (C dependencies are automatically generated.) -# use file-extension c for "c-only"-files - -## INS: -SRC = ins.c -SRC += pios_board.c -#SRC += ins_timer.c -#SRC += insgps13state.c -SRC += $(FLIGHTLIB)/fifo_buffer.c -#SRC += $(FLIGHTLIB)/ins_spi_comm.c -#SRC += $(FLIGHTLIB)/ins_comm_objects.c -#SRC += $(FLIGHTLIB)/CoordinateConversions.c -#SRC += $(BOOT)/ins_spi_program_slave.c -#SRC += $(BOOT)/ins_slave_test.c -#SRC += $(BOOT)/ins_spi_program.c - -## PIOS Hardware (STM32F10x) -SRC += $(PIOSSTM32F10X)/pios_sys.c -SRC += $(PIOSSTM32F10X)/pios_led.c -SRC += $(PIOSSTM32F10X)/pios_delay.c -SRC += $(PIOSSTM32F10X)/pios_usart.c -SRC += $(PIOSSTM32F10X)/pios_irq.c -SRC += $(PIOSSTM32F10X)/pios_i2c.c -SRC += $(PIOSSTM32F10X)/pios_debug.c -SRC += $(PIOSSTM32F10X)/pios_gpio.c -SRC += $(PIOSSTM32F10X)/pios_spi.c -SRC += $(PIOSSTM32F10X)/pios_exti.c - -## PIOS Hardware (Common) -SRC += $(PIOSCOMMON)/pios_com.c -SRC += $(PIOSCOMMON)/printf-stdarg.c -SRC += $(PIOSCOMMON)/pios_iap.c -SRC += $(PIOSCOMMON)/pios_bma180.c -SRC += $(PIOSCOMMON)/pios_hmc5883.c -SRC += $(PIOSCOMMON)/pios_bmp085.c -SRC += $(PIOSCOMMON)/pios_imu3000.c - -## CMSIS for STM32 -SRC += $(CMSISDIR)/core_cm3.c -SRC += $(CMSISDIR)/system_stm32f10x.c - -## Used parts of the STM-Library -SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c -SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c -SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c -SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c -SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c -SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c -SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c -SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c -SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c -SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c -SRC += $(STMSPDSRCDIR)/misc.c - -# List C source files here which must be compiled in ARM-Mode (no -mthumb). -# use file-extension c for "c-only"-files -## just for testing, timer.c could be compiled in thumb-mode too -SRCARM = - -# List C++ source files here. -# use file-extension .cpp for C++-files (not .C) -CPPSRC = - -# List C++ source files here which must be compiled in ARM-Mode. -# use file-extension .cpp for C++-files (not .C) -#CPPSRCARM = $(TARGET).cpp -CPPSRCARM = - -# List Assembler source files here. -# Make them always end in a capital .S. Files ending in a lowercase .s -# will not be considered source files but generated files (assembler -# output from the compiler), and will be deleted upon "make clean"! -# Even though the DOS/Win* filesystem matches both .s and .S the same, -# it will preserve the spelling of the filenames, and gcc itself does -# care about how the name is spelled on its command-line. -ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S - -# List Assembler source files here which must be assembled in ARM-Mode.. -ASRCARM = - -# List any extra directories to look for include files here. -# Each directory must be seperated by a space. -EXTRAINCDIRS += $(PIOS) -EXTRAINCDIRS += $(PIOSINC) -EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(PIOSSTM32F10X) -EXTRAINCDIRS += $(PIOSCOMMON) -EXTRAINCDIRS += $(PIOSBOARDS) -EXTRAINCDIRS += $(STMSPDINCDIR) -EXTRAINCDIRS += $(CMSISDIR) -EXTRAINCDIRS += $(INSINC) -EXTRAINCDIRS += $(OPUAVSYNTHDIR) -EXTRAINCDIRS += $(BOOTINC) -EXTRAINCDIRS += $(HWDEFSINC) - -# List any extra directories to look for library files here. -# Also add directories where the linker should search for -# includes from linker-script to the list -# Each directory must be seperated by a space. -EXTRA_LIBDIRS = - -# Extra Libraries -# Each library-name must be seperated by a space. -# i.e. to link with libxyz.a, libabc.a and libefsl.a: -# EXTRA_LIBS = xyz abc efsl -# for newlib-lpc (file: libnewlibc-lpc.a): -# EXTRA_LIBS = newlib-lpc -EXTRA_LIBS = - -# Path to Linker-Scripts -LINKERSCRIPTPATH = $(PIOSSTM32F10X) - -# Optimization level, can be [0, 1, 2, 3, s]. -# 0 = turn off optimization. s = optimize for size. -# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) - -ifeq ($(DEBUG),YES) -CFLAGS += -Os -CFLAGS += -DGENERAL_COV -else -CFLAGS += -Os -endif - -# Output format. (can be ihex or binary or both) -# binary to create a load-image in raw-binary format i.e. for SAM-BA, -# ihex to create a load-image in Intel hex format -#LOADFORMAT = ihex -#LOADFORMAT = binary -LOADFORMAT = both - -# Debugging format. -DEBUGF = dwarf-2 - -# Place project-specific -D (define) and/or -# -U options for C here. -CDEFS = -DSTM32F10X_$(MODEL) -CDEFS += -DUSE_STDPERIPH_DRIVER -CDEFS += -DUSE_$(BOARD) -CDEFS += -DIN_INS - -# Place project-specific -D and/or -U options for -# Assembler with preprocessor here. -#ADEFS = -DUSE_IRQ_ASM_WRAPPER -ADEFS = -D__ASSEMBLY__ - -# Compiler flag to set the C Standard level. -# c89 - "ANSI" C -# gnu89 - c89 plus GCC extensions -# c99 - ISO C99 standard (not yet fully implemented) -# gnu99 - c99 plus GCC extensions -CSTANDARD = -std=gnu99 - -#----- - -# Compiler flags. - -# -g*: generate debugging information -# -O*: optimization level -# -f...: tuning, see GCC manual and avr-libc documentation -# -Wall...: warning level -# -Wa,...: tell GCC to pass this to the assembler. -# -adhlns...: create assembler listing -# -# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) - - -ifeq ($(DEBUG),YES) -CFLAGS += -g$(DEBUGF) #-DDEBUG -else -CFLAGS += -g$(DEBUGF) -endif - - -CFLAGS += -ffast-math - -CFLAGS += -mcpu=$(MCU) -CFLAGS += $(CDEFS) -CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. - -CFLAGS += -mapcs-frame -CFLAGS += -fomit-frame-pointer -ifeq ($(CODE_SOURCERY), YES) -CFLAGS += -fpromote-loop-indices -endif - -CFLAGS += -Wall -#CFLAGS += -Werror -CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) -# Compiler flags to generate dependency files: -CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d - -# flags only for C -#CONLYFLAGS += -Wnested-externs -CONLYFLAGS += $(CSTANDARD) - -# Assembler flags. -# -Wa,...: tell GCC to pass this to the assembler. -# -ahlns: create listing -ASFLAGS = -mcpu=$(MCU) -I. -x assembler-with-cpp -ASFLAGS += $(ADEFS) -ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) -ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) - -MATH_LIB = -lm - -# Linker flags. -# -Wl,...: tell GCC to pass this to linker. -# -Map: create map file -# --cref: add cross reference to map file -LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections -LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) -LDFLAGS += -lc -LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) -LDFLAGS += $(MATH_LIB) -LDFLAGS += -lc -lgcc - -# Set linker-script name depending on selected submodel name -LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_memory.ld -LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_sections.ld - -# Define programs and commands. -REMOVE = $(REMOVE_CMD) -f - -# List of all source files. -ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) -# List of all source files without directory and file-extension. -ALLSRCBASE = $(notdir $(basename $(ALLSRC))) - -# Define all object files. -ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) - -# Define all listing files (used for make clean). -LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) -# Define all depedency-files (used for make clean). -DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) - -# Default target. -all: gccversion build - -ifeq ($(LOADFORMAT),ihex) -build: elf hex lss sym -else -ifeq ($(LOADFORMAT),binary) -build: elf bin lss sym -else -ifeq ($(LOADFORMAT),both) -build: elf hex bin lss sym -else -$(error "$(MSG_FORMATERROR) $(FORMAT)") -endif -endif -endif - -# Link: create ELF output file from object files. -$(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ))) - -# Assemble: create object files from assembler source files. -$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) - -# Assemble: create object files from assembler source files. ARM-only -$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) - -# Compile: create object files from C source files. -$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) - -# Compile: create object files from C source files. ARM-only -$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) - -# Compile: create object files from C++ source files. -$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) - -# Compile: create object files from C++ source files. ARM-only -$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) - -# Compile: create assembler files from C source files. ARM/Thumb -$(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC)) - -# Compile: create assembler files from C source files. ARM only -$(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) - -$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin - -$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) - -# Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) - -.PHONY: elf lss sym hex bin bino opfw -elf: $(OUTDIR)/$(TARGET).elf -lss: $(OUTDIR)/$(TARGET).lss -sym: $(OUTDIR)/$(TARGET).sym -hex: $(OUTDIR)/$(TARGET).hex -bin: $(OUTDIR)/$(TARGET).bin -bino: $(OUTDIR)/$(TARGET).bin.o -opfw: $(OUTDIR)/$(TARGET).opfw - -# Display sizes of sections. -$(eval $(call SIZE_TEMPLATE, $(OUTDIR)/$(TARGET).elf)) - -# Generate Doxygen documents -docs: - doxygen $(DOXYGENDIR)/doxygen.cfg - -# Install: install binary file with prefix/suffix into install directory -install: $(OUTDIR)/$(TARGET).opfw -ifneq ($(INSTALL_DIR),) - @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) mkdir -p $(INSTALL_DIR) - $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).opfw -else - $(error INSTALL_DIR must be specified for $@) -endif - -# Target: clean project. -clean: clean_list - -clean_list : - @echo $(MSG_CLEANING) - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).map - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).elf - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).hex - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).sym - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).lss - $(V1) $(REMOVE) $(ALLOBJ) - $(V1) $(REMOVE) $(LSTFILES) - $(V1) $(REMOVE) $(DEPFILES) - $(V1) $(REMOVE) $(SRC:.c=.s) - $(V1) $(REMOVE) $(SRCARM:.c=.s) - $(V1) $(REMOVE) $(CPPSRC:.cpp=.s) - $(V1) $(REMOVE) $(CPPSRCARM:.cpp=.s) - -# Create output files directory -# all known MS Windows OS define the ComSpec environment variable -ifdef ComSpec -$(shell md $(subst /,\\,$(OUTDIR)) 2>NUL) -else -$(shell mkdir -p $(OUTDIR) 2>/dev/null) -endif - -# Include the dependency files. -ifdef ComSpec --include $(shell md $(subst /,\\,$(OUTDIR))\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) -else --include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) -endif - -# Listing of phony targets. -.PHONY : all build clean clean_list install diff --git a/flight/INS/inc/ins.h b/flight/INS/inc/ins.h deleted file mode 100644 index 90fd57476..000000000 --- a/flight/INS/inc/ins.h +++ /dev/null @@ -1,129 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup INS INS - - * @brief The main INS headers - * - * @{ - * @addtogroup INS_Main - * @brief INS headers - * @{ - * - * @file ins.h - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @brief INS Headers - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef INS_H -#define INS_H - -/* PIOS Includes */ -#include - -struct mag_sensor { - uint8_t id[4]; - uint8_t updated; - struct { - int16_t axis[3]; - } raw; - struct { - float axis[3]; - } scaled; - struct { - float bias[3]; - float scale[3]; - float variance[3]; - } calibration; -}; - -//! Contains the data from the accelerometer -struct accel_sensor { - struct { - uint16_t x; - uint16_t y; - uint16_t z; - } raw; - struct { - float x; - float y; - float z; - } filtered; - struct { - float scale[3][4]; - float variance[3]; - } calibration; -}; - -//! Contains the data from the gyro -struct gyro_sensor { - struct { - uint16_t x; - uint16_t y; - uint16_t z; - } raw; - struct { - float x; - float y; - float z; - } filtered; - struct { - float bias[3]; - float scale[3]; - float variance[3]; - float tempcompfactor[3]; - } calibration; - struct { - uint16_t xy; - uint16_t z; - } temp; -}; - -//! Conains the current estimate of the attitude -struct attitude_solution { - struct { - float q1; - float q2; - float q3; - float q4; - } quaternion; -}; - -//! Contains data from the altitude sensor -struct altitude_sensor { - float altitude; - bool updated; -}; - -//! Contains data from the GPS (via the SPI link) -struct gps_sensor { - float NED[3]; - float heading; - float groundspeed; - float quality; - bool updated; -}; - -#endif /* INS_H */ - -/** - * @} - * @} - */ diff --git a/flight/INS/inc/pios_config.h b/flight/INS/inc/pios_config.h deleted file mode 100644 index a13394179..000000000 --- a/flight/INS/inc/pios_config.h +++ /dev/null @@ -1,62 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup INS INS - - * @brief The INS configuration - * - * @{ - * @addtogroup INS_Main - * @brief INS configuration - * @{ - * - * @file pios_config.h - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @brief PiOS configuration header. - * - Central compile time config for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_I2C -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SPI -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_USART -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_GPS -#define PIOS_INCLUDE_HMC5883 -#define PIOS_INCLUDE_BMP085 -#define PIOS_INCLUDE_IMU3000 -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_EXTI -#define PIOS_INCLUDE_IAP - -#define PIOS_INCLUDE_BMA180 - -#endif /* PIOS_CONFIG_H */ -/** - * @} - * @} - */ diff --git a/flight/INS/ins.c b/flight/INS/ins.c deleted file mode 100644 index 2fe538acc..000000000 --- a/flight/INS/ins.c +++ /dev/null @@ -1,218 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup INS INS - - * @brief The INS Modules perform - * - * @{ - * @addtogroup INS_Main - * @brief Main function which does the hardware dependent stuff - * @{ - * - * - * @file ins.c - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @brief INSGPS Test Program - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* OpenPilot Includes */ -#include "ins.h" -#include "pios.h" -#include -#include "fifo_buffer.h" - -void reset_values(); - -/** - * @addtogroup INS_Global_Data INS Global Data - * @{ - * Public data. Used by both EKF and the sender - */ - -//! Contains the data from the mag sensor chip -struct mag_sensor mag_data; - -//! Contains the data from the accelerometer -struct accel_sensor accel_data; - -//! Contains the data from the gyro -struct gyro_sensor gyro_data; - -//! Conains the current estimate of the attitude -struct attitude_solution attitude_data; - -//! Contains data from the altitude sensor -struct altitude_sensor altitude_data; - -//! Contains data from the GPS (via the SPI link) -struct gps_sensor gps_data; - -//! Offset correction of barometric alt, to match gps data -//static float baro_offset = 0; - -//static float mag_len = 0; - -typedef enum { INS_IDLE, INS_DATA_READY, INS_PROCESSING } states; -volatile int32_t ekf_too_slow; -volatile int32_t total_conversion_blocks; - -/** - * @} - */ - -/* INS functions */ -void blink(int led, int times) -{ - for(int i=0; i - -#if 0 -#define PIOS_COM_AUX_TX_BUF_LEN 192 -static uint8_t pios_com_aux_tx_buffer[PIOS_COM_AUX_TX_BUF_LEN]; -#endif - -#define PIOS_COM_GPS_RX_BUF_LEN 96 -static uint8_t pios_com_gps_rx_buffer[PIOS_COM_GPS_RX_BUF_LEN]; - -uint32_t pios_com_aux_id; -uint32_t pios_com_gps_id; - -/** - * PIOS_Board_Init() - * initializes all the core subsystems on this specific hardware - * called from System/openpilot.c - */ -void PIOS_Board_Init(void) { - /* Brings up System using CMSIS functions, enables the LEDs. */ - PIOS_SYS_Init(); - -#if defined(PIOS_INCLUDE_LED) - PIOS_LED_Init(&pios_led_cfg); -#endif /* PIOS_INCLUDE_LED */ - - /* Delay system */ - PIOS_DELAY_Init(); - - /* IAP System Setup */ - PIOS_IAP_Init(); - -#if defined(PIOS_INCLUDE_COM) -#if defined(PIOS_INCLUDE_GPS) - uint32_t pios_usart_gps_id; - if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) { - PIOS_DEBUG_Assert(0); - } - if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, - pios_com_gps_rx_buffer, sizeof(pios_com_gps_rx_buffer), - NULL, 0)) { - PIOS_DEBUG_Assert(0); - } -#endif /* PIOS_INCLUDE_GPS */ -#endif /* PIOS_INCLUDE_COM */ - -#if defined (PIOS_INCLUDE_I2C) - if (PIOS_I2C_Init(&pios_i2c_pres_mag_adapter_id, &pios_i2c_pres_mag_adapter_cfg)) { - PIOS_DEBUG_Assert(0); - } -#if defined (PIOS_INCLUDE_BMP085) - PIOS_BMP085_Init(); -#endif /* PIOS_INCLUDE_BMP085 */ -#if defined (PIOS_INCLUDE_HMC5883) - PIOS_HMC5883_Init(); -#endif /* PIOS_INCLUDE_HMC5883 */ - -#if defined(PIOS_INCLUDE_IMU3000) - if (PIOS_I2C_Init(&pios_i2c_gyro_adapter_id, &pios_i2c_gyro_adapter_cfg)) { - PIOS_DEBUG_Assert(0); - } - PIOS_IMU3000_Init(); -#endif /* PIOS_INCLUDE_IMU3000 */ -#endif /* PIOS_INCLUDE_I2C */ - -#if defined(PIOS_INCLUDE_SPI) - /* Set up the SPI interface to the accelerometer*/ - if (PIOS_SPI_Init(&pios_spi_accel_id, &pios_spi_accel_cfg)) { - PIOS_DEBUG_Assert(0); - } - - PIOS_BMA180_Attach(pios_spi_accel_id); - -// #include "ahrs_spi_comm.h" -// InsInitComms(); -// -// /* Set up the SPI interface to the OP board */ -// if (PIOS_SPI_Init(&pios_spi_op_id, &pios_spi_op_cfg)) { -// PIOS_DEBUG_Assert(0); -// } -// -// InsConnect(pios_spi_op_id); -#endif /* PIOS_INCLUDE_SPI */ -} - -/** - * @} - * @} - */ - diff --git a/flight/Libraries/CoordinateConversions.c b/flight/Libraries/CoordinateConversions.c index be8f03a15..732dcb92d 100644 --- a/flight/Libraries/CoordinateConversions.c +++ b/flight/Libraries/CoordinateConversions.c @@ -31,16 +31,17 @@ #include #include "CoordinateConversions.h" -#define RAD2DEG (180.0/M_PI) -#define DEG2RAD (M_PI/180.0) +#define F_PI 3.14159265358979323846f +#define RAD2DEG (180.0f/ F_PI) +#define DEG2RAD (F_PI /180.0f) // ****** convert Lat,Lon,Alt to ECEF ************ -void LLA2ECEF(double LLA[3], double ECEF[3]) +void LLA2ECEF(float LLA[3], float ECEF[3]) { - const double a = 6378137.0; // Equatorial Radius - const double e = 8.1819190842622e-2; // Eccentricity - double sinLat, sinLon, cosLat, cosLon; - double N; + const float a = 6378137.0; // Equatorial Radius + const float e = 8.1819190842622e-2; // Eccentricity + float sinLat, sinLon, cosLat, cosLon; + float N; sinLat = sin(DEG2RAD * LLA[0]); sinLon = sin(DEG2RAD * LLA[1]); @@ -55,7 +56,7 @@ void LLA2ECEF(double LLA[3], double ECEF[3]) } // ****** convert ECEF to Lat,Lon,Alt (ITERATIVE!) ********* -uint16_t ECEF2LLA(double ECEF[3], double LLA[3]) +uint16_t ECEF2LLA(float ECEF[3], float LLA[3]) { /** * LLA parameter is used to prime the iteration. @@ -66,10 +67,10 @@ uint16_t ECEF2LLA(double ECEF[3], double LLA[3]) * Suggestion: [0,0,0] **/ - const double a = 6378137.0; // Equatorial Radius - const double e = 8.1819190842622e-2; // Eccentricity - double x = ECEF[0], y = ECEF[1], z = ECEF[2]; - double Lat, N, NplusH, delta, esLat; + const float a = 6378137.0; // Equatorial Radius + const float e = 8.1819190842622e-2; // Eccentricity + float x = ECEF[0], y = ECEF[1], z = ECEF[2]; + float Lat, N, NplusH, delta, esLat; uint16_t iter; #define MAX_ITER 10 // should not take more than 5 for valid coordinates #define ACCURACY 1.0e-11 // used to be e-14, but we don't need sub micrometer exact calculations @@ -99,7 +100,7 @@ uint16_t ECEF2LLA(double ECEF[3], double LLA[3]) } // ****** find ECEF to NED rotation matrix ******** -void RneFromLLA(double LLA[3], float Rne[3][3]) +void RneFromLLA(float LLA[3], float Rne[3][3]) { float sinLat, sinLon, cosLat, cosLon; @@ -128,10 +129,10 @@ void Quaternion2RPY(const float q[4], float rpy[3]) float q2s = q[2] * q[2]; float q3s = q[3] * q[3]; - R13 = 2 * (q[1] * q[3] - q[0] * q[2]); + R13 = 2.0f * (q[1] * q[3] - q[0] * q[2]); R11 = q0s + q1s - q2s - q3s; - R12 = 2 * (q[1] * q[2] + q[0] * q[3]); - R23 = 2 * (q[2] * q[3] + q[0] * q[1]); + R12 = 2.0f * (q[1] * q[2] + q[0] * q[3]); + R23 = 2.0f * (q[2] * q[3] + q[0] * q[1]); R33 = q0s - q1s - q2s + q3s; rpy[1] = RAD2DEG * asinf(-R13); // pitch always between -pi/2 to pi/2 @@ -188,9 +189,9 @@ void Quaternion2R(float q[4], float Rbe[3][3]) } // ****** Express LLA in a local NED Base Frame ******** -void LLA2Base(double LLA[3], double BaseECEF[3], float Rne[3][3], float NED[3]) +void LLA2Base(float LLA[3], float BaseECEF[3], float Rne[3][3], float NED[3]) { - double ECEF[3]; + float ECEF[3]; float diff[3]; LLA2ECEF(LLA, ECEF); @@ -205,7 +206,7 @@ void LLA2Base(double LLA[3], double BaseECEF[3], float Rne[3][3], float NED[3]) } // ****** Express ECEF in a local NED Base Frame ******** -void ECEF2Base(double ECEF[3], double BaseECEF[3], float Rne[3][3], float NED[3]) +void ECEF2Base(float ECEF[3], float BaseECEF[3], float Rne[3][3], float NED[3]) { float diff[3]; @@ -239,7 +240,7 @@ void R2Quaternion(float R[3][3], float q[4]) index = i; } } - mag = 2*sqrt(mag); + mag = 2*sqrtf(mag); if (index == 0) { q[0] = mag/4; @@ -373,7 +374,7 @@ void CrossProduct(const float v1[3], const float v2[3], float result[3]) // ****** Vector Magnitude ******** float VectorMagnitude(const float v[3]) { - return(sqrt(v[0]*v[0] + v[1]*v[1] + v[2]*v[2])); + return(sqrtf(v[0]*v[0] + v[1]*v[1] + v[2]*v[2])); } /** diff --git a/flight/PipXtreme/aes.c b/flight/Libraries/aes.c similarity index 100% rename from flight/PipXtreme/aes.c rename to flight/Libraries/aes.c diff --git a/flight/Libraries/ahrs_comm_objects.c b/flight/Libraries/ahrs_comm_objects.c index 0f98e6a6c..3bc3bff3c 100644 --- a/flight/Libraries/ahrs_comm_objects.c +++ b/flight/Libraries/ahrs_comm_objects.c @@ -30,15 +30,16 @@ static AttitudeRawData AttitudeRaw; static AttitudeActualData AttitudeActual; -static AHRSCalibrationData AHRSCalibration; -static AhrsStatusData AhrsStatus; static BaroAltitudeData BaroAltitude; static GPSPositionData GPSPosition; +static HomeLocationData HomeLocation; +static InsStatusData InsStatus; +static InsSettingsData InsSettings; +static FirmwareIAPObjData FirmwareIAPObj; static PositionActualData PositionActual; static VelocityActualData VelocityActual; -static HomeLocationData HomeLocation; -static AHRSSettingsData AHRSSettings; -static FirmwareIAPObjData FirmwareIAPObj; +static GPSSatellitesData GPSSatellites; +static GPSTimeData GPSTime; AhrsSharedObject objectHandles[MAX_AHRS_OBJECTS]; @@ -54,17 +55,18 @@ AhrsSharedObject objectHandles[MAX_AHRS_OBJECTS]; CREATEHANDLE(0, AttitudeRaw); CREATEHANDLE(1, AttitudeActual); -CREATEHANDLE(2, AHRSCalibration); -CREATEHANDLE(3, AhrsStatus); +CREATEHANDLE(2, InsSettings); +CREATEHANDLE(3, InsStatus); CREATEHANDLE(4, BaroAltitude); CREATEHANDLE(5, GPSPosition); CREATEHANDLE(6, PositionActual); CREATEHANDLE(7, VelocityActual); CREATEHANDLE(8, HomeLocation); -CREATEHANDLE(9, AHRSSettings); -CREATEHANDLE(10, FirmwareIAPObj); +CREATEHANDLE(9, FirmwareIAPObj); +CREATEHANDLE(10, GPSSatellites); +CREATEHANDLE(11, GPSTime); -#if 11 != MAX_AHRS_OBJECTS //sanity check +#if 12 != MAX_AHRS_OBJECTS //sanity check #error We did not create the correct number of xxxHandle() functions #endif @@ -97,15 +99,17 @@ void AhrsInitHandles(void) //the last has the lowest priority ADDHANDLE(idx++, AttitudeRaw); ADDHANDLE(idx++, AttitudeActual); - ADDHANDLE(idx++, AHRSCalibration); - ADDHANDLE(idx++, AhrsStatus); + ADDHANDLE(idx++, InsSettings); + ADDHANDLE(idx++, InsStatus); ADDHANDLE(idx++, BaroAltitude); ADDHANDLE(idx++, GPSPosition); ADDHANDLE(idx++, PositionActual); ADDHANDLE(idx++, VelocityActual); ADDHANDLE(idx++, HomeLocation); - ADDHANDLE(idx++, AHRSSettings); ADDHANDLE(idx++, FirmwareIAPObj); + ADDHANDLE(idx++, GPSSatellites); + ADDHANDLE(idx++, GPSTime); + if (idx != MAX_AHRS_OBJECTS) { PIOS_DEBUG_Assert(0); } @@ -113,11 +117,8 @@ void AhrsInitHandles(void) //When the AHRS writes to these the data does a round trip //AHRS->OP->AHRS due to these events #ifndef IN_AHRS - AHRSSettingsConnectCallback(ObjectUpdatedCb); - BaroAltitudeConnectCallback(ObjectUpdatedCb); - GPSPositionConnectCallback(ObjectUpdatedCb); + InsSettingsConnectCallback(ObjectUpdatedCb); HomeLocationConnectCallback(ObjectUpdatedCb); - AHRSCalibrationConnectCallback(ObjectUpdatedCb); FirmwareIAPObjConnectCallback(ObjectUpdatedCb); #endif } diff --git a/flight/Libraries/ahrs_spi_comm.c b/flight/Libraries/ahrs_spi_comm.c index 9ee2ea206..9c6f65d70 100644 --- a/flight/Libraries/ahrs_spi_comm.c +++ b/flight/Libraries/ahrs_spi_comm.c @@ -33,7 +33,7 @@ #include "pios_spi.h" #include "pios_irq.h" #include "ahrs_spi_program_slave.h" -#include "STM32103CB_AHRS.h" +//#include "STM32103CB_AHRS.h" #endif /*transmit and receive packet magic numbers. @@ -53,7 +53,7 @@ typedef enum { COMMS_NULL, COMMS_OBJECT } COMMSCOMMAND; //The maximum number of objects that can be updated in one cycle. //Currently the link is capable of sending 3 packets per cycle but 2 is enough -#define MAX_UPDATE_OBJECTS 1 +#define MAX_UPDATE_OBJECTS 2 //Number of transmissions + 1 before we expect to see the data acknowledge //This is controlled by the SPI hardware. @@ -298,13 +298,11 @@ int32_t AhrsConnectCallBack(AhrsObjHandle obj, AhrsEventCallback cb) return (0); } -AhrsCommStatus AhrsGetStatus() +void AhrsGetStatus(AhrsCommStatus * status) { - AhrsCommStatus status; - status.remote = rxPacket.status; - status.local = txPacket.status; - status.linkOk = linkOk; - return (status); + status->remote = rxPacket.status; + status->local = txPacket.status; + status->linkOk = linkOk; } @@ -439,7 +437,9 @@ void AhrsSendObjects(void) void SendPacket(void) { +#ifndef IN_AHRS PIOS_SPI_RC_PinSet(opahrs_spi_id, 0); +#endif //no point checking if this failed. There isn't much we could do about it if it did fail PIOS_SPI_TransferBlock(opahrs_spi_id, (uint8_t *) & txPacket, (uint8_t *) & rxPacket, sizeof(CommsDataPacket), &CommsCallback); } diff --git a/flight/Libraries/fifo_buffer.c b/flight/Libraries/fifo_buffer.c index 7c5262c7d..7b68fcf09 100644 --- a/flight/Libraries/fifo_buffer.c +++ b/flight/Libraries/fifo_buffer.c @@ -1,266 +1,266 @@ -/** - ****************************************************************************** - * - * @file fifo_buffer.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief GPIO input functions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include - -#include "fifo_buffer.h" - -// ***************************************************************************** -// circular buffer functions - -uint16_t fifoBuf_getSize(t_fifo_buffer *buf) -{ // return the usable size of the buffer - - uint16_t buf_size = buf->buf_size; - - if (buf_size > 0) - return (buf_size - 1); - else - return 0; -} - -uint16_t fifoBuf_getUsed(t_fifo_buffer *buf) -{ // return the number of bytes available in the rx buffer - - uint16_t rd = buf->rd; - uint16_t wr = buf->wr; - uint16_t buf_size = buf->buf_size; - - uint16_t num_bytes = wr - rd; - if (wr < rd) - num_bytes = (buf_size - rd) + wr; - - return num_bytes; -} - -uint16_t fifoBuf_getFree(t_fifo_buffer *buf) -{ // return the free space size in the buffer - - uint16_t buf_size = buf->buf_size; - - uint16_t num_bytes = fifoBuf_getUsed(buf); - - return ((buf_size - num_bytes) - 1); -} - -void fifoBuf_clearData(t_fifo_buffer *buf) -{ // remove all data from the buffer - buf->rd = buf->wr; -} - -void fifoBuf_removeData(t_fifo_buffer *buf, uint16_t len) -{ // remove a number of bytes from the buffer - - uint16_t rd = buf->rd; - uint16_t buf_size = buf->buf_size; - - // get number of bytes available - uint16_t num_bytes = fifoBuf_getUsed(buf); - - if (num_bytes > len) - num_bytes = len; - - if (num_bytes < 1) - return; // nothing to remove - - rd += num_bytes; - if (rd >= buf_size) - rd -= buf_size; - - buf->rd = rd; -} - -int16_t fifoBuf_getBytePeek(t_fifo_buffer *buf) -{ // get a data byte from the buffer without removing it - - uint16_t rd = buf->rd; - - // get number of bytes available - uint16_t num_bytes = fifoBuf_getUsed(buf); - - if (num_bytes < 1) - return -1; // no byte retuened - - return buf->buf_ptr[rd]; // return the byte -} - -int16_t fifoBuf_getByte(t_fifo_buffer *buf) -{ // get a data byte from the buffer - - uint16_t rd = buf->rd; - uint16_t buf_size = buf->buf_size; - uint8_t *buff = buf->buf_ptr; - - // get number of bytes available - uint16_t num_bytes = fifoBuf_getUsed(buf); - - if (num_bytes < 1) - return -1; // no byte returned - - uint8_t b = buff[rd]; - if (++rd >= buf_size) - rd = 0; - - buf->rd = rd; - - return b; // return the byte -} - -uint16_t fifoBuf_getDataPeek(t_fifo_buffer *buf, void *data, uint16_t len) -{ // get data from the buffer without removing it - - uint16_t rd = buf->rd; - uint16_t buf_size = buf->buf_size; - uint8_t *buff = buf->buf_ptr; - - // get number of bytes available - uint16_t num_bytes = fifoBuf_getUsed(buf); - - if (num_bytes > len) - num_bytes = len; - - if (num_bytes < 1) - return 0; // return number of bytes copied - - uint8_t *p = (uint8_t *)data; - uint16_t i = 0; - - while (num_bytes > 0) - { - uint16_t j = buf_size - rd; - if (j > num_bytes) - j = num_bytes; - memcpy(p + i, buff + rd, j); - i += j; - num_bytes -= j; - rd += j; - if (rd >= buf_size) - rd = 0; - } - - return i; // return number of bytes copied -} - -uint16_t fifoBuf_getData(t_fifo_buffer *buf, void *data, uint16_t len) -{ // get data from our rx buffer - - uint16_t rd = buf->rd; - uint16_t buf_size = buf->buf_size; - uint8_t *buff = buf->buf_ptr; - - // get number of bytes available - uint16_t num_bytes = fifoBuf_getUsed(buf); - - if (num_bytes > len) - num_bytes = len; - - if (num_bytes < 1) - return 0; // return number of bytes copied - - uint8_t *p = (uint8_t *)data; - uint16_t i = 0; - - while (num_bytes > 0) - { - uint16_t j = buf_size - rd; - if (j > num_bytes) - j = num_bytes; - memcpy(p + i, buff + rd, j); - i += j; - num_bytes -= j; - rd += j; - if (rd >= buf_size) - rd = 0; - } - - buf->rd = rd; - - return i; // return number of bytes copied -} - -uint16_t fifoBuf_putByte(t_fifo_buffer *buf, const uint8_t b) -{ // add a data byte to the buffer - - uint16_t wr = buf->wr; - uint16_t buf_size = buf->buf_size; - uint8_t *buff = buf->buf_ptr; - - uint16_t num_bytes = fifoBuf_getFree(buf); - if (num_bytes < 1) - return 0; - - buff[wr] = b; - if (++wr >= buf_size) - wr = 0; - - buf->wr = wr; - - return 1; // return number of bytes copied -} - -uint16_t fifoBuf_putData(t_fifo_buffer *buf, const void *data, uint16_t len) -{ // add data to the buffer - - uint16_t wr = buf->wr; - uint16_t buf_size = buf->buf_size; - uint8_t *buff = buf->buf_ptr; - - uint16_t num_bytes = fifoBuf_getFree(buf); - if (num_bytes > len) - num_bytes = len; - - if (num_bytes < 1) - return 0; // return number of bytes copied - - uint8_t *p = (uint8_t *)data; - uint16_t i = 0; - - while (num_bytes > 0) - { - uint16_t j = buf_size - wr; - if (j > num_bytes) - j = num_bytes; - memcpy(buff + wr, p + i, j); - i += j; - num_bytes -= j; - wr += j; - if (wr >= buf_size) - wr = 0; - } - - buf->wr = wr; - - return i; // return number of bytes copied -} - -void fifoBuf_init(t_fifo_buffer *buf, const void *buffer, const uint16_t buffer_size) -{ - buf->buf_ptr = (uint8_t *)buffer; - buf->rd = 0; - buf->wr = 0; - buf->buf_size = buffer_size; -} - -// ***************************************************************************** +/** + ****************************************************************************** + * + * @file fifo_buffer.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief GPIO input functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include + +#include "fifo_buffer.h" + +// ***************************************************************************** +// circular buffer functions + +uint16_t fifoBuf_getSize(t_fifo_buffer *buf) +{ // return the usable size of the buffer + + uint16_t buf_size = buf->buf_size; + + if (buf_size > 0) + return (buf_size - 1); + else + return 0; +} + +uint16_t fifoBuf_getUsed(t_fifo_buffer *buf) +{ // return the number of bytes available in the rx buffer + + uint16_t rd = buf->rd; + uint16_t wr = buf->wr; + uint16_t buf_size = buf->buf_size; + + uint16_t num_bytes = wr - rd; + if (wr < rd) + num_bytes = (buf_size - rd) + wr; + + return num_bytes; +} + +uint16_t fifoBuf_getFree(t_fifo_buffer *buf) +{ // return the free space size in the buffer + + uint16_t buf_size = buf->buf_size; + + uint16_t num_bytes = fifoBuf_getUsed(buf); + + return ((buf_size - num_bytes) - 1); +} + +void fifoBuf_clearData(t_fifo_buffer *buf) +{ // remove all data from the buffer + buf->rd = buf->wr; +} + +void fifoBuf_removeData(t_fifo_buffer *buf, uint16_t len) +{ // remove a number of bytes from the buffer + + uint16_t rd = buf->rd; + uint16_t buf_size = buf->buf_size; + + // get number of bytes available + uint16_t num_bytes = fifoBuf_getUsed(buf); + + if (num_bytes > len) + num_bytes = len; + + if (num_bytes < 1) + return; // nothing to remove + + rd += num_bytes; + if (rd >= buf_size) + rd -= buf_size; + + buf->rd = rd; +} + +int16_t fifoBuf_getBytePeek(t_fifo_buffer *buf) +{ // get a data byte from the buffer without removing it + + uint16_t rd = buf->rd; + + // get number of bytes available + uint16_t num_bytes = fifoBuf_getUsed(buf); + + if (num_bytes < 1) + return -1; // no byte retuened + + return buf->buf_ptr[rd]; // return the byte +} + +int16_t fifoBuf_getByte(t_fifo_buffer *buf) +{ // get a data byte from the buffer + + uint16_t rd = buf->rd; + uint16_t buf_size = buf->buf_size; + uint8_t *buff = buf->buf_ptr; + + // get number of bytes available + uint16_t num_bytes = fifoBuf_getUsed(buf); + + if (num_bytes < 1) + return -1; // no byte returned + + uint8_t b = buff[rd]; + if (++rd >= buf_size) + rd = 0; + + buf->rd = rd; + + return b; // return the byte +} + +uint16_t fifoBuf_getDataPeek(t_fifo_buffer *buf, void *data, uint16_t len) +{ // get data from the buffer without removing it + + uint16_t rd = buf->rd; + uint16_t buf_size = buf->buf_size; + uint8_t *buff = buf->buf_ptr; + + // get number of bytes available + uint16_t num_bytes = fifoBuf_getUsed(buf); + + if (num_bytes > len) + num_bytes = len; + + if (num_bytes < 1) + return 0; // return number of bytes copied + + uint8_t *p = (uint8_t *)data; + uint16_t i = 0; + + while (num_bytes > 0) + { + uint16_t j = buf_size - rd; + if (j > num_bytes) + j = num_bytes; + memcpy(p + i, buff + rd, j); + i += j; + num_bytes -= j; + rd += j; + if (rd >= buf_size) + rd = 0; + } + + return i; // return number of bytes copied +} + +uint16_t fifoBuf_getData(t_fifo_buffer *buf, void *data, uint16_t len) +{ // get data from our rx buffer + + uint16_t rd = buf->rd; + uint16_t buf_size = buf->buf_size; + uint8_t *buff = buf->buf_ptr; + + // get number of bytes available + uint16_t num_bytes = fifoBuf_getUsed(buf); + + if (num_bytes > len) + num_bytes = len; + + if (num_bytes < 1) + return 0; // return number of bytes copied + + uint8_t *p = (uint8_t *)data; + uint16_t i = 0; + + while (num_bytes > 0) + { + uint16_t j = buf_size - rd; + if (j > num_bytes) + j = num_bytes; + memcpy(p + i, buff + rd, j); + i += j; + num_bytes -= j; + rd += j; + if (rd >= buf_size) + rd = 0; + } + + buf->rd = rd; + + return i; // return number of bytes copied +} + +uint16_t fifoBuf_putByte(t_fifo_buffer *buf, const uint8_t b) +{ // add a data byte to the buffer + + uint16_t wr = buf->wr; + uint16_t buf_size = buf->buf_size; + uint8_t *buff = buf->buf_ptr; + + uint16_t num_bytes = fifoBuf_getFree(buf); + if (num_bytes < 1) + return 0; + + buff[wr] = b; + if (++wr >= buf_size) + wr = 0; + + buf->wr = wr; + + return 1; // return number of bytes copied +} + +uint16_t fifoBuf_putData(t_fifo_buffer *buf, const void *data, uint16_t len) +{ // add data to the buffer + + uint16_t wr = buf->wr; + uint16_t buf_size = buf->buf_size; + uint8_t *buff = buf->buf_ptr; + + uint16_t num_bytes = fifoBuf_getFree(buf); + if (num_bytes > len) + num_bytes = len; + + if (num_bytes < 1) + return 0; // return number of bytes copied + + uint8_t *p = (uint8_t *)data; + uint16_t i = 0; + + while (num_bytes > 0) + { + uint16_t j = buf_size - wr; + if (j > num_bytes) + j = num_bytes; + memcpy(buff + wr, p + i, j); + i += j; + num_bytes -= j; + wr += j; + if (wr >= buf_size) + wr = 0; + } + + buf->wr = wr; + + return i; // return number of bytes copied +} + +void fifoBuf_init(t_fifo_buffer *buf, const void *buffer, const uint16_t buffer_size) +{ + buf->buf_ptr = (uint8_t *)buffer; + buf->rd = 0; + buf->wr = 0; + buf->buf_size = buffer_size; +} + +// ***************************************************************************** diff --git a/flight/Libraries/inc/CoordinateConversions.h b/flight/Libraries/inc/CoordinateConversions.h index 7f9013b28..020628d72 100644 --- a/flight/Libraries/inc/CoordinateConversions.h +++ b/flight/Libraries/inc/CoordinateConversions.h @@ -31,12 +31,12 @@ #define COORDINATECONVERSIONS_H_ // ****** convert Lat,Lon,Alt to ECEF ************ -void LLA2ECEF(double LLA[3], double ECEF[3]); +void LLA2ECEF(float LLA[3], float ECEF[3]); // ****** convert ECEF to Lat,Lon,Alt (ITERATIVE!) ********* -uint16_t ECEF2LLA(double ECEF[3], double LLA[3]); +uint16_t ECEF2LLA(float ECEF[3], float LLA[3]); -void RneFromLLA(double LLA[3], float Rne[3][3]); +void RneFromLLA(float LLA[3], float Rne[3][3]); // ****** find rotation matrix from rotation vector void Rv2Rot(float Rv[3], float R[3][3]); @@ -51,10 +51,10 @@ void RPY2Quaternion(const float rpy[3], float q[4]); void Quaternion2R(float q[4], float Rbe[3][3]); // ****** Express LLA in a local NED Base Frame ******** -void LLA2Base(double LLA[3], double BaseECEF[3], float Rne[3][3], float NED[3]); +void LLA2Base(float LLA[3], float BaseECEF[3], float Rne[3][3], float NED[3]); // ****** Express ECEF in a local NED Base Frame ******** -void ECEF2Base(double ECEF[3], double BaseECEF[3], float Rne[3][3], float NED[3]); +void ECEF2Base(float ECEF[3], float BaseECEF[3], float Rne[3][3], float NED[3]); // ****** convert Rotation Matrix to Quaternion ******** // ****** if R converts from e to b, q is rotation from e to b **** diff --git a/flight/PipXtreme/reserved/api_comms.h b/flight/Libraries/inc/NMEA.h similarity index 69% rename from flight/PipXtreme/reserved/api_comms.h rename to flight/Libraries/inc/NMEA.h index 9f9cece0f..c3f8b66d9 100644 --- a/flight/PipXtreme/reserved/api_comms.h +++ b/flight/Libraries/inc/NMEA.h @@ -1,40 +1,42 @@ -/** - ****************************************************************************** - * - * @file api_comms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RF Module hardware layer - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef __API_COMMS_H__ -#define __API_COMMS_H__ - -#include "stdint.h" - -// ***************************************************************************** - -void api_1ms_tick(void); -void api_process(void); - -void api_init(void); - -// ***************************************************************************** - -#endif +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup GSPModule GPS Module + * @brief Process GPS information + * @{ + * + * @file NMEA.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief GPS module, handles GPS and NMEA stream + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef NMEA_H +#define NMEA_H + +#include +#include + +#define NMEA_MAX_PACKET_LENGTH 96 + +extern bool NMEA_update_position(char *nmea_sentence); +extern bool NMEA_checksum(char *nmea_sentence); + +#endif /* NMEA_H */ diff --git a/flight/PipXtreme/inc/aes.h b/flight/Libraries/inc/aes.h similarity index 100% rename from flight/PipXtreme/inc/aes.h rename to flight/Libraries/inc/aes.h diff --git a/flight/Libraries/inc/ahrs_comm_objects.h b/flight/Libraries/inc/ahrs_comm_objects.h index 3b4ded2b7..f6c0cb380 100644 --- a/flight/Libraries/inc/ahrs_comm_objects.h +++ b/flight/Libraries/inc/ahrs_comm_objects.h @@ -29,36 +29,38 @@ #include "attitudeactual.h" #include "attituderaw.h" -#include "ahrsstatus.h" #include "baroaltitude.h" #include "gpsposition.h" +#include "homelocation.h" +#include "insstatus.h" +#include "inssettings.h" #include "positionactual.h" #include "velocityactual.h" -#include "homelocation.h" -#include "ahrscalibration.h" -#include "ahrssettings.h" #include "firmwareiapobj.h" - +#include "gpsposition.h" +#include "gpssatellites.h" +#include "gpstime.h" /** union that will fit any UAVObject. */ typedef union { AttitudeRawData AttitudeRaw; AttitudeActualData AttitudeActual; - AHRSCalibrationData AHRSCalibration; - AhrsStatusData AhrsStatus; + InsStatusData AhrsStatus; BaroAltitudeData BaroAltitude; GPSPositionData GPSPosition; PositionActualData PositionActual; VelocityActualData VelocityActual; HomeLocationData HomeLocation; - AHRSSettingsData AHRSSettings; + InsSettingsData InsSettings; FirmwareIAPObjData FirmwareIAPObj; + GPSSatellitesData GPSSatellites; + GPSTimeData GPSTime; } __attribute__ ((packed)) AhrsSharedData; /** The number of UAVObjects we will be dealing with. */ -#define MAX_AHRS_OBJECTS 11 +#define MAX_AHRS_OBJECTS 12 /** Our own version of a UAVObject. */ diff --git a/flight/Libraries/inc/ahrs_spi_comm.h b/flight/Libraries/inc/ahrs_spi_comm.h index 588f873ec..e86a1bb46 100644 --- a/flight/Libraries/inc/ahrs_spi_comm.h +++ b/flight/Libraries/inc/ahrs_spi_comm.h @@ -110,7 +110,7 @@ int32_t AhrsConnectCallBack(AhrsObjHandle obj, AhrsEventCallback cb); Returns: the status. Note: the remote status will only be valid if the link is up and running */ -AhrsCommStatus AhrsGetStatus(); +void AhrsGetStatus(AhrsCommStatus * status); #ifdef IN_AHRS //slave only /** Send the latest objects to the OP diff --git a/flight/Libraries/inc/fifo_buffer.h b/flight/Libraries/inc/fifo_buffer.h index 6e4955f7e..6ba85877e 100644 --- a/flight/Libraries/inc/fifo_buffer.h +++ b/flight/Libraries/inc/fifo_buffer.h @@ -1,65 +1,65 @@ -/** - ****************************************************************************** - * - * @file fifo_buffer.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief GPIO functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef _FIFO_BUFFER_H_ -#define _FIFO_BUFFER_H_ - -#include - -// ********************* - -typedef struct -{ - uint8_t *buf_ptr; - volatile uint16_t rd; - volatile uint16_t wr; - uint16_t buf_size; -} t_fifo_buffer; - -// ********************* - -uint16_t fifoBuf_getSize(t_fifo_buffer *buf); - -uint16_t fifoBuf_getUsed(t_fifo_buffer *buf); -uint16_t fifoBuf_getFree(t_fifo_buffer *buf); - -void fifoBuf_clearData(t_fifo_buffer *buf); -void fifoBuf_removeData(t_fifo_buffer *buf, uint16_t len); - -int16_t fifoBuf_getBytePeek(t_fifo_buffer *buf); -int16_t fifoBuf_getByte(t_fifo_buffer *buf); - -uint16_t fifoBuf_getDataPeek(t_fifo_buffer *buf, void *data, uint16_t len); -uint16_t fifoBuf_getData(t_fifo_buffer *buf, void *data, uint16_t len); - -uint16_t fifoBuf_putByte(t_fifo_buffer *buf, const uint8_t b); - -uint16_t fifoBuf_putData(t_fifo_buffer *buf, const void *data, uint16_t len); - -void fifoBuf_init(t_fifo_buffer *buf, const void *buffer, const uint16_t buffer_size); - -// ********************* - -#endif +/** + ****************************************************************************** + * + * @file fifo_buffer.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief GPIO functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef _FIFO_BUFFER_H_ +#define _FIFO_BUFFER_H_ + +#include "stdint.h" + +// ********************* + +typedef struct +{ + uint8_t *buf_ptr; + volatile uint16_t rd; + volatile uint16_t wr; + uint16_t buf_size; +} t_fifo_buffer; + +// ********************* + +uint16_t fifoBuf_getSize(t_fifo_buffer *buf); + +uint16_t fifoBuf_getUsed(t_fifo_buffer *buf); +uint16_t fifoBuf_getFree(t_fifo_buffer *buf); + +void fifoBuf_clearData(t_fifo_buffer *buf); +void fifoBuf_removeData(t_fifo_buffer *buf, uint16_t len); + +int16_t fifoBuf_getBytePeek(t_fifo_buffer *buf); +int16_t fifoBuf_getByte(t_fifo_buffer *buf); + +uint16_t fifoBuf_getDataPeek(t_fifo_buffer *buf, void *data, uint16_t len); +uint16_t fifoBuf_getData(t_fifo_buffer *buf, void *data, uint16_t len); + +uint16_t fifoBuf_putByte(t_fifo_buffer *buf, const uint8_t b); + +uint16_t fifoBuf_putData(t_fifo_buffer *buf, const void *data, uint16_t len); + +void fifoBuf_init(t_fifo_buffer *buf, const void *buffer, const uint16_t buffer_size); + +// ********************* + +#endif diff --git a/flight/AHRS/inc/insgps.h b/flight/Libraries/inc/insgps.h similarity index 100% rename from flight/AHRS/inc/insgps.h rename to flight/Libraries/inc/insgps.h diff --git a/flight/Libraries/inc/packet_handler.h b/flight/Libraries/inc/packet_handler.h new file mode 100644 index 000000000..b0bd8315c --- /dev/null +++ b/flight/Libraries/inc/packet_handler.h @@ -0,0 +1,121 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * + * @file packet_handler.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief A packet handler for handeling radio packet transmission. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef __PACKET_HANDLER_H__ +#define __PACKET_HANDLER_H__ + +// Public defines / macros +#define PHPacketSize(p) ((uint8_t*)(p->data) + p->header.data_size - (uint8_t*)p) +#define PHPacketSizeECC(p) ((uint8_t*)(p->data) + p->header.data_size + RS_ECC_NPARITY - (uint8_t*)p) + +// Public types +typedef enum { + PACKET_TYPE_NONE = 0, + PACKET_TYPE_CONNECT, // for requesting a connection + PACKET_TYPE_DISCONNECT, // to tell the other modem they cannot connect to us + PACKET_TYPE_READY, // tells the other modem we are ready to accept more data + PACKET_TYPE_NOTREADY, // tells the other modem we're not ready to accept more data - we can also send user data in this packet type + PACKET_TYPE_STATUS, // broadcasts status of this modem + PACKET_TYPE_DATARATE, // for changing the RF data rate + PACKET_TYPE_PING, // used to check link is still up + PACKET_TYPE_ADJUST_TX_PWR, // used to ask the other modem to adjust it's tx power + PACKET_TYPE_DATA, // data packet (packet contains user data) + PACKET_TYPE_ACKED_DATA, // data packet that requies an ACK + PACKET_TYPE_PPM, // PPM relay values + PACKET_TYPE_ACK, + PACKET_TYPE_NACK +} PHPacketType; + +typedef struct { + uint32_t destination_id; + uint32_t source_id; + uint8_t type; + uint8_t data_size; + uint8_t tx_seq; + uint8_t rx_seq; +} PHPacketHeader; + +#define PH_MAX_DATA (PIOS_PH_MAX_PACKET - sizeof(PHPacketHeader) - RS_ECC_NPARITY) +#define PH_PACKET_SIZE(p) (p->data + p->header.data_size - (uint8_t*)p + RS_ECC_NPARITY) +typedef struct { + PHPacketHeader header; + uint8_t data[PH_MAX_DATA + RS_ECC_NPARITY]; +} PHPacket, *PHPacketHandle; + +#define PH_PPM_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) +typedef struct { + PHPacketHeader header; + uint16_t channels[PIOS_RCVR_MAX_CHANNELS]; + uint8_t ecc[RS_ECC_NPARITY]; +} PHPpmPacket, *PHPpmPacketHandle; + +#define PH_STATUS_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) +typedef struct { + PHPacketHeader header; + uint16_t retries; + uint16_t errors; + uint16_t uavtalk_errors; + uint16_t dropped; + uint16_t resets; + uint8_t ecc[RS_ECC_NPARITY]; +} PHStatusPacket, *PHStatusPacketHandle; + +typedef struct { + uint8_t winSize; + uint16_t maxConnections; +} PacketHandlerConfig; + +typedef int32_t (*PHOutputStream)(PHPacketHandle packet); +typedef void (*PHDataHandler)(uint8_t *data, uint8_t len, int8_t rssi, int8_t afc); +typedef void (*PHStatusHandler)(PHStatusPacketHandle s, int8_t rssi, int8_t afc); +typedef void (*PHPPMHandler)(uint16_t *channels); + +typedef uint32_t PHInstHandle; + +// Public functions +PHInstHandle PHInitialize(PacketHandlerConfig *cfg); +void PHRegisterOutputStream(PHInstHandle h, PHOutputStream f); +void PHRegisterDataHandler(PHInstHandle h, PHDataHandler f); +void PHRegisterStatusHandler(PHInstHandle h, PHStatusHandler f); +void PHRegisterPPMHandler(PHInstHandle h, PHPPMHandler f); +uint32_t PHConnect(PHInstHandle h, uint32_t dest_id); +PHPacketHandle PHGetRXPacket(PHInstHandle h); +void PHReleaseTXPacket(PHInstHandle h, PHPacketHandle p); +PHPacketHandle PHGetTXPacket(PHInstHandle h); +void PHReleaseTXPacket(PHInstHandle h, PHPacketHandle p); +uint8_t PHTransmitPacket(PHInstHandle h, PHPacketHandle p); +int32_t PHVerifyPacket(PHInstHandle h, PHPacketHandle p, uint16_t received_len); +uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error); + +#endif // __PACKET_HANDLER_H__ + +/** + * @} + * @} + */ diff --git a/flight/AHRS/insgps13state.c b/flight/Libraries/insgps13state.c similarity index 96% rename from flight/AHRS/insgps13state.c rename to flight/Libraries/insgps13state.c index 24ffab1db..a9e45df56 100644 --- a/flight/AHRS/insgps13state.c +++ b/flight/Libraries/insgps13state.c @@ -76,36 +76,52 @@ uint16_t ins_get_num_states() void INSGPSInit() //pretty much just a place holder for now { - Be[0] = 1; - Be[1] = 0; - Be[2] = 0; // local magnetic unit vector + Be[0] = 1.0f; + Be[1] = 0.0f; + Be[2] = 0.0f; // local magnetic unit vector for (int i = 0; i < NUMX; i++) { for (int j = 0; j < NUMX; j++) { - P[i][j] = 0; // zero all terms + P[i][j] = 0.0f; // zero all terms + F[i][j] = 0.0f; } + + for (int j = 0; j < NUMW; j++) + G[i][j] = 0.0f; + + for (int j = 0; j < NUMV; j++) { + H[j][i] = 0.0f; + K[i][j] = 0.0f; + } + + X[i] = 0.0f; } + for (int i = 0; i < NUMW; i++) + Q[i] = 0.0f; + for (int i = 0; i < NUMV; i++) + R[i] = 0.0f; + - P[0][0] = P[1][1] = P[2][2] = 25; // initial position variance (m^2) - P[3][3] = P[4][4] = P[5][5] = 5; // initial velocity variance (m/s)^2 - P[6][6] = P[7][7] = P[8][8] = P[9][9] = 1e-5; // initial quaternion variance - P[10][10] = P[11][11] = P[12][12] = 1e-5; // initial gyro bias variance (rad/s)^2 + P[0][0] = P[1][1] = P[2][2] = 25.0f; // initial position variance (m^2) + P[3][3] = P[4][4] = P[5][5] = 5.0f; // initial velocity variance (m/s)^2 + P[6][6] = P[7][7] = P[8][8] = P[9][9] = 1e-5f; // initial quaternion variance + P[10][10] = P[11][11] = P[12][12] = 1e-9f; // initial gyro bias variance (rad/s)^2 - X[0] = X[1] = X[2] = X[3] = X[4] = X[5] = 0; // initial pos and vel (m) - X[6] = 1; - X[7] = X[8] = X[9] = 0; // initial quaternion (level and North) (m/s) - X[10] = X[11] = X[12] = 0; // initial gyro bias (rad/s) + X[0] = X[1] = X[2] = X[3] = X[4] = X[5] = 0.0f; // initial pos and vel (m) + X[6] = 1.0f; + X[7] = X[8] = X[9] = 0.0f; // initial quaternion (level and North) (m/s) + X[10] = X[11] = X[12] = 0.0f; // initial gyro bias (rad/s) - Q[0] = Q[1] = Q[2] = 50e-8; // gyro noise variance (rad/s)^2 - Q[3] = Q[4] = Q[5] = 0.01; // accelerometer noise variance (m/s^2)^2 - Q[6] = Q[7] = Q[8] = 2e-9; // gyro bias random walk variance (rad/s^2)^2 + Q[0] = Q[1] = Q[2] = 50e-4f; // gyro noise variance (rad/s)^2 + Q[3] = Q[4] = Q[5] = 0.00001f; // accelerometer noise variance (m/s^2)^2 + Q[6] = Q[7] = Q[8] = 2e-8f; // gyro bias random walk variance (rad/s^2)^2 - R[0] = R[1] = 0.004; // High freq GPS horizontal position noise variance (m^2) - R[2] = 0.036; // High freq GPS vertical position noise variance (m^2) - R[3] = R[4] = 0.004; // High freq GPS horizontal velocity noise variance (m/s)^2 - R[5] = 100; // High freq GPS vertical velocity noise variance (m/s)^2 - R[6] = R[7] = R[8] = 0.005; // magnetometer unit vector noise variance - R[9] = .05; // High freq altimeter noise variance (m^2) + R[0] = R[1] = 0.004f; // High freq GPS horizontal position noise variance (m^2) + R[2] = 0.036f; // High freq GPS vertical position noise variance (m^2) + R[3] = R[4] = 0.004f; // High freq GPS horizontal velocity noise variance (m/s)^2 + R[5] = 100.0f; // High freq GPS vertical velocity noise variance (m/s)^2 + R[6] = R[7] = R[8] = 0.005f; // magnetometer unit vector noise variance + R[9] = .05f; // High freq altimeter noise variance (m^2) } void INSResetP(float PDiag[NUMX]) @@ -116,7 +132,7 @@ void INSResetP(float PDiag[NUMX]) for (i=0;i 0.01) + dT = 0.01; + + // format data for INS algo + gyro[0] = gyro_data.filtered.x; + gyro[1] = gyro_data.filtered.y; + gyro[2] = gyro_data.filtered.z; + accel[0] = accel_data.filtered.x, + accel[1] = accel_data.filtered.y, + accel[2] = accel_data.filtered.z, + + INSStatePrediction(gyro, accel, dT); + attitude_data.quaternion.q1 = Nav.q[0]; + attitude_data.quaternion.q2 = Nav.q[1]; + attitude_data.quaternion.q3 = Nav.q[2]; + attitude_data.quaternion.q4 = Nav.q[3]; + send_attitude(); // get message out quickly + INSCovariancePrediction(dT); + + PositionActualData positionActual; + PositionActualGet(&positionActual); + positionActual.North = Nav.Pos[0]; + positionActual.East = Nav.Pos[1]; + positionActual.Down = Nav.Pos[2]; + PositionActualSet(&positionActual); + + VelocityActualData velocityActual; + VelocityActualGet(&velocityActual); + velocityActual.North = Nav.Vel[0]; + velocityActual.East = Nav.Vel[1]; + velocityActual.Down = Nav.Vel[2]; + VelocityActualSet(&velocityActual); + + sensors = 0; + + if (gps_data.updated) + { + vel[0] = gps_data.groundspeed * cos(gps_data.heading * DEG_TO_RAD); + vel[1] = gps_data.groundspeed * sin(gps_data.heading * DEG_TO_RAD); + vel[2] = 0; + + if (abs(gps_data.NED[0] - Nav.Pos[0]) > INSGPS_GPS_FAR || + abs(gps_data.NED[1] - Nav.Pos[1]) > INSGPS_GPS_FAR || + abs(gps_data.NED[2] - Nav.Pos[2]) > INSGPS_GPS_FAR || + abs(vel[0] - Nav.Vel[0]) > INSGPS_GPS_FAR || + abs(vel[1] - Nav.Vel[1]) > INSGPS_GPS_FAR) { + gps_far_count++; + total_far_count++; + gps_data.updated = false; + + if(gps_far_count > 30) { + INSPosVelReset(gps_data.NED,vel); + relocated++; + } + } + else { + sensors |= HORIZ_SENSORS | POS_SENSORS; + + /* + * When using gps need to make sure that barometer is brought into NED frame + * we should try and see if the altitude from the home location is good enough + * to use for the offset but for now starting with this conservative filter + */ + if(fabs(gps_data.NED[2] + (altitude_data.altitude - baro_offset)) > 10) { + baro_offset = gps_data.NED[2] + altitude_data.altitude; + } else { + /* IIR filter with 100 second or so tau to keep them crudely in the same frame */ + baro_offset = baro_offset * 0.999 + (gps_data.NED[2] + altitude_data.altitude) * 0.001; + } + gps_data.updated = false; + } + } + + if(mag_data.updated) { + sensors |= MAG_SENSORS; + mag_data.updated = false; + } + + if(altitude_data.updated) { + sensors |= BARO_SENSOR; + altitude_data.updated = false; + } + + /* + * TODO: Need to add a general sanity check for all the inputs to make sure their kosher + * although probably should occur within INS itself + */ + INSCorrection(mag_data.scaled.axis, gps_data.NED, vel, altitude_data.altitude - baro_offset, sensors); + + if(fabs(Nav.gyro_bias[0]) > 0.1 || fabs(Nav.gyro_bias[1]) > 0.1 || fabs(Nav.gyro_bias[2]) > 0.1) { + float zeros[3] = {0,0,0}; + INSSetGyroBias(zeros); + } +} + +/** + * @brief Update the EKF when in indoor mode + */ +void ins_indoor_update() +{ + static uint32_t updated_without_gps = 0; + + float gyro[3], accel[3]; + float zeros[3] = {0, 0, 0}; + static uint32_t ins_last_time = 0; + uint16_t sensors = 0; + float dT; + + dT = PIOS_DELAY_DiffuS(ins_last_time) / 1e6; + ins_last_time = PIOS_DELAY_GetRaw(); + + // This should only happen at start up or at mode switches + if(dT > 0.01) + dT = 0.01; + + // format data for INS algo + gyro[0] = gyro_data.filtered.x; + gyro[1] = gyro_data.filtered.y; + gyro[2] = gyro_data.filtered.z; + accel[0] = accel_data.filtered.x, + accel[1] = accel_data.filtered.y, + accel[2] = accel_data.filtered.z, + + INSStatePrediction(gyro, accel, dT); + attitude_data.quaternion.q1 = Nav.q[0]; + attitude_data.quaternion.q2 = Nav.q[1]; + attitude_data.quaternion.q3 = Nav.q[2]; + attitude_data.quaternion.q4 = Nav.q[3]; + send_attitude(); // get message out quickly + INSCovariancePrediction(dT); + + /* Indoors, update with zero position and velocity and high covariance */ + sensors = HORIZ_SENSORS | VERT_SENSORS; + + if(mag_data.updated && (ahrs_algorithm == INSSETTINGS_ALGORITHM_INSGPS_INDOOR)) { + sensors |= MAG_SENSORS; + mag_data.updated = false; + } + + if(altitude_data.updated) { + sensors |= BARO_SENSOR; + altitude_data.updated = false; + } + + if(gps_data.updated) { + PositionActualData positionActual; + PositionActualGet(&positionActual); + positionActual.North = gps_data.NED[0]; + positionActual.East = gps_data.NED[1]; + positionActual.Down = Nav.Pos[2]; + PositionActualSet(&positionActual); + + VelocityActualData velocityActual; + VelocityActualGet(&velocityActual); + velocityActual.North = gps_data.groundspeed * cos(gps_data.heading * DEG_TO_RAD); + velocityActual.East = gps_data.groundspeed * sin(gps_data.heading * DEG_TO_RAD); + velocityActual.Down = Nav.Vel[2]; + VelocityActualSet(&velocityActual); + + updated_without_gps = 0; + gps_data.updated = false; + } else { + PositionActualData positionActual; + PositionActualGet(&positionActual); + + VelocityActualData velocityActual; + VelocityActualGet(&velocityActual); + + positionActual.Down = Nav.Pos[2]; + velocityActual.Down = Nav.Vel[2]; + + if(updated_without_gps > 500) { + // After 2-3 seconds without a GPS update set velocity estimate to NAN + positionActual.North = NAN; + positionActual.East = NAN; + velocityActual.North = NAN; + velocityActual.East = NAN; + } else + updated_without_gps++; + + PositionActualSet(&positionActual); + VelocityActualSet(&velocityActual); + } + + /* + * TODO: Need to add a general sanity check for all the inputs to make sure their kosher + * although probably should occur within INS itself + */ + INSCorrection(mag_data.scaled.axis, zeros, zeros, altitude_data.altitude, sensors); + + if(fabs(Nav.gyro_bias[0]) > 0.1 || fabs(Nav.gyro_bias[1]) > 0.1 || fabs(Nav.gyro_bias[2]) > 0.1) { + float zeros[3] = {0,0,0}; + INSSetGyroBias(zeros); + } + +} + +/** + * @brief Initialize the EKF assuming stationary + */ +bool inited = false; +float init_q[4]; +void ins_init_algorithm() +{ + inited = true; + float Rbe[3][3], q[4], accels[3], rpy[3], mag; + float ge[3]={0,0,-9.81}, zeros[3]={0,0,0}, Pdiag[16]={25,25,25,5,5,5,1e-5,1e-5,1e-5,1e-5,1e-5,1e-5,1e-5,1e-4,1e-4,1e-4}; + bool using_mags, using_gps; + + INSGPSInit(); + + HomeLocationData home; + HomeLocationGet(&home); + + accels[0]=accel_data.filtered.x; + accels[1]=accel_data.filtered.y; + accels[2]=accel_data.filtered.z; + + using_mags = (ahrs_algorithm == INSSETTINGS_ALGORITHM_INSGPS_OUTDOOR) || (ahrs_algorithm == INSSETTINGS_ALGORITHM_INSGPS_INDOOR); + using_mags &= (home.Be[0] != 0) || (home.Be[1] != 0) || (home.Be[2] != 0); /* only use mags when valid home location */ + + using_gps = (ahrs_algorithm == INSSETTINGS_ALGORITHM_INSGPS_OUTDOOR) && (gps_data.quality >= INSGPS_GPS_MINSAT); + + /* Block till a data update */ + get_accel_gyro_data(); + + /* Ensure we get mag data in a timely manner */ + uint16_t fail_count = 50; // 50 at 200 Hz is up to 0.25 sec + while(using_mags && !mag_data.updated && fail_count--) { + get_mag_data(); + get_accel_gyro_data(); + AhrsPoll(); + PIOS_DELAY_WaituS(2000); + } + using_mags &= mag_data.updated; + + if (using_mags) { + RotFrom2Vectors(accels, ge, mag_data.scaled.axis, home.Be, Rbe); + R2Quaternion(Rbe,q); + if (using_gps) + INSSetState(gps_data.NED, zeros, q, zeros, zeros); + else + INSSetState(zeros, zeros, q, zeros, zeros); + } else { + // assume yaw = 0 + mag = VectorMagnitude(accels); + rpy[1] = asinf(-accels[0]/mag); + rpy[0] = atan2(accels[1]/mag,accels[2]/mag); + rpy[2] = 0; + RPY2Quaternion(rpy,init_q); + if (using_gps) + INSSetState(gps_data.NED, zeros, init_q, zeros, zeros); + else { + for (uint32_t i = 0; i < 5; i++) { + INSSetState(zeros, zeros, init_q, zeros, zeros); + ins_indoor_update(); + } + } + } + + INSResetP(Pdiag); + + // TODO: include initial estimate of gyro bias? +} diff --git a/flight/Libraries/packet_handler.c b/flight/Libraries/packet_handler.c new file mode 100644 index 000000000..59a9a187f --- /dev/null +++ b/flight/Libraries/packet_handler.c @@ -0,0 +1,507 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * + * @file packet_handler.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief A packet handler for handeling radio packet transmission. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "packet_handler.h" +#include "aes.h" +#include "ecc.h" + +extern char *debug_msg; + +// Private types and constants +typedef struct { + PacketHandlerConfig cfg; + PHPacket *tx_packets; + uint8_t tx_win_start; + uint8_t tx_win_end; + PHPacket *rx_packets; + uint8_t rx_win_start; + uint8_t rx_win_end; + uint16_t tx_seq_id; + PHOutputStream stream; + xSemaphoreHandle lock; + PHOutputStream output_stream; + PHDataHandler data_handler; + PHStatusHandler status_handler; + PHPPMHandler ppm_handler; +} PHPacketData, *PHPacketDataHandle; + +// Private functions +static uint8_t PHLSendAck(PHPacketDataHandle data, PHPacketHandle p); +static uint8_t PHLSendNAck(PHPacketDataHandle data, PHPacketHandle p); +static uint8_t PHLTransmitPacket(PHPacketDataHandle data, PHPacketHandle p); + +/** + * Initialize the Packet Handler library + * \param[in] txWinSize The transmission window size (number of tx packet buffers). + * \param[in] streme A callback function for transmitting the packet. + * \param[in] id The source ID of transmitter. + * \return PHInstHandle The Pachet Handler instance data. + * \return 0 Failure + */ +PHInstHandle PHInitialize(PacketHandlerConfig *cfg) +{ + // Allocate the primary structure + PHPacketDataHandle data = pvPortMalloc(sizeof(PHPacketData)); + if (!data) + return 0; + data->cfg = *cfg; + data->tx_seq_id = 0; + + // Allocate the packet windows + data->tx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.winSize); + data->rx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.winSize); + + // Initialize the windows + data->tx_win_start = data->tx_win_end = 0; + data->rx_win_start = data->rx_win_end = 0; + for (uint8_t i = 0; i < data->cfg.winSize; ++i) + { + data->tx_packets[i].header.type = PACKET_TYPE_NONE; + data->rx_packets[i].header.type = PACKET_TYPE_NONE; + } + + // Create the lock + data->lock = xSemaphoreCreateRecursiveMutex(); + + // Initialize the ECC library. + initialize_ecc(); + + // Return the structure. + return (PHInstHandle)data; +} + +/** + * Register an output stream handler + * \param[in] h The packet handler instance data pointer. + * \param[in] f The output stream handler function + */ +void PHRegisterOutputStream(PHInstHandle h, PHOutputStream f) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + + data->output_stream = f; +} + +/** + * Register a data handler + * \param[in] h The packet handler instance data pointer. + * \param[in] f The data handler function + */ +void PHRegisterDataHandler(PHInstHandle h, PHDataHandler f) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + + data->data_handler = f; +} + +/** + * Register a PPM packet handler + * \param[in] h The packet handler instance data pointer. + * \param[in] f The PPM handler function + */ +void PHRegisterStatusHandler(PHInstHandle h, PHStatusHandler f) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + + data->status_handler = f; +} + +/** + * Register a PPM packet handler + * \param[in] h The packet handler instance data pointer. + * \param[in] f The PPM handler function + */ +void PHRegisterPPMHandler(PHInstHandle h, PHPPMHandler f) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + + data->ppm_handler = f; +} + +/** + * Get a packet out of the transmit buffer. + * \param[in] h The packet handler instance data pointer. + * \param[in] dest_id The destination ID of this connection + * \return PHPacketHandle A pointer to the packet buffer. + * \return 0 No packets buffers avaiable in the transmit window. + */ +uint32_t PHConnect(PHInstHandle h, uint32_t dest_id) +{ + return 1; +} + +/** + * Get a packet out of the transmit buffer. + * \param[in] h The packet handler instance data pointer. + * \return PHPacketHandle A pointer to the packet buffer. + * \return 0 No packets buffers avaiable in the transmit window. + */ +PHPacketHandle PHGetTXPacket(PHInstHandle h) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + + // Lock + xSemaphoreTakeRecursive(data->lock, portMAX_DELAY); + PHPacketHandle p = data->tx_packets + data->tx_win_end; + + // Is the window full? + uint8_t next_end = (data->tx_win_end + 1) % data->cfg.winSize; + if(next_end == data->tx_win_start) + { + xSemaphoreGiveRecursive(data->lock); + return NULL; + } + data->tx_win_end = next_end; + + // Release lock + xSemaphoreGiveRecursive(data->lock); + + // Return a pointer to the packet at the end of the TX window. + return p; +} + +/** + * Release a packet from the transmit packet buffer window. + * \param[in] h The packet handler instance data pointer. + * \param[in] p A pointer to the packet buffer. + * \return Nothing + */ +void PHReleaseTXPacket(PHInstHandle h, PHPacketHandle p) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + + // Lock + xSemaphoreTakeRecursive(data->lock, portMAX_DELAY); + + // Change the packet type so we know this packet is unused. + p->header.type = PACKET_TYPE_NONE; + + // If this packet is at the start of the window, increment the start index. + while ((data->tx_win_start != data->tx_win_end) && + (data->tx_packets[data->tx_win_start].header.type == PACKET_TYPE_NONE)) + data->tx_win_start = (data->tx_win_start + 1) % data->cfg.winSize; + + // Release lock + xSemaphoreGiveRecursive(data->lock); +} + +/** + * Get a packet out of the receive buffer. + * \param[in] h The packet handler instance data pointer. + * \return PHPacketHandle A pointer to the packet buffer. + * \return 0 No packets buffers avaiable in the transmit window. + */ +PHPacketHandle PHGetRXPacket(PHInstHandle h) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + + // Lock + xSemaphoreTakeRecursive(data->lock, portMAX_DELAY); + PHPacketHandle p = data->rx_packets + data->rx_win_end; + + // Is the window full? + uint8_t next_end = (data->rx_win_end + 1) % data->cfg.winSize; + if(next_end == data->rx_win_start) + { + // Release lock + xSemaphoreGiveRecursive(data->lock); + return NULL; + } + data->rx_win_end = next_end; + + // Release lock + xSemaphoreGiveRecursive(data->lock); + + // Return a pointer to the packet at the end of the TX window. + return p; +} + +/** + * Release a packet from the receive packet buffer window. + * \param[in] h The packet handler instance data pointer. + * \param[in] p A pointer to the packet buffer. + * \return Nothing + */ +void PHReleaseRXPacket(PHInstHandle h, PHPacketHandle p) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + + // Lock + xSemaphoreTakeRecursive(data->lock, portMAX_DELAY); + + // Change the packet type so we know this packet is unused. + p->header.type = PACKET_TYPE_NONE; + + // If this packet is at the start of the window, increment the start index. + while ((data->rx_win_start != data->rx_win_end) && + (data->rx_packets[data->rx_win_start].header.type == PACKET_TYPE_NONE)) + data->rx_win_start = (data->rx_win_start + 1) % data->cfg.winSize; + + // Release lock + xSemaphoreGiveRecursive(data->lock); +} + +/** + * Transmit a packet from the transmit packet buffer window. + * \param[in] h The packet handler instance data pointer. + * \param[in] p A pointer to the packet buffer. + * \return 1 Success + * \return 0 Failure + */ +uint8_t PHTransmitPacket(PHInstHandle h, PHPacketHandle p) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + + // Try to transmit the packet. + if (!PHLTransmitPacket(data, p)) + return 0; + + // If this packet doesn't require an ACK, remove it from the TX window. + switch (p->header.type) { + case PACKET_TYPE_READY: + case PACKET_TYPE_NOTREADY: + case PACKET_TYPE_DATA: + case PACKET_TYPE_PPM: + PHReleaseTXPacket(h, p); + break; + } + + return 1; +} + +/** + * Verify that a buffer contains a valid packet. + * \param[in] h The packet handler instance data pointer. + * \param[in] p A pointer to the packet buffer. + * \param[in] received_len The length of data received. + * \return < 0 Failure + * \return > 0 Number of bytes consumed. + */ +int32_t PHVerifyPacket(PHInstHandle h, PHPacketHandle p, uint16_t received_len) +{ + + // Verify the packet length. + // Note: The last two bytes should be the RSSI and AFC. + uint16_t len = PHPacketSizeECC(p); + if (received_len < (len + 2)) + { + DEBUG_PRINTF(1, "Packet length error %d %d\n\r", received_len, len + 2); + return -1; + } + + // Attempt to correct any errors in the packet. + decode_data((unsigned char*)p, len); + + // Check that there were no unfixed errors. + bool rx_error = check_syndrome() != 0; + if(rx_error) + { + DEBUG_PRINTF(1, "Error in packet\n\r"); + return -2; + } + + return len + 2; +} + +/** + * Process a packet that has been received. + * \param[in] h The packet handler instance data pointer. + * \param[in] p A pointer to the packet buffer. + * \param[in] received_len The length of data received. + * \return 0 Failure + * \return 1 Success + */ +uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + uint16_t len = PHPacketSizeECC(p); + + // Extract the RSSI and AFC. + int8_t rssi = *(((int8_t*)p) + len); + int8_t afc = *(((int8_t*)p) + len + 1); + + switch (p->header.type) { + + case PACKET_TYPE_STATUS: + + if (!rx_error) + + // Pass on the channels to the status handler. + if(data->status_handler) + data->status_handler((PHStatusPacketHandle)p, rssi, afc); + + break; + + case PACKET_TYPE_ACKED_DATA: + + // Send the ACK / NACK + if (rx_error) + { + DEBUG_PRINTF(1, "Sending NACK\n\r"); + PHLSendNAck(data, p); + } + else + { + + PHLSendAck(data, p); + + // Pass on the data. + if(data->data_handler) + data->data_handler(p->data, p->header.data_size, rssi, afc); + } + + break; + + case PACKET_TYPE_ACK: + { + // Find the packet ID in the TX buffer, and free it. + unsigned int i = 0; + for (unsigned int i = 0; i < data->cfg.winSize; ++i) + if (data->tx_packets[i].header.tx_seq == p->header.rx_seq) + PHReleaseTXPacket(h, data->tx_packets + i); +#ifdef DEBUG_LEVEL + if (i == data->cfg.winSize) + DEBUG_PRINTF(1, "Error finding acked packet to release\n\r"); +#endif + } + break; + + case PACKET_TYPE_NACK: + { + // Resend the packet. + unsigned int i = 0; + for ( ; i < data->cfg.winSize; ++i) + if (data->tx_packets[i].header.tx_seq == p->header.rx_seq) + PHLTransmitPacket(data, data->tx_packets + i); +#ifdef DEBUG_LEVEL + if (i == data->cfg.winSize) + DEBUG_PRINTF(1, "Error finding acked packet to NACK\n\r"); + DEBUG_PRINTF(1, "Resending after NACK\n\r"); +#endif + } + break; + + case PACKET_TYPE_PPM: + + if (!rx_error) + + // Pass on the channels to the PPM handler. + if(data->ppm_handler) + data->ppm_handler(((PHPpmPacketHandle)p)->channels); + + break; + + case PACKET_TYPE_DATA: + + if (!rx_error) + + // Pass on the data to the data handler. + if(data->data_handler) + data->data_handler(p->data, p->header.data_size, rssi, afc); + + break; + + default: + break; + } + + // Release the packet. + PHReleaseRXPacket(h, p); + + return 1; +} + +/** + * Transmit a packet from the transmit packet buffer window. + * \param[in] data The packet handler instance data pointer. + * \param[in] p A pointer to the packet buffer. + * \return 1 Success + * \return 0 Failure + */ +static uint8_t PHLTransmitPacket(PHPacketDataHandle data, PHPacketHandle p) +{ + + if(!data->output_stream) + return 0; + + // Set the sequence ID to the current ID. + p->header.tx_seq = data->tx_seq_id++; + + // Add the error correcting code. + encode_data((unsigned char*)p, PHPacketSize(p), (unsigned char*)p); + + // Transmit the packet using the output stream. + if(data->output_stream(p) == -1) + return 0; + + return 1; +} + +/** + * Send an ACK packet. + * \param[in] data The packet handler instance data pointer. + * \param[in] p A pointer to the packet buffer of the packet to be ACKed. + * \return 1 Success + * \return 0 Failure + */ +static uint8_t PHLSendAck(PHPacketDataHandle data, PHPacketHandle p) +{ + + // Create the ACK message + PHPacketHeader ack; + ack.destination_id = p->header.source_id; + ack.type = PACKET_TYPE_ACK; + ack.rx_seq = p->header.tx_seq; + ack.data_size = 0; + + // Send the packet. + return PHLTransmitPacket(data, (PHPacketHandle)&ack); +} + +/** + * Send an NAck packet. + * \param[in] data The packet handler instance data pointer. + * \param[in] p A pointer to the packet buffer of the packet to be ACKed. + * \return 1 Success + * \return 0 Failure + */ +static uint8_t PHLSendNAck(PHPacketDataHandle data, PHPacketHandle p) +{ + + // Create the NAck message + PHPacketHeader ack; + ack.destination_id = p->header.source_id; + ack.type = PACKET_TYPE_NACK; + ack.rx_seq = p->header.tx_seq; + ack.data_size = 0; + + // Set the packet. + return PHLTransmitPacket(data, (PHPacketHandle)&ack); +} diff --git a/flight/Libraries/rscode/LICENSE b/flight/Libraries/rscode/LICENSE new file mode 100644 index 000000000..daab5a625 --- /dev/null +++ b/flight/Libraries/rscode/LICENSE @@ -0,0 +1,10 @@ + * (C) Henry Minsky (hqm@alum.mit.edu) 1991-2009 + * + * This software library is licensed under terms of the GNU GENERAL + * PUBLIC LICENSE. [See file gpl.txt] + * + * Commercial licensing is available under a separate license, please + * contact author for details. + * + * Latest source code and other info at http://rscode.sourceforge.net + diff --git a/flight/Libraries/rscode/Makefile b/flight/Libraries/rscode/Makefile new file mode 100644 index 000000000..daa12624f --- /dev/null +++ b/flight/Libraries/rscode/Makefile @@ -0,0 +1,50 @@ +# Makefile for Cross Interleaved Reed Solomon encoder/decoder +# +# (c) Henry Minsky, Universal Access 1991-1996 +# + +RANLIB = ranlib +AR = ar + + +VERSION = 1.0 +DIRNAME= rscode-$(VERSION) + + +CC = gcc +# OPTIMIZE_FLAGS = -O69 +DEBUG_FLAGS = -g +CFLAGS = -Wall -Wstrict-prototypes $(OPTIMIZE_FLAGS) $(DEBUG_FLAGS) -I.. +LDFLAGS = $(OPTIMIZE_FLAGS) $(DEBUG_FLAGS) + +LIB_CSRC = rs.c galois.c berlekamp.c crcgen.c +LIB_HSRC = ecc.h +LIB_OBJS = rs.o galois.o berlekamp.o crcgen.o + +TARGET_LIB = libecc.a +TEST_PROGS = example + +TARGETS = $(TARGET_LIB) $(TEST_PROGS) + +all: $(TARGETS) + +$(TARGET_LIB): $(LIB_OBJS) + $(RM) $@ + $(AR) cq $@ $(LIB_OBJS) + if [ "$(RANLIB)" ]; then $(RANLIB) $@; fi + +example: example.o galois.o berlekamp.o crcgen.o rs.o + gcc -o example example.o -L. -lecc + +clean: + rm -f *.o example libecc.a + rm -f *~ + +dist: + (cd ..; tar -cvf rscode-$(VERSION).tar $(DIRNAME)) + +depend: + makedepend $(SRCS) + +# DO NOT DELETE THIS LINE -- make depend depends on it. + diff --git a/flight/Libraries/rscode/README b/flight/Libraries/rscode/README new file mode 100644 index 000000000..92d68b3d8 --- /dev/null +++ b/flight/Libraries/rscode/README @@ -0,0 +1,27 @@ +RSCODE version 1.3 + +See the files + +config.doc documentation of some compile time parameters +rs.doc overview of the Reed-Solomon coding program +rs.man a man page, slightly outdated at this point +example.c a simple example of encoding,decoding, and error correction + +Makefile should work on a Sun system, may require GNU make. + + +Henry Minsky +hqm@alum.mit.edu + + + * (c) Henry Minsky (hqm@alum.mit.edu) 1991-2009 + * + * This software library is licensed under terms of the GNU GENERAL + * PUBLIC LICENSE. (See gpl.txt) + * + * Commercial licensing is available under a separate license, please + * contact author for details. + * + * Source code is available at http://rscode.sourceforge.net + + diff --git a/flight/Libraries/rscode/berlekamp.c b/flight/Libraries/rscode/berlekamp.c new file mode 100644 index 000000000..ef91991e3 --- /dev/null +++ b/flight/Libraries/rscode/berlekamp.c @@ -0,0 +1,324 @@ +/*********************************************************************** + * Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009 + * + * This software library is licensed under terms of the GNU GENERAL + * PUBLIC LICENSE + * + * + * RSCODE is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * RSCODE 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 Rscode. If not, see . + * + * Commercial licensing is available under a separate license, please + * contact author for details. + * + * Source code is available at http://rscode.sourceforge.net + * Berlekamp-Peterson and Berlekamp-Massey Algorithms for error-location + * + * From Cain, Clark, "Error-Correction Coding For Digital Communications", pp. 205. + * + * This finds the coefficients of the error locator polynomial. + * + * The roots are then found by looking for the values of a^n + * where evaluating the polynomial yields zero. + * + * Error correction is done using the error-evaluator equation on pp 207. + * + */ + +#include +#include "ecc.h" + +/* The Error Locator Polynomial, also known as Lambda or Sigma. Lambda[0] == 1 */ +static int Lambda[MAXDEG]; + +/* The Error Evaluator Polynomial */ +static int Omega[MAXDEG]; + +/* local ANSI declarations */ +static int compute_discrepancy(int lambda[], int S[], int L, int n); +static void init_gamma(int gamma[]); +static void compute_modified_omega (void); +static void mul_z_poly (int src[]); + +/* error locations found using Chien's search*/ +static int ErrorLocs[256]; +static int NErrors; + +/* erasure flags */ +static int ErasureLocs[256]; +static int NErasures; + +/* From Cain, Clark, "Error-Correction Coding For Digital Communications", pp. 216. */ +void +Modified_Berlekamp_Massey (void) +{ + int n, L, L2, k, d, i; + int psi[MAXDEG], psi2[MAXDEG], D[MAXDEG]; + int gamma[MAXDEG]; + + /* initialize Gamma, the erasure locator polynomial */ + init_gamma(gamma); + + /* initialize to z */ + copy_poly(D, gamma); + mul_z_poly(D); + + copy_poly(psi, gamma); + k = -1; L = NErasures; + + for (n = NErasures; n < RS_ECC_NPARITY; n++) { + + d = compute_discrepancy(psi, synBytes, L, n); + + if (d != 0) { + + /* psi2 = psi - d*D */ + for (i = 0; i < MAXDEG; i++) psi2[i] = psi[i] ^ gmult(d, D[i]); + + + if (L < (n-k)) { + L2 = n-k; + k = n-L; + /* D = scale_poly(ginv(d), psi); */ + for (i = 0; i < MAXDEG; i++) D[i] = gmult(psi[i], ginv(d)); + L = L2; + } + + /* psi = psi2 */ + for (i = 0; i < MAXDEG; i++) psi[i] = psi2[i]; + } + + mul_z_poly(D); + } + + for(i = 0; i < MAXDEG; i++) Lambda[i] = psi[i]; + compute_modified_omega(); + + +} + +/* given Psi (called Lambda in Modified_Berlekamp_Massey) and synBytes, + compute the combined erasure/error evaluator polynomial as + Psi*S mod z^4 + */ +void +compute_modified_omega () +{ + int i; + int product[MAXDEG*2]; + + mult_polys(product, Lambda, synBytes); + zero_poly(Omega); + for(i = 0; i < RS_ECC_NPARITY; i++) Omega[i] = product[i]; + +} + +/* polynomial multiplication */ +void +mult_polys (int dst[], int p1[], int p2[]) +{ + int i, j; + int tmp1[MAXDEG*2]; + + for (i=0; i < (MAXDEG*2); i++) dst[i] = 0; + + for (i = 0; i < MAXDEG; i++) { + for(j=MAXDEG; j<(MAXDEG*2); j++) tmp1[j]=0; + + /* scale tmp1 by p1[i] */ + for(j=0; j= i; j--) tmp1[j] = tmp1[j-i]; + for (j = 0; j < i; j++) tmp1[j] = 0; + + /* add into partial product */ + for(j=0; j < (MAXDEG*2); j++) dst[j] ^= tmp1[j]; + } +} + + + +/* gamma = product (1-z*a^Ij) for erasure locs Ij */ +void +init_gamma (int gamma[]) +{ + int e, tmp[MAXDEG]; + + zero_poly(gamma); + zero_poly(tmp); + gamma[0] = 1; + + for (e = 0; e < NErasures; e++) { + copy_poly(tmp, gamma); + scale_poly(gexp[ErasureLocs[e]], tmp); + mul_z_poly(tmp); + add_polys(gamma, tmp); + } +} + + + +void +compute_next_omega (int d, int A[], int dst[], int src[]) +{ + int i; + for ( i = 0; i < MAXDEG; i++) { + dst[i] = src[i] ^ gmult(d, A[i]); + } +} + + + +int +compute_discrepancy (int lambda[], int S[], int L, int n) +{ + int i, sum=0; + + for (i = 0; i <= L; i++) + sum ^= gmult(lambda[i], S[n-i]); + return (sum); +} + +/********** polynomial arithmetic *******************/ + +void add_polys (int dst[], int src[]) +{ + int i; + for (i = 0; i < MAXDEG; i++) dst[i] ^= src[i]; +} + +void copy_poly (int dst[], int src[]) +{ + int i; + for (i = 0; i < MAXDEG; i++) dst[i] = src[i]; +} + +void scale_poly (int k, int poly[]) +{ + int i; + for (i = 0; i < MAXDEG; i++) poly[i] = gmult(k, poly[i]); +} + + +void zero_poly (int poly[]) +{ + int i; + for (i = 0; i < MAXDEG; i++) poly[i] = 0; +} + + +/* multiply by z, i.e., shift right by 1 */ +static void mul_z_poly (int src[]) +{ + int i; + for (i = MAXDEG-1; i > 0; i--) src[i] = src[i-1]; + src[0] = 0; +} + + +/* Finds all the roots of an error-locator polynomial with coefficients + * Lambda[j] by evaluating Lambda at successive values of alpha. + * + * This can be tested with the decoder's equations case. + */ + + +void +Find_Roots (void) +{ + int sum, r, k; + NErrors = 0; + + for (r = 1; r < 256; r++) { + sum = 0; + /* evaluate lambda at r */ + for (k = 0; k < RS_ECC_NPARITY+1; k++) { + sum ^= gmult(gexp[(k*r)%255], Lambda[k]); + } + if (sum == 0) + { + ErrorLocs[NErrors] = (255-r); NErrors++; + //if (DEBUG) fprintf(stderr, "Root found at r = %d, (255-r) = %d\n", r, (255-r)); + } + } +} + +/* Combined Erasure And Error Magnitude Computation + * + * Pass in the codeword, its size in bytes, as well as + * an array of any known erasure locations, along the number + * of these erasures. + * + * Evaluate Omega(actually Psi)/Lambda' at the roots + * alpha^(-i) for error locs i. + * + * Returns 1 if everything ok, or 0 if an out-of-bounds error is found + * + */ + +int +correct_errors_erasures (unsigned char codeword[], + int csize, + int nerasures, + int erasures[]) +{ + int r, i, j, err; + + /* If you want to take advantage of erasure correction, be sure to + set NErasures and ErasureLocs[] with the locations of erasures. + */ + NErasures = nerasures; + for (i = 0; i < NErasures; i++) ErasureLocs[i] = erasures[i]; + + Modified_Berlekamp_Massey(); + Find_Roots(); + + + if ((NErrors <= RS_ECC_NPARITY) && NErrors > 0) { + + /* first check for illegal error locs */ + for (r = 0; r < NErrors; r++) { + if (ErrorLocs[r] >= csize) { + //if (DEBUG) fprintf(stderr, "Error loc i=%d outside of codeword length %d\n", i, csize); + return(0); + } + } + + for (r = 0; r < NErrors; r++) { + int num, denom; + i = ErrorLocs[r]; + /* evaluate Omega at alpha^(-i) */ + + num = 0; + for (j = 0; j < MAXDEG; j++) + num ^= gmult(Omega[j], gexp[((255-i)*j)%255]); + + /* evaluate Lambda' (derivative) at alpha^(-i) ; all odd powers disappear */ + denom = 0; + for (j = 1; j < MAXDEG; j += 2) { + denom ^= gmult(Lambda[j], gexp[((255-i)*(j-1)) % 255]); + } + + err = gmult(num, ginv(denom)); + //if (DEBUG) fprintf(stderr, "Error magnitude %#x at loc %d\n", err, csize-i); + + codeword[csize-i-1] ^= err; + } + return(1); + } + else { + //if (DEBUG && NErrors) fprintf(stderr, "Uncorrectable codeword\n"); + return(0); + } +} + diff --git a/flight/Libraries/rscode/config.doc b/flight/Libraries/rscode/config.doc new file mode 100644 index 000000000..77771893d --- /dev/null +++ b/flight/Libraries/rscode/config.doc @@ -0,0 +1,18 @@ +The basic coding parameters are defined using +macros, and an executable can be made by compiling using macro +definitions defining the values of the following names in the file +"ecc.h": + +The important compile time parameter is the number of parity bytes, +specified by the #define NPAR. + +The library is shipped with + +#define NPAR 4 + +The error-correction routines are polynomial in the number of +parity bytes, so try to keep NPAR small for high performance. + +Remember, the sum of the message length (in bytes) plus parity bytes +must be less than or equal to 255. + diff --git a/flight/Libraries/rscode/crcgen.c b/flight/Libraries/rscode/crcgen.c new file mode 100644 index 000000000..487dba5d0 --- /dev/null +++ b/flight/Libraries/rscode/crcgen.c @@ -0,0 +1,66 @@ +/***************************** + * Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009 + * + * This software library is licensed under terms of the GNU GENERAL + * PUBLIC LICENSE + * + * RSCODE is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * RSCODE 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 Rscode. If not, see . + + * Commercial licensing is available under a separate license, please + * contact author for details. + * + * Source code is available at http://rscode.sourceforge.net + * + * CRC-CCITT generator simulator for byte wide data. + * + * + * CRC-CCITT = x^16 + x^12 + x^5 + 1 + * + * + ******************************/ + + +#include "ecc.h" + +BIT16 crchware(BIT16 data, BIT16 genpoly, BIT16 accum); + +/* Computes the CRC-CCITT checksum on array of byte data, length len +*/ +BIT16 crc_ccitt(unsigned char *msg, int len) +{ + int i; + BIT16 acc = 0; + + for (i = 0; i < len; i++) { + acc = crchware((BIT16) msg[i], (BIT16) 0x1021, acc); + } + + return(acc); +} + +/* models crc hardware (minor variation on polynomial division algorithm) */ +BIT16 crchware(BIT16 data, BIT16 genpoly, BIT16 accum) +{ + static BIT16 i; + data <<= 8; + for (i = 8; i > 0; i--) { + if ((data ^ accum) & 0x8000) + accum = ((accum << 1) ^ genpoly) & 0xFFFF; + else + accum = (accum<<1) & 0xFFFF; + data = (data<<1) & 0xFFFF; + } + return (accum); +} + diff --git a/flight/Libraries/rscode/ecc.h b/flight/Libraries/rscode/ecc.h new file mode 100644 index 000000000..bf56a0b9a --- /dev/null +++ b/flight/Libraries/rscode/ecc.h @@ -0,0 +1,98 @@ +/* Reed Solomon Coding for glyphs + * Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009 + * + * This software library is licensed under terms of the GNU GENERAL + * PUBLIC LICENSE + * + * RSCODE is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * RSCODE 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 Rscode. If not, see . + * + * Source code is available at http://rscode.sourceforge.net + * + * Commercial licensing is available under a separate license, please + * contact author for details. + * + */ + +/**************************************************************** + + Below is NPAR, the only compile-time parameter you should have to + modify. + + It is the number of parity bytes which will be appended to + your data to create a codeword. + + Note that the maximum codeword size is 255, so the + sum of your message length plus parity should be less than + or equal to this maximum limit. + + In practice, you will get slooow error correction and decoding + if you use more than a reasonably small number of parity bytes. + (say, 10 or 20) + + ****************************************************************/ + +/****************************************************************/ + + +#include + +#define TRUE 1 +#define FALSE 0 + +typedef unsigned long BIT32; +typedef unsigned short BIT16; + +/* **************************************************************** */ + +/* Maximum degree of various polynomials. */ +#define MAXDEG (RS_ECC_NPARITY*2) + +/*************************************/ +/* Encoder parity bytes */ +extern int pBytes[MAXDEG]; + +/* Decoder syndrome bytes */ +extern int synBytes[MAXDEG]; + +/* print debugging info */ +extern int DEBUG; + +/* Reed Solomon encode/decode routines */ +void initialize_ecc (void); +int check_syndrome (void); +void decode_data (unsigned char data[], int nbytes); +void encode_data (unsigned char msg[], int nbytes, unsigned char dst[]); + +/* CRC-CCITT checksum generator */ +BIT16 crc_ccitt(unsigned char *msg, int len); + +/* galois arithmetic tables */ +extern const int gexp[]; +extern const int glog[]; + +void init_galois_tables (void); +int ginv(int elt); +int gmult(int a, int b); + + +/* Error location routines */ +int correct_errors_erasures (unsigned char codeword[], int csize,int nerasures, int erasures[]); + +/* polynomial arithmetic */ +void add_polys(int dst[], int src[]) ; +void scale_poly(int k, int poly[]); +void mult_polys(int dst[], int p1[], int p2[]); + +void copy_poly(int dst[], int src[]); +void zero_poly(int poly[]); diff --git a/flight/Libraries/rscode/example.c b/flight/Libraries/rscode/example.c new file mode 100644 index 000000000..b4df5b87f --- /dev/null +++ b/flight/Libraries/rscode/example.c @@ -0,0 +1,128 @@ +/* Example use of Reed-Solomon library + * + * Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009 + * + * This software library is licensed under terms of the GNU GENERAL + * PUBLIC LICENSE + * + * RSCODE is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * RSCODE 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 Rscode. If not, see . + + * Commercial licensing is available under a separate license, please + * contact author for details. + * + * This same code demonstrates the use of the encodier and + * decoder/error-correction routines. + * + * We are assuming we have at least four bytes of parity (NPAR >= 4). + * + * This gives us the ability to correct up to two errors, or + * four erasures. + * + * In general, with E errors, and K erasures, you will need + * 2E + K bytes of parity to be able to correct the codeword + * back to recover the original message data. + * + * You could say that each error 'consumes' two bytes of the parity, + * whereas each erasure 'consumes' one byte. + * + * Thus, as demonstrated below, we can inject one error (location unknown) + * and two erasures (with their locations specified) and the + * error-correction routine will be able to correct the codeword + * back to the original message. + * */ + +#include +#include +#include "ecc.h" + +unsigned char msg[] = "Nervously I loaded the twin ducks aboard the revolving pl\ +atform."; +unsigned char codeword[256]; + +/* Some debugging routines to introduce errors or erasures + into a codeword. + */ + +/* Introduce a byte error at LOC */ +void +byte_err (int err, int loc, unsigned char *dst) +{ + printf("Adding Error at loc %d, data %#x\n", loc, dst[loc-1]); + dst[loc-1] ^= err; +} + +/* Pass in location of error (first byte position is + labeled starting at 1, not 0), and the codeword. +*/ +void +byte_erasure (int loc, unsigned char dst[], int cwsize, int erasures[]) +{ + printf("Erasure at loc %d, data %#x\n", loc, dst[loc-1]); + dst[loc-1] = 0; +} + + +int +main (int argc, char *argv[]) +{ + + int erasures[16]; + int nerasures = 0; + + /* Initialization the ECC library */ + + initialize_ecc (); + + /* ************** */ + + /* Encode data into codeword, adding NPAR parity bytes */ + encode_data(msg, sizeof(msg), codeword); + + printf("Encoded data is: \"%s\"\n", codeword); + +#define ML (sizeof (msg) + NPAR) + + + /* Add one error and two erasures */ + byte_err(0x35, 3, codeword); + + byte_err(0x23, 17, codeword); + byte_err(0x34, 19, codeword); + + + printf("with some errors: \"%s\"\n", codeword); + + /* We need to indicate the position of the erasures. Eraseure + positions are indexed (1 based) from the end of the message... */ + + erasures[nerasures++] = ML-17; + erasures[nerasures++] = ML-19; + + + /* Now decode -- encoded codeword size must be passed */ + decode_data(codeword, ML); + + /* check if syndrome is all zeros */ + if (check_syndrome () != 0) { + correct_errors_erasures (codeword, + ML, + nerasures, + erasures); + + printf("Corrected codeword: \"%s\"\n", codeword); + } + + exit(0); +} + diff --git a/flight/Libraries/rscode/galois.c b/flight/Libraries/rscode/galois.c new file mode 100644 index 000000000..6326715d0 --- /dev/null +++ b/flight/Libraries/rscode/galois.c @@ -0,0 +1,164 @@ +/***************************** + * Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009 + * + * This software library is licensed under terms of the GNU GENERAL + * PUBLIC LICENSE + * + * RSCODE is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * RSCODE 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 Rscode. If not, see . + + * Commercial licensing is available under a separate license, please + * contact author for details. + * + * Source code is available at http://rscode.sourceforge.net + * + * + * Multiplication and Arithmetic on Galois Field GF(256) + * + * From Mee, Daniel, "Magnetic Recording, Volume III", Ch. 5 by Patel. + * + * + ******************************/ + + +#include +#include +#include "ecc.h" + +/* This is one of 14 irreducible polynomials + * of degree 8 and cycle length 255. (Ch 5, pp. 275, Magnetic Recording) + * The high order 1 bit is implicit */ +/* x^8 + x^4 + x^3 + x^2 + 1 */ +#define PPOLY 0x1D + + +const int gexp[512] = { + 1, 2, 4, 8, 16, 32, 64, 128, 29, 58, 116, 232, 205, 135, 19, 38, + 76, 152, 45, 90, 180, 117, 234, 201, 143, 3, 6, 12, 24, 48, 96, 192, + 157, 39, 78, 156, 37, 74, 148, 53, 106, 212, 181, 119, 238, 193, 159, 35, + 70, 140, 5, 10, 20, 40, 80, 160, 93, 186, 105, 210, 185, 111, 222, 161, + 95, 190, 97, 194, 153, 47, 94, 188, 101, 202, 137, 15, 30, 60, 120, 240, + 253, 231, 211, 187, 107, 214, 177, 127, 254, 225, 223, 163, 91, 182, 113, 226, + 217, 175, 67, 134, 17, 34, 68, 136, 13, 26, 52, 104, 208, 189, 103, 206, + 129, 31, 62, 124, 248, 237, 199, 147, 59, 118, 236, 197, 151, 51, 102, 204, + 133, 23, 46, 92, 184, 109, 218, 169, 79, 158, 33, 66, 132, 21, 42, 84, + 168, 77, 154, 41, 82, 164, 85, 170, 73, 146, 57, 114, 228, 213, 183, 115, + 230, 209, 191, 99, 198, 145, 63, 126, 252, 229, 215, 179, 123, 246, 241, 255, + 227, 219, 171, 75, 150, 49, 98, 196, 149, 55, 110, 220, 165, 87, 174, 65, + 130, 25, 50, 100, 200, 141, 7, 14, 28, 56, 112, 224, 221, 167, 83, 166, + 81, 162, 89, 178, 121, 242, 249, 239, 195, 155, 43, 86, 172, 69, 138, 9, + 18, 36, 72, 144, 61, 122, 244, 245, 247, 243, 251, 235, 203, 139, 11, 22, + 44, 88, 176, 125, 250, 233, 207, 131, 27, 54, 108, 216, 173, 71, 142, 1, + 2, 4, 8, 16, 32, 64, 128, 29, 58, 116, 232, 205, 135, 19, 38, 76, + 152, 45, 90, 180, 117, 234, 201, 143, 3, 6, 12, 24, 48, 96, 192, 157, + 39, 78, 156, 37, 74, 148, 53, 106, 212, 181, 119, 238, 193, 159, 35, 70, + 140, 5, 10, 20, 40, 80, 160, 93, 186, 105, 210, 185, 111, 222, 161, 95, + 190, 97, 194, 153, 47, 94, 188, 101, 202, 137, 15, 30, 60, 120, 240, 253, + 231, 211, 187, 107, 214, 177, 127, 254, 225, 223, 163, 91, 182, 113, 226, 217, + 175, 67, 134, 17, 34, 68, 136, 13, 26, 52, 104, 208, 189, 103, 206, 129, + 31, 62, 124, 248, 237, 199, 147, 59, 118, 236, 197, 151, 51, 102, 204, 133, + 23, 46, 92, 184, 109, 218, 169, 79, 158, 33, 66, 132, 21, 42, 84, 168, + 77, 154, 41, 82, 164, 85, 170, 73, 146, 57, 114, 228, 213, 183, 115, 230, + 209, 191, 99, 198, 145, 63, 126, 252, 229, 215, 179, 123, 246, 241, 255, 227, + 219, 171, 75, 150, 49, 98, 196, 149, 55, 110, 220, 165, 87, 174, 65, 130, + 25, 50, 100, 200, 141, 7, 14, 28, 56, 112, 224, 221, 167, 83, 166, 81, + 162, 89, 178, 121, 242, 249, 239, 195, 155, 43, 86, 172, 69, 138, 9, 18, + 36, 72, 144, 61, 122, 244, 245, 247, 243, 251, 235, 203, 139, 11, 22, 44, + 88, 176, 125, 250, 233, 207, 131, 27, 54, 108, 216, 173, 71, 142, 1, 0, +}; +const int glog[256] = { + 0, 0, 1, 25, 2, 50, 26, 198, 3, 223, 51, 238, 27, 104, 199, 75, + 4, 100, 224, 14, 52, 141, 239, 129, 28, 193, 105, 248, 200, 8, 76, 113, + 5, 138, 101, 47, 225, 36, 15, 33, 53, 147, 142, 218, 240, 18, 130, 69, + 29, 181, 194, 125, 106, 39, 249, 185, 201, 154, 9, 120, 77, 228, 114, 166, + 6, 191, 139, 98, 102, 221, 48, 253, 226, 152, 37, 179, 16, 145, 34, 136, + 54, 208, 148, 206, 143, 150, 219, 189, 241, 210, 19, 92, 131, 56, 70, 64, + 30, 66, 182, 163, 195, 72, 126, 110, 107, 58, 40, 84, 250, 133, 186, 61, + 202, 94, 155, 159, 10, 21, 121, 43, 78, 212, 229, 172, 115, 243, 167, 87, + 7, 112, 192, 247, 140, 128, 99, 13, 103, 74, 222, 237, 49, 197, 254, 24, + 227, 165, 153, 119, 38, 184, 180, 124, 17, 68, 146, 217, 35, 32, 137, 46, + 55, 63, 209, 91, 149, 188, 207, 205, 144, 135, 151, 178, 220, 252, 190, 97, + 242, 86, 211, 171, 20, 42, 93, 158, 132, 60, 57, 83, 71, 109, 65, 162, + 31, 45, 67, 216, 183, 123, 164, 118, 196, 23, 73, 236, 127, 12, 111, 246, + 108, 161, 59, 82, 41, 157, 85, 170, 251, 96, 134, 177, 187, 204, 62, 90, + 203, 89, 95, 176, 156, 169, 160, 81, 11, 245, 22, 235, 122, 117, 44, 215, + 79, 174, 213, 233, 230, 231, 173, 232, 116, 214, 244, 234, 168, 80, 88, 175, +}; + + +//static void init_exp_table (void); + + +void +init_galois_tables (void) +{ + /* initialize the table of powers of alpha */ + //init_exp_table(); +} + + +#ifdef NEVER +static void +init_exp_table (void) +{ + int i, z; + int pinit,p1,p2,p3,p4,p5,p6,p7,p8; + + pinit = p2 = p3 = p4 = p5 = p6 = p7 = p8 = 0; + p1 = 1; + + gexp[0] = 1; + gexp[255] = gexp[0]; + glog[0] = 0; /* shouldn't log[0] be an error? */ + + for (i = 1; i < 256; i++) { + pinit = p8; + p8 = p7; + p7 = p6; + p6 = p5; + p5 = p4 ^ pinit; + p4 = p3 ^ pinit; + p3 = p2 ^ pinit; + p2 = p1; + p1 = pinit; + gexp[i] = p1 + p2*2 + p3*4 + p4*8 + p5*16 + p6*32 + p7*64 + p8*128; + gexp[i+255] = gexp[i]; + } + + for (i = 1; i < 256; i++) { + for (z = 0; z < 256; z++) { + if (gexp[z] == i) { + glog[i] = z; + break; + } + } + } +} +#endif + +/* multiplication using logarithms */ +int gmult(int a, int b) +{ + int i,j; + if (a==0 || b == 0) return (0); + i = glog[a]; + j = glog[b]; + return (gexp[i+j]); +} + + +int ginv (int elt) +{ + return (gexp[255-glog[elt]]); +} + diff --git a/flight/Libraries/rscode/gpl.txt b/flight/Libraries/rscode/gpl.txt new file mode 100644 index 000000000..94a9ed024 --- /dev/null +++ b/flight/Libraries/rscode/gpl.txt @@ -0,0 +1,674 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + Copyright (C) + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. diff --git a/flight/Libraries/rscode/rs.c b/flight/Libraries/rscode/rs.c new file mode 100644 index 000000000..5373b3ea0 --- /dev/null +++ b/flight/Libraries/rscode/rs.c @@ -0,0 +1,207 @@ +/* + * Reed Solomon Encoder/Decoder + * + * Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009 + * + * This software library is licensed under terms of the GNU GENERAL + * PUBLIC LICENSE + * + * RSCODE is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * RSCODE 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 Rscode. If not, see . + + * Commercial licensing is available under a separate license, please + * contact author for details. + * + * Source code is available at http://rscode.sourceforge.net + */ + +#include +#include +#include "ecc.h" + +/* Encoder parity bytes */ +int pBytes[MAXDEG]; + +/* Decoder syndrome bytes */ +int synBytes[MAXDEG]; + +/* generator polynomial */ +int genPoly[MAXDEG*2]; + +int DEBUG = FALSE; + +static void +compute_genpoly (int nbytes, int genpoly[]); + +/* Initialize lookup tables, polynomials, etc. */ +void +initialize_ecc () +{ + /* Initialize the galois field arithmetic tables */ + init_galois_tables(); + + /* Compute the encoder generator polynomial */ + compute_genpoly(RS_ECC_NPARITY, genPoly); +} + +void +zero_fill_from (unsigned char buf[], int from, int to) +{ + int i; + for (i = from; i < to; i++) buf[i] = 0; +} + +/* debugging routines */ +void +print_parity (void) +{ +#ifdef NEVER + int i; + printf("Parity Bytes: "); + for (i = 0; i < RS_ECC_NPARITY; i++) + printf("[%d]:%x, ",i,pBytes[i]); + printf("\n"); +#endif +} + + +void +print_syndrome (void) +{ +#ifdef NEVER + int i; + printf("Syndrome Bytes: "); + for (i = 0; i < RS_ECC_NPARITY; i++) + printf("[%d]:%x, ",i,synBytes[i]); + printf("\n"); +#endif +} + +/* Append the parity bytes onto the end of the message */ +void +build_codeword (unsigned char msg[], int nbytes, unsigned char dst[]) +{ + int i; + + for (i = 0; i < nbytes; i++) dst[i] = msg[i]; + + for (i = 0; i < RS_ECC_NPARITY; i++) { + dst[i+nbytes] = pBytes[RS_ECC_NPARITY-1-i]; + } +} + +/********************************************************** + * Reed Solomon Decoder + * + * Computes the syndrome of a codeword. Puts the results + * into the synBytes[] array. + */ + +void +decode_data(unsigned char data[], int nbytes) +{ + int i, j, sum; + for (j = 0; j < RS_ECC_NPARITY; j++) { + sum = 0; + for (i = 0; i < nbytes; i++) { + sum = data[i] ^ gmult(gexp[j+1], sum); + } + synBytes[j] = sum; + } +} + + +/* Check if the syndrome is zero */ +int +check_syndrome (void) +{ + int i, nz = 0; + for (i =0 ; i < RS_ECC_NPARITY; i++) { + if (synBytes[i] != 0) { + nz = 1; + break; + } + } + return nz; +} + + +void +debug_check_syndrome (void) +{ +#ifdef NEVER + int i; + + for (i = 0; i < 3; i++) { + printf(" inv log S[%d]/S[%d] = %d\n", i, i+1, + glog[gmult(synBytes[i], ginv(synBytes[i+1]))]); + } +#endif +} + + +/* Create a generator polynomial for an n byte RS code. + * The coefficients are returned in the genPoly arg. + * Make sure that the genPoly array which is passed in is + * at least n+1 bytes long. + */ + +static void +compute_genpoly (int nbytes, int genpoly[]) +{ + int i, tp[256], tp1[256]; + + /* multiply (x + a^n) for n = 1 to nbytes */ + + zero_poly(tp1); + tp1[0] = 1; + + for (i = 1; i <= nbytes; i++) { + zero_poly(tp); + tp[0] = gexp[i]; /* set up x+a^n */ + tp[1] = 1; + + mult_polys(genpoly, tp, tp1); + copy_poly(tp1, genpoly); + } +} + +/* Simulate a LFSR with generator polynomial for n byte RS code. + * Pass in a pointer to the data array, and amount of data. + * + * The parity bytes are deposited into pBytes[], and the whole message + * and parity are copied to dest to make a codeword. + * + */ + +void +encode_data (unsigned char msg[], int nbytes, unsigned char dst[]) +{ + int i, LFSR[RS_ECC_NPARITY+1],dbyte, j; + + for(i=0; i < RS_ECC_NPARITY+1; i++) LFSR[i]=0; + + for (i = 0; i < nbytes; i++) { + dbyte = msg[i] ^ LFSR[RS_ECC_NPARITY-1]; + for (j = RS_ECC_NPARITY-1; j > 0; j--) { + LFSR[j] = LFSR[j-1] ^ gmult(genPoly[j], dbyte); + } + LFSR[0] = gmult(genPoly[0], dbyte); + } + + for (i = 0; i < RS_ECC_NPARITY; i++) + pBytes[i] = LFSR[i]; + + build_codeword(msg, nbytes, dst); +} + diff --git a/flight/Libraries/rscode/rs.doc b/flight/Libraries/rscode/rs.doc new file mode 100644 index 000000000..651f76c78 --- /dev/null +++ b/flight/Libraries/rscode/rs.doc @@ -0,0 +1,86 @@ + + +Introduction to Reed Solomon Codes: + +Henry Minsky, Universal Access Inc. +hqm@alum.mit.edu + +[For details see Cain, Clark, "Error-Correction Coding For Digital +Communications", pp. 205.] The Reed-Solomon Code is an algebraic code +belonging to the class of BCH (Bose-Chaudry-Hocquehen) multiple burst +correcting cyclic codes. The Reed Solomon code operates on bytes of +fixed length. + +Given m parity bytes, a Reed-Solomon code can correct up to m byte +errors in known positions (erasures), or detect and correct up to m/2 +byte errors in unknown positions. + +This is an implementation of a Reed-Solomon code with 8 bit bytes, and +a configurable number of parity bytes. The maximum sequence length +(codeword) that can be generated is 255 bytes, including parity bytes. +In practice, shorter sequences are used. + +ENCODING: The basic principle of encoding is to find the remainder of +the message divided by a generator polynomial G(x). The encoder works +by simulating a Linear Feedback Shift Register with degree equal to +G(x), and feedback taps with the coefficents of the generating +polynomial of the code. + +The rs.c file contains an algorithm to generate the encoder polynomial +for any number of bytes of parity, configurable as the NPAR constant +in the file ecc.h. + +For this RS code, G(x) = (x-a^1)(x-a^2)(x-a^3)(x-a^4)...(x-a^NPAR) +where 'a' is a primitive element of the Galois Field GF(256) (== 2). + +DECODING + +The decoder generates four syndrome bytes, which will be all zero if +the message has no errors. If there are errors, the location and value +of the errors can be determined in a number of ways. + +Computing the syndromes is easily done as a sum of products, see pp. +179 [Rhee 89]. + +Fundamentally, the syndome bytes form four simultaneous equations +which can be solved to find the error locations. Once error locations +are known, the syndrome bytes can be used to find the value of the +errors, and they can thus be corrected. + +A simplified solution for locating and correcting single errors is +given in Cain and Clark, Ch. 5. + +The more general error-location algorithm is the Berlekamp-Massey +algorithm, which will locate up to four errors, by iteratively solving +for the error-locator polynomial. The Modified Berlekamp Massey +algorithm takes as initial conditions any known suspicious bytes +(erasure flags) which you may have (such as might be flagged by +a laser demodulator, or deduced from a failure in a cross-interleaved +block code row or column). + +Once the location of errors is known, error correction is done using +the error-evaluator polynomial. + +APPLICATION IDEAS + +As an example application, this library could be used to implement the +Compact Disc standard of 24 data bytes and 4 parity bytes. A RS code +with 24 data bytes and 4 parity bytes is referred to as a (28,24) RS +code. A (n, k) RS code is said to have efficiency k/n. This first +(28,24) coding is called the C2 or level 2 encoding, because in a +doubly encoded scheme, the codewords are decoded at the second +decoding step. + +In following the approach used by Compact Disc digital audio, the 28 +byte C2 codewords are four way interleaved and then the interleaved +data is encoded again with a (32,28) RS code. The is the C1 encoding +stage. This produces what is known as a "product code", and has +excellent error correction capability due to the imposition of +two-dimensional structure on the parity checks. The interleave helps +to insure against the case that a multibyte burst error wipes out more +than two bytes in each codeword. The cross-correction capability of +the product code can provide backup if in fact there are more than 2 +uncorrectable errors in a block. + + + diff --git a/flight/Modules/AHRSComms/ahrs_comms.c b/flight/Modules/AHRSComms/ahrs_comms.c index c3fb45fae..abda58ee0 100644 --- a/flight/Modules/AHRSComms/ahrs_comms.c +++ b/flight/Modules/AHRSComms/ahrs_comms.c @@ -52,11 +52,10 @@ #include "ahrs_comms.h" #include "ahrs_spi_comm.h" -#include "ahrsstatus.h" -#include "ahrscalibration.h" +#include "insstatus.h" // Private constants -#define STACK_SIZE configMINIMAL_STACK_SIZE-128 +#define STACK_SIZE configMINIMAL_STACK_SIZE #define TASK_PRIORITY (tskIDLE_PRIORITY+4) // Private types @@ -87,9 +86,10 @@ int32_t AHRSCommsStart(void) */ int32_t AHRSCommsInitialize(void) { - AhrsStatusInitialize(); - AHRSCalibrationInitialize(); + InsStatusInitialize(); + InsSettingsInitialize(); AttitudeRawInitialize(); + AttitudeActualInitialize(); VelocityActualInitialize(); PositionActualInitialize(); @@ -109,19 +109,17 @@ static void ahrscommsTask(void *parameters) // Main task loop while (1) { PIOS_WDG_UpdateFlag(PIOS_WDG_AHRS); + AhrsCommStatus stat; - AHRSSettingsData settings; - AHRSSettingsGet(&settings); - AhrsSendObjects(); - AhrsCommStatus stat = AhrsGetStatus(); + AhrsGetStatus(&stat); if (stat.linkOk) { AlarmsClear(SYSTEMALARMS_ALARM_AHRSCOMMS); } else { AlarmsSet(SYSTEMALARMS_ALARM_AHRSCOMMS, SYSTEMALARMS_ALARM_WARNING); } - AhrsStatusData sData; - AhrsStatusGet(&sData); + InsStatusData sData; + InsStatusGet(&sData); sData.LinkRunning = stat.linkOk; sData.AhrsKickstarts = stat.remote.kickStarts; @@ -132,9 +130,9 @@ static void ahrscommsTask(void *parameters) sData.OpRetries = stat.local.retries; sData.OpInvalidPackets = stat.local.invalidPacket; - AhrsStatusSet(&sData); + InsStatusSet(&sData); /* Wait for the next update interval */ - vTaskDelayUntil(&lastSysTime, settings.UpdatePeriod / portTICK_RATE_MS); + vTaskDelayUntil(&lastSysTime, 2 / portTICK_RATE_MS); } } diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c index 9cc856487..1995355e3 100644 --- a/flight/Modules/Actuator/actuator.c +++ b/flight/Modules/Actuator/actuator.c @@ -216,7 +216,7 @@ static void actuatorTask(void* parameters) AlarmsClear(SYSTEMALARMS_ALARM_ACTUATOR); bool armed = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED; - bool positiveThrottle = desired.Throttle >= 0.00; + bool positiveThrottle = desired.Throttle >= 0.00f; bool spinWhileArmed = MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE; float curve1 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve1,MIXERSETTINGS_THROTTLECURVE1_NUMELEM); @@ -325,26 +325,29 @@ static void actuatorTask(void* parameters) else status[ct] = -1; } - - command.Channel[ct] = scaleChannel(status[ct], - ChannelMax[ct], - ChannelMin[ct], - ChannelNeutral[ct]); } -#if defined(DIAGNOSTICS) - MixerStatusSet(&mixerStatus); -#endif - + + for(int i = 0; i < MAX_MIX_ACTUATORS; i++) + command.Channel[i] = scaleChannel(status[i], + ChannelMax[i], + ChannelMin[i], + ChannelNeutral[i]); + // Store update time - command.UpdateTime = 1000*dT; - if(1000*dT > command.MaxUpdateTime) - command.MaxUpdateTime = 1000*dT; - + command.UpdateTime = 1000.0f*dT; + if(1000.0f*dT > command.MaxUpdateTime) + command.MaxUpdateTime = 1000.0f*dT; + // Update output object ActuatorCommandSet(&command); // Update in case read only (eg. during servo configuration) ActuatorCommandGet(&command); +#if defined(DIAGNOSTICS) + MixerStatusSet(&mixerStatus); +#endif + + // Update servo outputs bool success = true; @@ -367,22 +370,21 @@ static void actuatorTask(void* parameters) /** *Process mixing for one actuator */ - float ProcessMixer(const int index, const float curve1, const float curve2, MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, const float period) { Mixer_t * mixers = (Mixer_t *)&mixerSettings->Mixer1Type; //pointer to array of mixers in UAVObjects Mixer_t * mixer = &mixers[index]; - float result = ((mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE1] / 128.0f) * curve1) + - ((mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE2] / 128.0f) * curve2) + - ((mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_ROLL] / 128.0f) * desired->Roll) + - ((mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_PITCH] / 128.0f) * desired->Pitch) + - ((mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_YAW] / 128.0f) * desired->Yaw); + float result = (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE1] / 128.0f) * curve1) + + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE2] / 128.0f) * curve2) + + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_ROLL] / 128.0f) * desired->Roll) + + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_PITCH] / 128.0f) * desired->Pitch) + + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_YAW] / 128.0f) * desired->Yaw); if(mixer->type == MIXERSETTINGS_MIXER1TYPE_MOTOR) { - if(result < 0) //idle throttle + if(result < 0.0f) //idle throttle { - result = 0; + result = 0.0f; } //feed forward @@ -392,7 +394,7 @@ float ProcessMixer(const int index, const float curve1, const float curve2, result += accumulator; if(period !=0) { - if(accumulator > 0) + if(accumulator > 0.0f) { float filter = mixerSettings->AccelTime / period; if(filter <1) @@ -422,6 +424,7 @@ float ProcessMixer(const int index, const float curve1, const float curve2, } lastFilteredResult[index] = result; } + return(result); } @@ -432,7 +435,7 @@ float ProcessMixer(const int index, const float curve1, const float curve2, */ static float MixerCurve(const float throttle, const float* curve, uint8_t elements) { - float scale = throttle * (elements - 1); + float scale = throttle * (float) (elements - 1); int idx1 = scale; scale -= (float)idx1; //remainder if(curve[0] < -1) @@ -453,7 +456,7 @@ static float MixerCurve(const float throttle, const float* curve, uint8_t elemen idx1 = elements -1; } } - return((curve[idx1] * (1 - scale)) + (curve[idx2] * scale)); + return curve[idx1] * (1.0f - scale) + curve[idx2] * scale; } @@ -464,7 +467,7 @@ static int16_t scaleChannel(float value, int16_t max, int16_t min, int16_t neutr { int16_t valueScaled; // Scale - if ( value >= 0.0) + if ( value >= 0.0f) { valueScaled = (int16_t)(value*((float)(max-neutral))) + neutral; } @@ -520,6 +523,8 @@ static void setFailsafe() { Channel[n] = 0; } + + } // Set alarm @@ -532,7 +537,7 @@ static void setFailsafe() } // Update output object's parts that we changed - ActuatorCommandChannelGet(Channel); + ActuatorCommandChannelSet(Channel); } diff --git a/flight/Modules/Altitude/altitude.c b/flight/Modules/Altitude/altitude.c index 87a4240b6..4898829b0 100644 --- a/flight/Modules/Altitude/altitude.c +++ b/flight/Modules/Altitude/altitude.c @@ -120,7 +120,7 @@ static void altitudeTask(void *parameters) { BaroAltitudeData data; portTickType lastSysTime; - + #if defined(PIOS_INCLUDE_HCSR04) SonarAltitudeData sonardata; int32_t value=0,timeout=5; @@ -129,7 +129,7 @@ static void altitudeTask(void *parameters) PIOS_HCSR04_Trigger(); #endif PIOS_BMP085_Init(); - + // Main task loop lastSysTime = xTaskGetTickCount(); while (1) @@ -145,7 +145,7 @@ static void altitudeTask(void *parameters) height_out = (height_out * (1 - coeff)) + (height_in * coeff); sonardata.Altitude = height_out; // m/us } - + // Update the AltitudeActual UAVObject SonarAltitudeSet(&sonardata); timeout=5; @@ -167,7 +167,7 @@ static void altitudeTask(void *parameters) #endif PIOS_BMP085_ReadADC(); alt_ds_temp += PIOS_BMP085_GetTemperature(); - + // Update the pressure data PIOS_BMP085_StartADC(PressureConv); #ifdef PIOS_BMP085_HAS_GPIOS @@ -177,7 +177,7 @@ static void altitudeTask(void *parameters) #endif PIOS_BMP085_ReadADC(); alt_ds_pres += PIOS_BMP085_GetPressure(); - + if (++alt_ds_count >= alt_ds_size) { alt_ds_count = 0; @@ -203,6 +203,6 @@ static void altitudeTask(void *parameters) } /** - * @} + * @} * @} */ diff --git a/flight/Modules/Altitude/revolution/altitude.c b/flight/Modules/Altitude/revolution/altitude.c new file mode 100644 index 000000000..7f9052038 --- /dev/null +++ b/flight/Modules/Altitude/revolution/altitude.c @@ -0,0 +1,158 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup AltitudeModule Altitude Module + * @brief Communicate with BMP085 and update @ref BaroAltitude "BaroAltitude UAV Object" + * @{ + * + * @file altitude.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Altitude module, handles temperature and pressure readings from BMP085 + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/** + * Output object: BaroAltitude + * + * This module will periodically update the value of the BaroAltitude object. + * + */ + +#include "openpilot.h" +#include "altitude.h" +#include "baroaltitude.h" // object that will be updated by the module +#if defined(PIOS_INCLUDE_HCSR04) +#include "sonaraltitude.h" // object that will be updated by the module +#endif + +// Private constants +#define STACK_SIZE_BYTES 500 +#define TASK_PRIORITY (tskIDLE_PRIORITY+1) + +// Private types + +// Private variables +static xTaskHandle taskHandle; + +// Private functions +static void altitudeTask(void *parameters); + +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t AltitudeStart() +{ +#if defined(PIOS_INCLUDE_HCSR04) + SonarAltitudeInitialze(); +#endif + + // Start main task + xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle); + + return 0; +} + +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t AltitudeInitialize() +{ + BaroAltitudeInitialize(); + + return 0; +} +MODULE_INITCALL(AltitudeInitialize, AltitudeStart) +/** + * Module thread, should not return. + */ +static void altitudeTask(void *parameters) +{ + BaroAltitudeData data; + +#if defined(PIOS_INCLUDE_HCSR04) + SonarAltitudeData sonardata; + int32_t value=0,timeout=5; + float coeff=0.25,height_out=0,height_in=0; + PIOS_HCSR04_Init(); + PIOS_HCSR04_Trigger(); +#endif + + // TODO: Check the pressure sensor and set a warning if it fails test + + // Main task loop + while (1) + { +#if defined(PIOS_INCLUDE_HCSR04) + // Compute the current altitude (all pressures in kPa) + if(PIOS_HCSR04_Completed()) + { + value = PIOS_HCSR04_Get(); + if((value>100) && (value < 15000)) //from 3.4cm to 5.1m + { + height_in = value*0.00034; + height_out = (height_out * (1 - coeff)) + (height_in * coeff); + sonardata.Altitude = height_out; // m/us + } + + // Update the AltitudeActual UAVObject + SonarAltitudeSet(&sonardata); + timeout=5; + PIOS_HCSR04_Trigger(); + } + if(timeout--) + { + //retrigger + timeout=5; + PIOS_HCSR04_Trigger(); + } +#endif + float temp, press; + + // Update the temperature data + PIOS_MS5611_StartADC(TemperatureConv); + vTaskDelay(PIOS_MS5611_GetDelay()); + PIOS_MS5611_ReadADC(); + + // Update the pressure data + PIOS_MS5611_StartADC(PressureConv); + vTaskDelay(PIOS_MS5611_GetDelay()); + PIOS_MS5611_ReadADC(); + + + temp = PIOS_MS5611_GetTemperature(); + press = PIOS_MS5611_GetPressure(); + + data.Temperature = temp; + data.Pressure = press; + data.Altitude = 44330.0f * (1.0f - powf(data.Pressure / MS5611_P0, (1.0f / 5.255f))); + + // Update the AltitudeActual UAVObject + BaroAltitudeSet(&data); + } +} + +/** + * @} + * @} + */ diff --git a/flight/Modules/Altitude/revolution/inc/altitude.h b/flight/Modules/Altitude/revolution/inc/altitude.h new file mode 100644 index 000000000..2dad6acc2 --- /dev/null +++ b/flight/Modules/Altitude/revolution/inc/altitude.h @@ -0,0 +1,41 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup AltitudeModule Altitude Module + * @brief Communicate with BMP085 and update @ref AltitudeActual "AltitudeActual UAV Object" + * @{ + * + * @file altitude.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Altitude module, reads temperature and pressure from BMP085 + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ALTITUDE_H +#define ALTITUDE_H + +int32_t AltitudeInitialize(); + +#endif // ALTITUDE_H + +/** + * @} + * @} + */ diff --git a/flight/Modules/AltitudeHold/altitudehold.c b/flight/Modules/AltitudeHold/altitudehold.c new file mode 100644 index 000000000..9514be5c9 --- /dev/null +++ b/flight/Modules/AltitudeHold/altitudehold.c @@ -0,0 +1,372 @@ +/** + ****************************************************************************** + * + * @file guidance.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This module compared @ref PositionActuatl to @ref ActiveWaypoint + * and sets @ref AttitudeDesired. It only does this when the FlightMode field + * of @ref ManualControlCommand is Auto. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/** + * Input object: ActiveWaypoint + * Input object: PositionActual + * Input object: ManualControlCommand + * Output object: AttitudeDesired + * + * This module will periodically update the value of the AttitudeDesired object. + * + * The module executes in its own thread in this example. + * + * Modules have no API, all communication to other modules is done through UAVObjects. + * However modules may use the API exposed by shared libraries. + * See the OpenPilot wiki for more details. + * http://www.openpilot.org/OpenPilot_Application_Architecture + * + */ + +#include "openpilot.h" +#include +#include "CoordinateConversions.h" +#include "altholdsmoothed.h" +#include "attitudeactual.h" +#include "altitudeholdsettings.h" +#include "altitudeholddesired.h" // object that will be updated by the module +#include "baroaltitude.h" +#include "positionactual.h" +#include "flightstatus.h" +#include "stabilizationdesired.h" +#include "accels.h" + +// Private constants +#define MAX_QUEUE_SIZE 2 +#define STACK_SIZE_BYTES 1024 +#define TASK_PRIORITY (tskIDLE_PRIORITY+1) +// Private types + +// Private variables +static xTaskHandle altitudeHoldTaskHandle; +static xQueueHandle queue; +static AltitudeHoldSettingsData altitudeHoldSettings; + +// Private functions +static void altitudeHoldTask(void *parameters); +static void SettingsUpdatedCb(UAVObjEvent * ev); + +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t AltitudeHoldStart() +{ + // Start main task + xTaskCreate(altitudeHoldTask, (signed char *)"AltitudeHold", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &altitudeHoldTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDEHOLD, altitudeHoldTaskHandle); + + return 0; +} + +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t AltitudeHoldInitialize() +{ + AltitudeHoldSettingsInitialize(); + AltitudeHoldDesiredInitialize(); + AltHoldSmoothedInitialize(); + + // Create object queue + queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); + + AltitudeHoldSettingsConnectCallback(&SettingsUpdatedCb); + + return 0; +} +MODULE_INITCALL(AltitudeHoldInitialize, AltitudeHoldStart) + +float tau; +float throttleIntegral; +float velocity; +float decay; +float velocity_decay; +bool running = false; +float error; +float switchThrottle; +float smoothed_altitude; +float starting_altitude; + +/** + * Module thread, should not return. + */ +static void altitudeHoldTask(void *parameters) +{ + AltitudeHoldDesiredData altitudeHoldDesired; + StabilizationDesiredData stabilizationDesired; + + portTickType thisTime, lastUpdateTime; + UAVObjEvent ev; + + // Force update of the settings + SettingsUpdatedCb(&ev); + + // Listen for updates. + AltitudeHoldDesiredConnectQueue(queue); + BaroAltitudeConnectQueue(queue); + FlightStatusConnectQueue(queue); + AccelsConnectQueue(queue); + + BaroAltitudeAltitudeGet(&smoothed_altitude); + running = false; + enum init_state {WAITING_BARO, WAITIING_INIT, INITED} init = WAITING_BARO; + + // Main task loop + bool baro_updated = false; + while (1) { + // Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe + if ( xQueueReceive(queue, &ev, 100 / portTICK_RATE_MS) != pdTRUE ) + { + if(!running) + throttleIntegral = 0; + + // Todo: Add alarm if it should be running + continue; + } else if (ev.obj == BaroAltitudeHandle()) { + baro_updated = true; + + init = (init == WAITING_BARO) ? WAITIING_INIT : init; + } else if (ev.obj == FlightStatusHandle()) { + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + + if(flightStatus.FlightMode == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD && !running) { + // Copy the current throttle as a starting point for integral + StabilizationDesiredThrottleGet(&throttleIntegral); + switchThrottle = throttleIntegral; + error = 0; + velocity = 0; + running = true; + + AltHoldSmoothedData altHold; + AltHoldSmoothedGet(&altHold); + starting_altitude = altHold.Altitude; + } else if (flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) + running = false; + } else if (ev.obj == AccelsHandle()) { + static uint32_t timeval; + + static float z[4] = {0, 0, 0, 0}; + float z_new[4]; + float P[4][4], K[4][2], x[2]; + float G[4] = {1.0e-15f, 1.0e-15f, 1.0e-3f, 1.0e-7}; + static float V[4][4] = {{10.0f, 0, 0, 0}, {0, 100.0f, 0, 0}, {0, 0, 100.0f, 0}, {0, 0, 0, 1000.0f}}; + + float dT; + static float S[2] = {1.0f,10.0f}; + + thisTime = xTaskGetTickCount(); + + /* Somehow this always assigns to zero. Compiler bug? Race condition? */ + S[0] = altitudeHoldSettings.PressureNoise; + S[1] = altitudeHoldSettings.AccelNoise; + G[2] = altitudeHoldSettings.AccelDrift; + + AccelsData accels; + AccelsGet(&accels); + AttitudeActualData attitudeActual; + AttitudeActualGet(&attitudeActual); + BaroAltitudeData baro; + BaroAltitudeGet(&baro); + + if (init == WAITIING_INIT) { + z[0] = baro.Altitude; + z[1] = 0; + z[2] = accels.z; + z[3] = 0; + init = INITED; + } else if (init == WAITING_BARO) + continue; + + x[0] = baro.Altitude; + //rotate avg accels into earth frame and store it + if(1) { + float q[4], Rbe[3][3]; + q[0]=attitudeActual.q1; + q[1]=attitudeActual.q2; + q[2]=attitudeActual.q3; + q[3]=attitudeActual.q4; + Quaternion2R(q, Rbe); + x[1] = -(Rbe[0][2]*accels.x+ Rbe[1][2]*accels.y + Rbe[2][2]*accels.z + 9.81f); + } else { + x[1] = -accels.z + 9.81f; + } + + dT = PIOS_DELAY_DiffuS(timeval) / 1.0e6f; + timeval = PIOS_DELAY_GetRaw(); + + P[0][0] = dT*(V[0][1]+dT*V[1][1])+V[0][0]+G[0]+dT*V[1][0]; + P[0][1] = dT*(V[0][2]+dT*V[1][2])+V[0][1]+dT*V[1][1]; + P[0][2] = V[0][2]+dT*V[1][2]; + P[0][3] = V[0][3]+dT*V[1][3]; + P[1][0] = dT*(V[1][1]+dT*V[2][1])+V[1][0]+dT*V[2][0]; + P[1][1] = dT*(V[1][2]+dT*V[2][2])+V[1][1]+G[1]+dT*V[2][1]; + P[1][2] = V[1][2]+dT*V[2][2]; + P[1][3] = V[1][3]+dT*V[2][3]; + P[2][0] = V[2][0]+dT*V[2][1]; + P[2][1] = V[2][1]+dT*V[2][2]; + P[2][2] = V[2][2]+G[2]; + P[2][3] = V[2][3]; + P[3][0] = V[3][0]+dT*V[3][1]; + P[3][1] = V[3][1]+dT*V[3][2]; + P[3][2] = V[3][2]; + P[3][3] = V[3][3]+G[3]; + + if (baro_updated) { + K[0][0] = -(V[2][2]*S[0]+V[2][3]*S[0]+V[3][2]*S[0]+V[3][3]*S[0]+G[2]*S[0]+G[3]*S[0]+S[0]*S[1])/(V[0][0]*G[2]+V[0][0]*G[3]+V[2][2]*G[0]+V[2][3]*G[0]+V[3][2]*G[0]+V[3][3]*G[0]+V[0][0]*S[1]+V[2][2]*S[0]+V[2][3]*S[0]+V[3][2]*S[0]+V[3][3]*S[0]+V[0][0]*V[2][2]-V[0][2]*V[2][0]+V[0][0]*V[2][3]+V[0][0]*V[3][2]-V[0][2]*V[3][0]-V[2][0]*V[0][3]+V[0][0]*V[3][3]-V[0][3]*V[3][0]+G[0]*G[2]+G[0]*G[3]+G[0]*S[1]+G[2]*S[0]+G[3]*S[0]+S[0]*S[1]+(dT*dT)*V[1][1]*V[2][2]-(dT*dT)*V[1][2]*V[2][1]+(dT*dT)*V[1][1]*V[2][3]+(dT*dT)*V[1][1]*V[3][2]-(dT*dT)*V[1][2]*V[3][1]-(dT*dT)*V[2][1]*V[1][3]+(dT*dT)*V[1][1]*V[3][3]-(dT*dT)*V[1][3]*V[3][1]+dT*V[0][1]*G[2]+dT*V[1][0]*G[2]+dT*V[0][1]*G[3]+dT*V[1][0]*G[3]+dT*V[0][1]*S[1]+dT*V[1][0]*S[1]+(dT*dT)*V[1][1]*G[2]+(dT*dT)*V[1][1]*G[3]+(dT*dT)*V[1][1]*S[1]+dT*V[0][1]*V[2][2]+dT*V[1][0]*V[2][2]-dT*V[0][2]*V[2][1]-dT*V[2][0]*V[1][2]+dT*V[0][1]*V[2][3]+dT*V[0][1]*V[3][2]+dT*V[1][0]*V[2][3]+dT*V[1][0]*V[3][2]-dT*V[0][2]*V[3][1]-dT*V[2][0]*V[1][3]-dT*V[0][3]*V[2][1]-dT*V[1][2]*V[3][0]+dT*V[0][1]*V[3][3]+dT*V[1][0]*V[3][3]-dT*V[0][3]*V[3][1]-dT*V[3][0]*V[1][3])+1.0f; + K[0][1] = ((V[0][2]+V[0][3])*S[0]+dT*(V[1][2]+V[1][3])*S[0])/(V[0][0]*G[2]+V[0][0]*G[3]+V[2][2]*G[0]+V[2][3]*G[0]+V[3][2]*G[0]+V[3][3]*G[0]+V[0][0]*S[1]+V[2][2]*S[0]+V[2][3]*S[0]+V[3][2]*S[0]+V[3][3]*S[0]+V[0][0]*V[2][2]-V[0][2]*V[2][0]+V[0][0]*V[2][3]+V[0][0]*V[3][2]-V[0][2]*V[3][0]-V[2][0]*V[0][3]+V[0][0]*V[3][3]-V[0][3]*V[3][0]+G[0]*G[2]+G[0]*G[3]+G[0]*S[1]+G[2]*S[0]+G[3]*S[0]+S[0]*S[1]+(dT*dT)*V[1][1]*V[2][2]-(dT*dT)*V[1][2]*V[2][1]+(dT*dT)*V[1][1]*V[2][3]+(dT*dT)*V[1][1]*V[3][2]-(dT*dT)*V[1][2]*V[3][1]-(dT*dT)*V[2][1]*V[1][3]+(dT*dT)*V[1][1]*V[3][3]-(dT*dT)*V[1][3]*V[3][1]+dT*V[0][1]*G[2]+dT*V[1][0]*G[2]+dT*V[0][1]*G[3]+dT*V[1][0]*G[3]+dT*V[0][1]*S[1]+dT*V[1][0]*S[1]+(dT*dT)*V[1][1]*G[2]+(dT*dT)*V[1][1]*G[3]+(dT*dT)*V[1][1]*S[1]+dT*V[0][1]*V[2][2]+dT*V[1][0]*V[2][2]-dT*V[0][2]*V[2][1]-dT*V[2][0]*V[1][2]+dT*V[0][1]*V[2][3]+dT*V[0][1]*V[3][2]+dT*V[1][0]*V[2][3]+dT*V[1][0]*V[3][2]-dT*V[0][2]*V[3][1]-dT*V[2][0]*V[1][3]-dT*V[0][3]*V[2][1]-dT*V[1][2]*V[3][0]+dT*V[0][1]*V[3][3]+dT*V[1][0]*V[3][3]-dT*V[0][3]*V[3][1]-dT*V[3][0]*V[1][3]); + K[1][0] = (V[1][0]*G[2]+V[1][0]*G[3]+V[1][0]*S[1]+V[1][0]*V[2][2]-V[2][0]*V[1][2]+V[1][0]*V[2][3]+V[1][0]*V[3][2]-V[2][0]*V[1][3]-V[1][2]*V[3][0]+V[1][0]*V[3][3]-V[3][0]*V[1][3]+(dT*dT)*V[2][1]*V[3][2]-(dT*dT)*V[2][2]*V[3][1]+(dT*dT)*V[2][1]*V[3][3]-(dT*dT)*V[3][1]*V[2][3]+dT*V[1][1]*G[2]+dT*V[2][0]*G[2]+dT*V[1][1]*G[3]+dT*V[2][0]*G[3]+dT*V[1][1]*S[1]+dT*V[2][0]*S[1]+(dT*dT)*V[2][1]*G[2]+(dT*dT)*V[2][1]*G[3]+(dT*dT)*V[2][1]*S[1]+dT*V[1][1]*V[2][2]-dT*V[1][2]*V[2][1]+dT*V[1][1]*V[2][3]+dT*V[1][1]*V[3][2]+dT*V[2][0]*V[3][2]-dT*V[1][2]*V[3][1]-dT*V[2][1]*V[1][3]-dT*V[3][0]*V[2][2]+dT*V[1][1]*V[3][3]+dT*V[2][0]*V[3][3]-dT*V[3][0]*V[2][3]-dT*V[1][3]*V[3][1])/(V[0][0]*G[2]+V[0][0]*G[3]+V[2][2]*G[0]+V[2][3]*G[0]+V[3][2]*G[0]+V[3][3]*G[0]+V[0][0]*S[1]+V[2][2]*S[0]+V[2][3]*S[0]+V[3][2]*S[0]+V[3][3]*S[0]+V[0][0]*V[2][2]-V[0][2]*V[2][0]+V[0][0]*V[2][3]+V[0][0]*V[3][2]-V[0][2]*V[3][0]-V[2][0]*V[0][3]+V[0][0]*V[3][3]-V[0][3]*V[3][0]+G[0]*G[2]+G[0]*G[3]+G[0]*S[1]+G[2]*S[0]+G[3]*S[0]+S[0]*S[1]+(dT*dT)*V[1][1]*V[2][2]-(dT*dT)*V[1][2]*V[2][1]+(dT*dT)*V[1][1]*V[2][3]+(dT*dT)*V[1][1]*V[3][2]-(dT*dT)*V[1][2]*V[3][1]-(dT*dT)*V[2][1]*V[1][3]+(dT*dT)*V[1][1]*V[3][3]-(dT*dT)*V[1][3]*V[3][1]+dT*V[0][1]*G[2]+dT*V[1][0]*G[2]+dT*V[0][1]*G[3]+dT*V[1][0]*G[3]+dT*V[0][1]*S[1]+dT*V[1][0]*S[1]+(dT*dT)*V[1][1]*G[2]+(dT*dT)*V[1][1]*G[3]+(dT*dT)*V[1][1]*S[1]+dT*V[0][1]*V[2][2]+dT*V[1][0]*V[2][2]-dT*V[0][2]*V[2][1]-dT*V[2][0]*V[1][2]+dT*V[0][1]*V[2][3]+dT*V[0][1]*V[3][2]+dT*V[1][0]*V[2][3]+dT*V[1][0]*V[3][2]-dT*V[0][2]*V[3][1]-dT*V[2][0]*V[1][3]-dT*V[0][3]*V[2][1]-dT*V[1][2]*V[3][0]+dT*V[0][1]*V[3][3]+dT*V[1][0]*V[3][3]-dT*V[0][3]*V[3][1]-dT*V[3][0]*V[1][3]); + K[1][1] = (V[1][2]*G[0]+V[1][3]*G[0]+V[1][2]*S[0]+V[1][3]*S[0]+V[0][0]*V[1][2]-V[1][0]*V[0][2]+V[0][0]*V[1][3]-V[1][0]*V[0][3]+(dT*dT)*V[0][1]*V[2][2]+(dT*dT)*V[1][0]*V[2][2]-(dT*dT)*V[0][2]*V[2][1]-(dT*dT)*V[2][0]*V[1][2]+(dT*dT)*V[0][1]*V[2][3]+(dT*dT)*V[1][0]*V[2][3]-(dT*dT)*V[2][0]*V[1][3]-(dT*dT)*V[0][3]*V[2][1]+(dT*dT*dT)*V[1][1]*V[2][2]-(dT*dT*dT)*V[1][2]*V[2][1]+(dT*dT*dT)*V[1][1]*V[2][3]-(dT*dT*dT)*V[2][1]*V[1][3]+dT*V[2][2]*G[0]+dT*V[2][3]*G[0]+dT*V[2][2]*S[0]+dT*V[2][3]*S[0]+dT*V[0][0]*V[2][2]+dT*V[0][1]*V[1][2]-dT*V[0][2]*V[1][1]-dT*V[0][2]*V[2][0]+dT*V[0][0]*V[2][3]+dT*V[0][1]*V[1][3]-dT*V[1][1]*V[0][3]-dT*V[2][0]*V[0][3])/(V[0][0]*G[2]+V[0][0]*G[3]+V[2][2]*G[0]+V[2][3]*G[0]+V[3][2]*G[0]+V[3][3]*G[0]+V[0][0]*S[1]+V[2][2]*S[0]+V[2][3]*S[0]+V[3][2]*S[0]+V[3][3]*S[0]+V[0][0]*V[2][2]-V[0][2]*V[2][0]+V[0][0]*V[2][3]+V[0][0]*V[3][2]-V[0][2]*V[3][0]-V[2][0]*V[0][3]+V[0][0]*V[3][3]-V[0][3]*V[3][0]+G[0]*G[2]+G[0]*G[3]+G[0]*S[1]+G[2]*S[0]+G[3]*S[0]+S[0]*S[1]+(dT*dT)*V[1][1]*V[2][2]-(dT*dT)*V[1][2]*V[2][1]+(dT*dT)*V[1][1]*V[2][3]+(dT*dT)*V[1][1]*V[3][2]-(dT*dT)*V[1][2]*V[3][1]-(dT*dT)*V[2][1]*V[1][3]+(dT*dT)*V[1][1]*V[3][3]-(dT*dT)*V[1][3]*V[3][1]+dT*V[0][1]*G[2]+dT*V[1][0]*G[2]+dT*V[0][1]*G[3]+dT*V[1][0]*G[3]+dT*V[0][1]*S[1]+dT*V[1][0]*S[1]+(dT*dT)*V[1][1]*G[2]+(dT*dT)*V[1][1]*G[3]+(dT*dT)*V[1][1]*S[1]+dT*V[0][1]*V[2][2]+dT*V[1][0]*V[2][2]-dT*V[0][2]*V[2][1]-dT*V[2][0]*V[1][2]+dT*V[0][1]*V[2][3]+dT*V[0][1]*V[3][2]+dT*V[1][0]*V[2][3]+dT*V[1][0]*V[3][2]-dT*V[0][2]*V[3][1]-dT*V[2][0]*V[1][3]-dT*V[0][3]*V[2][1]-dT*V[1][2]*V[3][0]+dT*V[0][1]*V[3][3]+dT*V[1][0]*V[3][3]-dT*V[0][3]*V[3][1]-dT*V[3][0]*V[1][3]); + K[2][0] = (V[2][0]*G[3]-V[3][0]*G[2]+V[2][0]*S[1]+V[2][0]*V[3][2]-V[3][0]*V[2][2]+V[2][0]*V[3][3]-V[3][0]*V[2][3]+dT*V[2][1]*G[3]-dT*V[3][1]*G[2]+dT*V[2][1]*S[1]+dT*V[2][1]*V[3][2]-dT*V[2][2]*V[3][1]+dT*V[2][1]*V[3][3]-dT*V[3][1]*V[2][3])/(V[0][0]*G[2]+V[0][0]*G[3]+V[2][2]*G[0]+V[2][3]*G[0]+V[3][2]*G[0]+V[3][3]*G[0]+V[0][0]*S[1]+V[2][2]*S[0]+V[2][3]*S[0]+V[3][2]*S[0]+V[3][3]*S[0]+V[0][0]*V[2][2]-V[0][2]*V[2][0]+V[0][0]*V[2][3]+V[0][0]*V[3][2]-V[0][2]*V[3][0]-V[2][0]*V[0][3]+V[0][0]*V[3][3]-V[0][3]*V[3][0]+G[0]*G[2]+G[0]*G[3]+G[0]*S[1]+G[2]*S[0]+G[3]*S[0]+S[0]*S[1]+(dT*dT)*V[1][1]*V[2][2]-(dT*dT)*V[1][2]*V[2][1]+(dT*dT)*V[1][1]*V[2][3]+(dT*dT)*V[1][1]*V[3][2]-(dT*dT)*V[1][2]*V[3][1]-(dT*dT)*V[2][1]*V[1][3]+(dT*dT)*V[1][1]*V[3][3]-(dT*dT)*V[1][3]*V[3][1]+dT*V[0][1]*G[2]+dT*V[1][0]*G[2]+dT*V[0][1]*G[3]+dT*V[1][0]*G[3]+dT*V[0][1]*S[1]+dT*V[1][0]*S[1]+(dT*dT)*V[1][1]*G[2]+(dT*dT)*V[1][1]*G[3]+(dT*dT)*V[1][1]*S[1]+dT*V[0][1]*V[2][2]+dT*V[1][0]*V[2][2]-dT*V[0][2]*V[2][1]-dT*V[2][0]*V[1][2]+dT*V[0][1]*V[2][3]+dT*V[0][1]*V[3][2]+dT*V[1][0]*V[2][3]+dT*V[1][0]*V[3][2]-dT*V[0][2]*V[3][1]-dT*V[2][0]*V[1][3]-dT*V[0][3]*V[2][1]-dT*V[1][2]*V[3][0]+dT*V[0][1]*V[3][3]+dT*V[1][0]*V[3][3]-dT*V[0][3]*V[3][1]-dT*V[3][0]*V[1][3]); + K[2][1] = (V[0][0]*G[2]+V[2][2]*G[0]+V[2][3]*G[0]+V[2][2]*S[0]+V[2][3]*S[0]+V[0][0]*V[2][2]-V[0][2]*V[2][0]+V[0][0]*V[2][3]-V[2][0]*V[0][3]+G[0]*G[2]+G[2]*S[0]+(dT*dT)*V[1][1]*V[2][2]-(dT*dT)*V[1][2]*V[2][1]+(dT*dT)*V[1][1]*V[2][3]-(dT*dT)*V[2][1]*V[1][3]+dT*V[0][1]*G[2]+dT*V[1][0]*G[2]+(dT*dT)*V[1][1]*G[2]+dT*V[0][1]*V[2][2]+dT*V[1][0]*V[2][2]-dT*V[0][2]*V[2][1]-dT*V[2][0]*V[1][2]+dT*V[0][1]*V[2][3]+dT*V[1][0]*V[2][3]-dT*V[2][0]*V[1][3]-dT*V[0][3]*V[2][1])/(V[0][0]*G[2]+V[0][0]*G[3]+V[2][2]*G[0]+V[2][3]*G[0]+V[3][2]*G[0]+V[3][3]*G[0]+V[0][0]*S[1]+V[2][2]*S[0]+V[2][3]*S[0]+V[3][2]*S[0]+V[3][3]*S[0]+V[0][0]*V[2][2]-V[0][2]*V[2][0]+V[0][0]*V[2][3]+V[0][0]*V[3][2]-V[0][2]*V[3][0]-V[2][0]*V[0][3]+V[0][0]*V[3][3]-V[0][3]*V[3][0]+G[0]*G[2]+G[0]*G[3]+G[0]*S[1]+G[2]*S[0]+G[3]*S[0]+S[0]*S[1]+(dT*dT)*V[1][1]*V[2][2]-(dT*dT)*V[1][2]*V[2][1]+(dT*dT)*V[1][1]*V[2][3]+(dT*dT)*V[1][1]*V[3][2]-(dT*dT)*V[1][2]*V[3][1]-(dT*dT)*V[2][1]*V[1][3]+(dT*dT)*V[1][1]*V[3][3]-(dT*dT)*V[1][3]*V[3][1]+dT*V[0][1]*G[2]+dT*V[1][0]*G[2]+dT*V[0][1]*G[3]+dT*V[1][0]*G[3]+dT*V[0][1]*S[1]+dT*V[1][0]*S[1]+(dT*dT)*V[1][1]*G[2]+(dT*dT)*V[1][1]*G[3]+(dT*dT)*V[1][1]*S[1]+dT*V[0][1]*V[2][2]+dT*V[1][0]*V[2][2]-dT*V[0][2]*V[2][1]-dT*V[2][0]*V[1][2]+dT*V[0][1]*V[2][3]+dT*V[0][1]*V[3][2]+dT*V[1][0]*V[2][3]+dT*V[1][0]*V[3][2]-dT*V[0][2]*V[3][1]-dT*V[2][0]*V[1][3]-dT*V[0][3]*V[2][1]-dT*V[1][2]*V[3][0]+dT*V[0][1]*V[3][3]+dT*V[1][0]*V[3][3]-dT*V[0][3]*V[3][1]-dT*V[3][0]*V[1][3]); + K[3][0] = (-V[2][0]*G[3]+V[3][0]*G[2]+V[3][0]*S[1]-V[2][0]*V[3][2]+V[3][0]*V[2][2]-V[2][0]*V[3][3]+V[3][0]*V[2][3]-dT*V[2][1]*G[3]+dT*V[3][1]*G[2]+dT*V[3][1]*S[1]-dT*V[2][1]*V[3][2]+dT*V[2][2]*V[3][1]-dT*V[2][1]*V[3][3]+dT*V[3][1]*V[2][3])/(V[0][0]*G[2]+V[0][0]*G[3]+V[2][2]*G[0]+V[2][3]*G[0]+V[3][2]*G[0]+V[3][3]*G[0]+V[0][0]*S[1]+V[2][2]*S[0]+V[2][3]*S[0]+V[3][2]*S[0]+V[3][3]*S[0]+V[0][0]*V[2][2]-V[0][2]*V[2][0]+V[0][0]*V[2][3]+V[0][0]*V[3][2]-V[0][2]*V[3][0]-V[2][0]*V[0][3]+V[0][0]*V[3][3]-V[0][3]*V[3][0]+G[0]*G[2]+G[0]*G[3]+G[0]*S[1]+G[2]*S[0]+G[3]*S[0]+S[0]*S[1]+(dT*dT)*V[1][1]*V[2][2]-(dT*dT)*V[1][2]*V[2][1]+(dT*dT)*V[1][1]*V[2][3]+(dT*dT)*V[1][1]*V[3][2]-(dT*dT)*V[1][2]*V[3][1]-(dT*dT)*V[2][1]*V[1][3]+(dT*dT)*V[1][1]*V[3][3]-(dT*dT)*V[1][3]*V[3][1]+dT*V[0][1]*G[2]+dT*V[1][0]*G[2]+dT*V[0][1]*G[3]+dT*V[1][0]*G[3]+dT*V[0][1]*S[1]+dT*V[1][0]*S[1]+(dT*dT)*V[1][1]*G[2]+(dT*dT)*V[1][1]*G[3]+(dT*dT)*V[1][1]*S[1]+dT*V[0][1]*V[2][2]+dT*V[1][0]*V[2][2]-dT*V[0][2]*V[2][1]-dT*V[2][0]*V[1][2]+dT*V[0][1]*V[2][3]+dT*V[0][1]*V[3][2]+dT*V[1][0]*V[2][3]+dT*V[1][0]*V[3][2]-dT*V[0][2]*V[3][1]-dT*V[2][0]*V[1][3]-dT*V[0][3]*V[2][1]-dT*V[1][2]*V[3][0]+dT*V[0][1]*V[3][3]+dT*V[1][0]*V[3][3]-dT*V[0][3]*V[3][1]-dT*V[3][0]*V[1][3]); + K[3][1] = (V[0][0]*G[3]+V[3][2]*G[0]+V[3][3]*G[0]+V[3][2]*S[0]+V[3][3]*S[0]+V[0][0]*V[3][2]-V[0][2]*V[3][0]+V[0][0]*V[3][3]-V[0][3]*V[3][0]+G[0]*G[3]+G[3]*S[0]+(dT*dT)*V[1][1]*V[3][2]-(dT*dT)*V[1][2]*V[3][1]+(dT*dT)*V[1][1]*V[3][3]-(dT*dT)*V[1][3]*V[3][1]+dT*V[0][1]*G[3]+dT*V[1][0]*G[3]+(dT*dT)*V[1][1]*G[3]+dT*V[0][1]*V[3][2]+dT*V[1][0]*V[3][2]-dT*V[0][2]*V[3][1]-dT*V[1][2]*V[3][0]+dT*V[0][1]*V[3][3]+dT*V[1][0]*V[3][3]-dT*V[0][3]*V[3][1]-dT*V[3][0]*V[1][3])/(V[0][0]*G[2]+V[0][0]*G[3]+V[2][2]*G[0]+V[2][3]*G[0]+V[3][2]*G[0]+V[3][3]*G[0]+V[0][0]*S[1]+V[2][2]*S[0]+V[2][3]*S[0]+V[3][2]*S[0]+V[3][3]*S[0]+V[0][0]*V[2][2]-V[0][2]*V[2][0]+V[0][0]*V[2][3]+V[0][0]*V[3][2]-V[0][2]*V[3][0]-V[2][0]*V[0][3]+V[0][0]*V[3][3]-V[0][3]*V[3][0]+G[0]*G[2]+G[0]*G[3]+G[0]*S[1]+G[2]*S[0]+G[3]*S[0]+S[0]*S[1]+(dT*dT)*V[1][1]*V[2][2]-(dT*dT)*V[1][2]*V[2][1]+(dT*dT)*V[1][1]*V[2][3]+(dT*dT)*V[1][1]*V[3][2]-(dT*dT)*V[1][2]*V[3][1]-(dT*dT)*V[2][1]*V[1][3]+(dT*dT)*V[1][1]*V[3][3]-(dT*dT)*V[1][3]*V[3][1]+dT*V[0][1]*G[2]+dT*V[1][0]*G[2]+dT*V[0][1]*G[3]+dT*V[1][0]*G[3]+dT*V[0][1]*S[1]+dT*V[1][0]*S[1]+(dT*dT)*V[1][1]*G[2]+(dT*dT)*V[1][1]*G[3]+(dT*dT)*V[1][1]*S[1]+dT*V[0][1]*V[2][2]+dT*V[1][0]*V[2][2]-dT*V[0][2]*V[2][1]-dT*V[2][0]*V[1][2]+dT*V[0][1]*V[2][3]+dT*V[0][1]*V[3][2]+dT*V[1][0]*V[2][3]+dT*V[1][0]*V[3][2]-dT*V[0][2]*V[3][1]-dT*V[2][0]*V[1][3]-dT*V[0][3]*V[2][1]-dT*V[1][2]*V[3][0]+dT*V[0][1]*V[3][3]+dT*V[1][0]*V[3][3]-dT*V[0][3]*V[3][1]-dT*V[3][0]*V[1][3]); + + z_new[0] = -K[0][0]*(dT*z[1]-x[0]+z[0])+dT*z[1]-K[0][1]*(-x[1]+z[2]+z[3])+z[0]; + z_new[1] = -K[1][0]*(dT*z[1]-x[0]+z[0])+dT*z[2]-K[1][1]*(-x[1]+z[2]+z[3])+z[1]; + z_new[2] = -K[2][0]*(dT*z[1]-x[0]+z[0])-K[2][1]*(-x[1]+z[2]+z[3])+z[2]; + z_new[3] = -K[3][0]*(dT*z[1]-x[0]+z[0])-K[3][1]*(-x[1]+z[2]+z[3])+z[3]; + + memcpy(z, z_new, sizeof(z_new)); + + V[0][0] = -K[0][1]*P[2][0]-K[0][1]*P[3][0]-P[0][0]*(K[0][0]-1.0f); + V[0][1] = -K[0][1]*P[2][1]-K[0][1]*P[3][2]-P[0][1]*(K[0][0]-1.0f); + V[0][2] = -K[0][1]*P[2][2]-K[0][1]*P[3][2]-P[0][2]*(K[0][0]-1.0f); + V[0][3] = -K[0][1]*P[2][3]-K[0][1]*P[3][3]-P[0][3]*(K[0][0]-1.0f); + V[1][0] = P[1][0]-K[1][0]*P[0][0]-K[1][1]*P[2][0]-K[1][1]*P[3][0]; + V[1][1] = P[1][1]-K[1][0]*P[0][1]-K[1][1]*P[2][1]-K[1][1]*P[3][2]; + V[1][2] = P[1][2]-K[1][0]*P[0][2]-K[1][1]*P[2][2]-K[1][1]*P[3][2]; + V[1][3] = P[1][3]-K[1][0]*P[0][3]-K[1][1]*P[2][3]-K[1][1]*P[3][3]; + V[2][0] = -K[2][0]*P[0][0]-K[2][1]*P[3][0]-P[2][0]*(K[2][1]-1.0f); + V[2][1] = -K[2][0]*P[0][1]-K[2][1]*P[3][2]-P[2][1]*(K[2][1]-1.0f); + V[2][2] = -K[2][0]*P[0][2]-K[2][1]*P[3][2]-P[2][2]*(K[2][1]-1.0f); + V[2][3] = -K[2][0]*P[0][3]-K[2][1]*P[3][3]-P[2][3]*(K[2][1]-1.0f); + V[3][0] = -K[3][0]*P[0][0]-K[3][1]*P[2][0]-P[3][0]*(K[3][1]-1.0f); + V[3][1] = -K[3][0]*P[0][1]-K[3][1]*P[2][1]-P[3][2]*(K[3][1]-1.0f); + V[3][2] = -K[3][0]*P[0][2]-K[3][1]*P[2][2]-P[3][2]*(K[3][1]-1.0f); + V[3][3] = -K[3][0]*P[0][3]-K[3][1]*P[2][3]-P[3][3]*(K[3][1]-1.0f); + + + baro_updated = false; + } else { + K[0][0] = (V[0][2]+V[0][3]+dT*V[1][2]+dT*V[1][3])/(V[2][2]+V[2][3]+V[3][2]+V[3][3]+G[2]+G[3]+S[1]); + K[1][0] = (V[1][2]+V[1][3]+dT*V[2][2]+dT*V[2][3])/(V[2][2]+V[2][3]+V[3][2]+V[3][3]+G[2]+G[3]+S[1]); + K[2][0] = (V[2][2]+V[2][3]+G[2])/(V[2][2]+V[2][3]+V[3][2]+V[3][3]+G[2]+G[3]+S[1]); + K[3][0] = (V[3][2]+V[3][3]+G[3])/(V[2][2]+V[2][3]+V[3][2]+V[3][3]+G[2]+G[3]+S[1]); + + + z_new[0] = dT*z[1]-K[0][0]*(-x[1]+z[2]+z[3])+z[0]; + z_new[1] = dT*z[2]-K[1][0]*(-x[1]+z[2]+z[3])+z[1]; + z_new[2] = -K[2][0]*(-x[1]+z[2]+z[3])+z[2]; + z_new[3] = -K[3][0]*(-x[1]+z[2]+z[3])+z[3]; + + memcpy(z, z_new, sizeof(z_new)); + + V[0][0] = P[0][0]-K[0][0]*P[2][0]-K[0][0]*P[3][0]; + V[0][1] = P[0][1]-K[0][0]*P[2][1]-K[0][0]*P[3][2]; + V[0][2] = P[0][2]-K[0][0]*P[2][2]-K[0][0]*P[3][2]; + V[0][3] = P[0][3]-K[0][0]*P[2][3]-K[0][0]*P[3][3]; + V[1][0] = P[1][0]-K[1][0]*P[2][0]-K[1][0]*P[3][0]; + V[1][1] = P[1][1]-K[1][0]*P[2][1]-K[1][0]*P[3][2]; + V[1][2] = P[1][2]-K[1][0]*P[2][2]-K[1][0]*P[3][2]; + V[1][3] = P[1][3]-K[1][0]*P[2][3]-K[1][0]*P[3][3]; + V[2][0] = -K[2][0]*P[3][0]-P[2][0]*(K[2][0]-1.0f); + V[2][1] = -K[2][0]*P[3][2]-P[2][1]*(K[2][0]-1.0f); + V[2][2] = -K[2][0]*P[3][2]-P[2][2]*(K[2][0]-1.0f); + V[2][3] = -K[2][0]*P[3][3]-P[2][3]*(K[2][0]-1.0f); + V[3][0] = -K[3][0]*P[2][0]-P[3][0]*(K[3][0]-1.0f); + V[3][1] = -K[3][0]*P[2][1]-P[3][2]*(K[3][0]-1.0f); + V[3][2] = -K[3][0]*P[2][2]-P[3][2]*(K[3][0]-1.0f); + V[3][3] = -K[3][0]*P[2][3]-P[3][3]*(K[3][0]-1.0f); + } + + AltHoldSmoothedData altHold; + AltHoldSmoothedGet(&altHold); + altHold.Altitude = z[0]; + altHold.Velocity = z[1]; + altHold.Accel = z[2]; + AltHoldSmoothedSet(&altHold); + + AltHoldSmoothedGet(&altHold); + + // Verify that we are in altitude hold mode + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + if(flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) { + running = false; + } + + if (!running) + continue; + + // Compute the altitude error + error = (starting_altitude + altitudeHoldDesired.Altitude) - altHold.Altitude; + + // Compute integral off altitude error + throttleIntegral += error * altitudeHoldSettings.Ki * dT; + + // Only update stabilizationDesired less frequently + if((thisTime - lastUpdateTime) < 20) + continue; + + lastUpdateTime = thisTime; + + // Instead of explicit limit on integral you output limit feedback + StabilizationDesiredGet(&stabilizationDesired); + stabilizationDesired.Throttle = error * altitudeHoldSettings.Kp + throttleIntegral - + altHold.Velocity * altitudeHoldSettings.Kd - altHold.Accel * altitudeHoldSettings.Ka; + if(stabilizationDesired.Throttle > 1) { + throttleIntegral -= (stabilizationDesired.Throttle - 1); + stabilizationDesired.Throttle = 1; + } + else if (stabilizationDesired.Throttle < 0) { + throttleIntegral -= stabilizationDesired.Throttle; + stabilizationDesired.Throttle = 0; + } + + stabilizationDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabilizationDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabilizationDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK; + stabilizationDesired.Roll = altitudeHoldDesired.Roll; + stabilizationDesired.Pitch = altitudeHoldDesired.Pitch; + stabilizationDesired.Yaw = altitudeHoldDesired.Yaw; + StabilizationDesiredSet(&stabilizationDesired); + + } else if (ev.obj == AltitudeHoldDesiredHandle()) { + AltitudeHoldDesiredGet(&altitudeHoldDesired); + } + + } +} + +static void SettingsUpdatedCb(UAVObjEvent * ev) +{ + AltitudeHoldSettingsGet(&altitudeHoldSettings); +} diff --git a/flight/PipXtreme/inc/watchdog.h b/flight/Modules/AltitudeHold/inc/altitudehold.h similarity index 78% rename from flight/PipXtreme/inc/watchdog.h rename to flight/Modules/AltitudeHold/inc/altitudehold.h index ba3fba199..86ef46b2d 100644 --- a/flight/PipXtreme/inc/watchdog.h +++ b/flight/Modules/AltitudeHold/inc/altitudehold.h @@ -1,9 +1,10 @@ /** ****************************************************************************** * - * @file watchdog.h + * @file examplemodperiodic.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RF Module hardware layer + * @brief Example module to be used as a template for actual modules. + * * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -22,11 +23,9 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#ifndef EXAMPLEMODPERIODIC_H +#define EXAMPLEMODPERIODIC_H -#ifndef _WATCHDOG_H_ -#define _WATCHDOG_H_ - -uint16_t watchdog_Init(uint16_t delayMs); -void watchdog_Clear(void); - -#endif +int32_t ExampleModPeriodicInitialize(); +int32_t GuidanceInitialize(void); +#endif // EXAMPLEMODPERIODIC_H diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index fdfa4681c..02ba45744 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -50,19 +50,21 @@ #include "pios.h" #include "attitude.h" -#include "attituderaw.h" +#include "gyros.h" +#include "accels.h" #include "attitudeactual.h" #include "attitudesettings.h" #include "flightstatus.h" #include "manualcontrolcommand.h" #include "CoordinateConversions.h" -#include "pios_flash_w25x.h" - +#include + // Private constants #define STACK_SIZE_BYTES 540 #define TASK_PRIORITY (tskIDLE_PRIORITY+3) -#define UPDATE_RATE 2.0f +#define SENSOR_PERIOD 4 +#define UPDATE_RATE 25.0f #define GYRO_NEUTRAL 1665 #define PI_MOD(x) (fmod(x + M_PI, M_PI * 2) - M_PI) @@ -77,8 +79,9 @@ static void AttitudeTask(void *parameters); static float gyro_correct_int[3] = {0,0,0}; static xQueueHandle gyro_queue; -static int8_t updateSensors(AttitudeRawData *); -static void updateAttitude(AttitudeRawData *); +static int32_t updateSensors(AccelsData *, GyrosData *); +static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData); +static void updateAttitude(AccelsData *, GyrosData *); static void settingsUpdatedCb(UAVObjEvent * objEv); static float accelKi = 0; @@ -124,8 +127,9 @@ int32_t AttitudeStart(void) int32_t AttitudeInitialize(void) { AttitudeActualInitialize(); - AttitudeRawInitialize(); AttitudeSettingsInitialize(); + AccelsInitialize(); + GyrosInitialize(); // Initialize quaternion AttitudeActualData attitude; @@ -151,14 +155,6 @@ int32_t AttitudeInitialize(void) trim_requested = false; - // Create queue for passing gyro data, allow 2 back samples in case - gyro_queue = xQueueCreate(1, sizeof(float) * 4); - if(gyro_queue == NULL) - return -1; - - - PIOS_ADC_SetQueue(gyro_queue); - AttitudeSettingsConnectCallback(&settingsUpdatedCb); return 0; @@ -169,23 +165,42 @@ MODULE_INITCALL(AttitudeInitialize, AttitudeStart) /** * Module thread, should not return. */ + +int32_t accel_test; +int32_t gyro_test; static void AttitudeTask(void *parameters) { uint8_t init = 0; AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); - PIOS_ADC_Config((PIOS_ADC_RATE / 1000.0f) * UPDATE_RATE); - - // Keep flash CS pin high while talking accel - PIOS_FLASH_DISABLE; - PIOS_ADXL345_Init(); - // Set critical error and wait until the accel is producing data while(PIOS_ADXL345_FifoElements() == 0) { AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_CRITICAL); PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE); } + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + bool cc3d = bdinfo->board_rev == 0x02; + + if(cc3d) { +#if defined(PIOS_INCLUDE_MPU6000) + gyro_test = PIOS_MPU6000_Test(); +#endif + } else { +#if defined(PIOS_INCLUDE_ADXL345) + accel_test = PIOS_ADXL345_Test(); +#endif + +#if defined(PIOS_INCLUDE_ADC) + // Create queue for passing gyro data, allow 2 back samples in case + gyro_queue = xQueueCreate(1, sizeof(float) * 4); + PIOS_Assert(gyro_queue != NULL); + PIOS_ADC_SetQueue(gyro_queue); + PIOS_ADC_Config((PIOS_ADC_RATE / 1000.0f) * UPDATE_RATE); +#endif + + } // Force settings update to make sure rotation loaded settingsUpdatedCb(AttitudeSettingsHandle()); @@ -216,27 +231,37 @@ static void AttitudeTask(void *parameters) } PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE); - - AttitudeRawData attitudeRaw; - AttitudeRawGet(&attitudeRaw); - if(updateSensors(&attitudeRaw) != 0) + + AccelsData accels; + GyrosData gyros; + int32_t retval = 0; + + if (cc3d) + retval = updateSensorsCC3D(&accels, &gyros); + else + retval = updateSensors(&accels, &gyros); + + // Only update attitude when sensor data is good + if (retval != 0) AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR); else { - // Only update attitude when sensor data is good - updateAttitude(&attitudeRaw); - AttitudeRawSet(&attitudeRaw); + // Do not update attitude data in simulation mode + if (!AttitudeActualReadOnly()) + updateAttitude(&accels, &gyros); + AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); } - } } +float gyros_passed[3]; + /** * Get an update from the sensors * @param[in] attitudeRaw Populate the UAVO instead of saving right here * @return 0 if successfull, -1 if not */ -static int8_t updateSensors(AttitudeRawData * attitudeRaw) +static int32_t updateSensors(AccelsData * accels, GyrosData * gyros) { struct pios_adxl345_data accel_data; float gyro[4]; @@ -246,15 +271,19 @@ static int8_t updateSensors(AttitudeRawData * attitudeRaw) AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR); return -1; } - + + // Do not read raw sensor data in simulation mode + if (GyrosReadOnly() || AccelsReadOnly()) + return 0; + // No accel data available if(PIOS_ADXL345_FifoElements() == 0) return -1; // First sample is temperature - attitudeRaw->gyros[ATTITUDERAW_GYROS_X] = -(gyro[1] - GYRO_NEUTRAL) * gyroGain; - attitudeRaw->gyros[ATTITUDERAW_GYROS_Y] = (gyro[2] - GYRO_NEUTRAL) * gyroGain; - attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] = -(gyro[3] - GYRO_NEUTRAL) * gyroGain; + gyros->x = -(gyro[1] - GYRO_NEUTRAL) * gyroGain; + gyros->y = (gyro[2] - GYRO_NEUTRAL) * gyroGain; + gyros->z = -(gyro[3] - GYRO_NEUTRAL) * gyroGain; int32_t x = 0; int32_t y = 0; @@ -268,26 +297,25 @@ static int8_t updateSensors(AttitudeRawData * attitudeRaw) y += -accel_data.y; z += -accel_data.z; } while ( (i < 32) && (samples_remaining > 0) ); - attitudeRaw->gyrotemp[0] = samples_remaining; - attitudeRaw->gyrotemp[1] = i; - + gyros->temperature = samples_remaining; + float accel[3] = {(float) x / i, (float) y / i, (float) z / i}; if(rotate) { // TODO: rotate sensors too so stabilization is well behaved float vec_out[3]; rot_mult(R, accel, vec_out); - attitudeRaw->accels[0] = vec_out[0]; - attitudeRaw->accels[1] = vec_out[1]; - attitudeRaw->accels[2] = vec_out[2]; - rot_mult(R, attitudeRaw->gyros, vec_out); - attitudeRaw->gyros[0] = vec_out[0]; - attitudeRaw->gyros[1] = vec_out[1]; - attitudeRaw->gyros[2] = vec_out[2]; + accels->x = vec_out[0]; + accels->y = vec_out[1]; + accels->z = vec_out[2]; + rot_mult(R, &gyros->x, vec_out); + gyros->x = vec_out[0]; + gyros->y = vec_out[1]; + gyros->z = vec_out[2]; } else { - attitudeRaw->accels[0] = accel[0]; - attitudeRaw->accels[1] = accel[1]; - attitudeRaw->accels[2] = accel[2]; + accels->x = accel[0]; + accels->y = accel[1]; + accels->z = accel[2]; } if (trim_requested) { @@ -301,33 +329,100 @@ static int8_t updateSensors(AttitudeRawData * attitudeRaw) if ((armed == FLIGHTSTATUS_ARMED_ARMED) && (throttle > 0)) { trim_samples++; // Store the digitally scaled version since that is what we use for bias - trim_accels[0] += attitudeRaw->accels[ATTITUDERAW_ACCELS_X]; - trim_accels[1] += attitudeRaw->accels[ATTITUDERAW_ACCELS_Y]; - trim_accels[2] += attitudeRaw->accels[ATTITUDERAW_ACCELS_Z]; + trim_accels[0] += accels->x; + trim_accels[1] += accels->y; + trim_accels[2] += accels->z; } } } // Scale accels and correct bias - attitudeRaw->accels[ATTITUDERAW_ACCELS_X] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_X] - accelbias[0]) * ACCEL_SCALE; - attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] - accelbias[1]) * ACCEL_SCALE; - attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] - accelbias[2]) * ACCEL_SCALE; + accels->x = (accels->x - accelbias[0]) * ACCEL_SCALE; + accels->y = (accels->y - accelbias[1]) * ACCEL_SCALE; + accels->z = (accels->z - accelbias[2]) * ACCEL_SCALE; if(bias_correct_gyro) { // Applying integral component here so it can be seen on the gyros and correct bias - attitudeRaw->gyros[ATTITUDERAW_GYROS_X] += gyro_correct_int[0]; - attitudeRaw->gyros[ATTITUDERAW_GYROS_Y] += gyro_correct_int[1]; - attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] += gyro_correct_int[2]; + gyros->x += gyro_correct_int[0]; + gyros->y += gyro_correct_int[1]; + gyros->z += gyro_correct_int[2]; } // Because most crafts wont get enough information from gravity to zero yaw gyro, we try // and make it average zero (weakly) - gyro_correct_int[2] += - attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] * yawBiasRate; - + gyro_correct_int[2] += - gyros->z * yawBiasRate; + + GyrosSet(gyros); + AccelsSet(accels); + return 0; } -static void updateAttitude(AttitudeRawData * attitudeRaw) +/** + * Get an update from the sensors + * @param[in] attitudeRaw Populate the UAVO instead of saving right here + * @return 0 if successfull, -1 if not + */ +struct pios_mpu6000_data mpu6000_data; +static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData) +{ + float accels[3], gyros[3]; + +#if defined(PIOS_INCLUDE_MPU6000) + + xQueueHandle queue = PIOS_MPU6000_GetQueue(); + + if(xQueueReceive(queue, (void *) &mpu6000_data, SENSOR_PERIOD) == errQUEUE_EMPTY) + return -1; // Error, no data + + gyros[0] = -mpu6000_data.gyro_y * PIOS_MPU6000_GetScale(); + gyros[1] = -mpu6000_data.gyro_x * PIOS_MPU6000_GetScale(); + gyros[2] = -mpu6000_data.gyro_z * PIOS_MPU6000_GetScale(); + + accels[0] = -mpu6000_data.accel_y * PIOS_MPU6000_GetAccelScale(); + accels[1] = -mpu6000_data.accel_x * PIOS_MPU6000_GetAccelScale(); + accels[2] = -mpu6000_data.accel_z * PIOS_MPU6000_GetAccelScale(); + + gyrosData->temperature = 35.0f + ((float) mpu6000_data.temperature + 512.0f) / 340.0f; + accelsData->temperature = 35.0f + ((float) mpu6000_data.temperature + 512.0f) / 340.0f; +#endif + + if(rotate) { + // TODO: rotate sensors too so stabilization is well behaved + float vec_out[3]; + rot_mult(R, accels, vec_out); + accels[0] = vec_out[0]; + accels[1] = vec_out[1]; + accels[2] = vec_out[2]; + rot_mult(R, gyros, vec_out); + gyros[0] = vec_out[0]; + gyros[1] = vec_out[1]; + gyros[2] = vec_out[2]; + } + + accelsData->x = accels[0] - accelbias[0] * ACCEL_SCALE; // Applying arbitrary scale here to match CC v1 + accelsData->y = accels[1] - accelbias[1] * ACCEL_SCALE; + accelsData->z = accels[2] - accelbias[2] * ACCEL_SCALE; + AccelsSet(&accelsData); + + gyrosData->x = gyros[0]; + gyrosData->y = gyros[1]; + gyrosData->z = gyros[2]; + + if(bias_correct_gyro) { + // Applying integral component here so it can be seen on the gyros and correct bias + gyrosData->x += gyro_correct_int[0]; + gyrosData->y += gyro_correct_int[1]; + gyrosData->z += gyro_correct_int[2]; + } + + GyrosSet(gyrosData); + AccelsSet(accelsData); + + return 0; +} + +static void updateAttitude(AccelsData * accelsData, GyrosData * gyrosData) { float dT; portTickType thisSysTime = xTaskGetTickCount(); @@ -337,48 +432,46 @@ static void updateAttitude(AttitudeRawData * attitudeRaw) lastSysTime = thisSysTime; // Bad practice to assume structure order, but saves memory - float gyro[3]; - gyro[0] = attitudeRaw->gyros[0]; - gyro[1] = attitudeRaw->gyros[1]; - gyro[2] = attitudeRaw->gyros[2]; + float * gyros = &gyrosData->x; + float * accels = &accelsData->x; - { - float * accels = attitudeRaw->accels; - float grot[3]; - float accel_err[3]; - - // Rotate gravity to body frame and cross with accels - grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2])); - grot[1] = -(2 * (q[2] * q[3] + q[0] * q[1])); - grot[2] = -(q[0] * q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]); - CrossProduct((const float *) accels, (const float *) grot, accel_err); - - // Account for accel magnitude - float accel_mag = sqrt(accels[0]*accels[0] + accels[1]*accels[1] + accels[2]*accels[2]); - accel_err[0] /= accel_mag; - accel_err[1] /= accel_mag; - accel_err[2] /= accel_mag; - - // Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s - gyro_correct_int[0] += accel_err[0] * accelKi; - gyro_correct_int[1] += accel_err[1] * accelKi; - - //gyro_correct_int[2] += accel_err[2] * accelKi; - - // Correct rates based on error, integral component dealt with in updateSensors - gyro[0] += accel_err[0] * accelKp / dT; - gyro[1] += accel_err[1] * accelKp / dT; - gyro[2] += accel_err[2] * accelKp / dT; - } + float grot[3]; + float accel_err[3]; + + // Rotate gravity to body frame and cross with accels + grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2])); + grot[1] = -(2 * (q[2] * q[3] + q[0] * q[1])); + grot[2] = -(q[0] * q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]); + CrossProduct((const float *) accels, (const float *) grot, accel_err); + + // Account for accel magnitude + float accel_mag = sqrtf(accels[0]*accels[0] + accels[1]*accels[1] + accels[2]*accels[2]); + if(accel_mag < 1.0e-3f) + return; + + accel_err[0] /= accel_mag; + accel_err[1] /= accel_mag; + accel_err[2] /= accel_mag; + + // Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s + gyro_correct_int[0] += accel_err[0] * accelKi; + gyro_correct_int[1] += accel_err[1] * accelKi; + + //gyro_correct_int[2] += accel_err[2] * accelKi; + + // Correct rates based on error, integral component dealt with in updateSensors + gyros[0] += accel_err[0] * accelKp / dT; + gyros[1] += accel_err[1] * accelKp / dT; + gyros[2] += accel_err[2] * accelKp / dT; { // scoping variables to save memory // Work out time derivative from INSAlgo writeup // Also accounts for the fact that gyros are in deg/s float qdot[4]; - qdot[0] = (-q[1] * gyro[0] - q[2] * gyro[1] - q[3] * gyro[2]) * dT * M_PI / 180 / 2; - qdot[1] = (q[0] * gyro[0] - q[3] * gyro[1] + q[2] * gyro[2]) * dT * M_PI / 180 / 2; - qdot[2] = (q[3] * gyro[0] + q[0] * gyro[1] - q[1] * gyro[2]) * dT * M_PI / 180 / 2; - qdot[3] = (-q[2] * gyro[0] + q[1] * gyro[1] + q[0] * gyro[2]) * dT * M_PI / 180 / 2; + qdot[0] = (-q[1] * gyros[0] - q[2] * gyros[1] - q[3] * gyros[2]) * dT * M_PI / 180 / 2; + qdot[1] = (q[0] * gyros[0] - q[3] * gyros[1] + q[2] * gyros[2]) * dT * M_PI / 180 / 2; + qdot[2] = (q[3] * gyros[0] + q[0] * gyros[1] - q[1] * gyros[2]) * dT * M_PI / 180 / 2; + qdot[3] = (-q[2] * gyros[0] + q[1] * gyros[1] + q[0] * gyros[2]) * dT * M_PI / 180 / 2; // Take a time step q[0] = q[0] + qdot[0]; @@ -395,7 +488,7 @@ static void updateAttitude(AttitudeRawData * attitudeRaw) } // Renomalize - float qmag = sqrt(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]); + float qmag = sqrtf(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]); q[0] = q[0] / qmag; q[1] = q[1] / qmag; q[2] = q[2] / qmag; diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c new file mode 100644 index 000000000..6b3fb6be2 --- /dev/null +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -0,0 +1,629 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup Attitude Copter Control Attitude Estimation + * @brief Acquires sensor data and computes attitude estimate + * Specifically updates the the @ref AttitudeActual "AttitudeActual" and @ref AttitudeRaw "AttitudeRaw" settings objects + * @{ + * + * @file attitude.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Module to handle all comms to the AHRS on a periodic basis. + * + * @see The GNU Public License (GPL) Version 3 + * + ******************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/** + * Input objects: None, takes sensor data via pios + * Output objects: @ref AttitudeRaw @ref AttitudeActual + * + * This module computes an attitude estimate from the sensor data + * + * The module executes in its own thread. + * + * UAVObjects are automatically generated by the UAVObjectGenerator from + * the object definition XML file. + * + * Modules have no API, all communication to other modules is done through UAVObjects. + * However modules may use the API exposed by shared libraries. + * See the OpenPilot wiki for more details. + * http://www.openpilot.org/OpenPilot_Application_Architecture + * + */ + +#include "pios.h" +#include "attitude.h" +#include "magnetometer.h" +#include "accels.h" +#include "gyros.h" +#include "gyrosbias.h" +#include "attitudeactual.h" +#include "attitudesettings.h" +#include "positionactual.h" +#include "velocityactual.h" +#include "gpsposition.h" +#include "baroaltitude.h" +#include "flightstatus.h" +#include "homelocation.h" +#include "CoordinateConversions.h" + +// Private constants +#define STACK_SIZE_BYTES 5540 +#define TASK_PRIORITY (tskIDLE_PRIORITY+3) +#define FAILSAFE_TIMEOUT_MS 10 + +#define F_PI 3.14159265358979323846f +#define PI_MOD(x) (fmodf(x + F_PI, F_PI * 2) - F_PI) +// Private types + +// Private variables +static xTaskHandle attitudeTaskHandle; + +static xQueueHandle gyroQueue; +static xQueueHandle accelQueue; +static xQueueHandle magQueue; +static xQueueHandle baroQueue; +static xQueueHandle gpsQueue; +const uint32_t SENSOR_QUEUE_SIZE = 10; + +// Private functions +static void AttitudeTask(void *parameters); + +static int32_t updateAttitudeComplimentary(bool first_run); +static int32_t updateAttitudeINSGPS(bool first_run); +static void settingsUpdatedCb(UAVObjEvent * objEv); + +static float accelKi = 0; +static float accelKp = 0; +static float yawBiasRate = 0; +static float gyroGain = 0.42; +static int16_t accelbias[3]; +static float R[3][3]; +static int8_t rotate = 0; +static bool zero_during_arming = false; + + +/** + * API for sensor fusion algorithms: + * Configure(xQueueHandle gyro, xQueueHandle accel, xQueueHandle mag, xQueueHandle baro) + * Stores all the queues the algorithm will pull data from + * FinalizeSensors() -- before saving the sensors modifies them based on internal state (gyro bias) + * Update() -- queries queues and updates the attitude estiamte + */ + + +/** + * Initialise the module. Called before the start function + * \returns 0 on success or -1 if initialisation failed + */ +int32_t AttitudeInitialize(void) +{ + AttitudeActualInitialize(); + AttitudeSettingsInitialize(); + PositionActualInitialize(); + VelocityActualInitialize(); + + // Initialize this here while we aren't setting the homelocation in GPS + HomeLocationInitialize(); + + // Initialize quaternion + AttitudeActualData attitude; + AttitudeActualGet(&attitude); + attitude.q1 = 1; + attitude.q2 = 0; + attitude.q3 = 0; + attitude.q4 = 0; + AttitudeActualSet(&attitude); + + // Cannot trust the values to init right above if BL runs + GyrosBiasData gyrosBias; + GyrosBiasGet(&gyrosBias); + gyrosBias.x = 0; + gyrosBias.y = 0; + gyrosBias.z = 0; + GyrosBiasSet(&gyrosBias); + + for(uint8_t i = 0; i < 3; i++) + for(uint8_t j = 0; j < 3; j++) + R[i][j] = 0; + + AttitudeSettingsConnectCallback(&settingsUpdatedCb); + + return 0; +} + +/** + * Start the task. Expects all objects to be initialized by this point. + * \returns 0 on success or -1 if initialisation failed + */ +int32_t AttitudeStart(void) +{ + // Create the queues for the sensors + gyroQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + accelQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + magQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + baroQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + gpsQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + + // Start main task + xTaskCreate(AttitudeTask, (signed char *)"Attitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &attitudeTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_ATTITUDE, attitudeTaskHandle); + PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE); + + GyrosConnectQueue(gyroQueue); + AccelsConnectQueue(accelQueue); + MagnetometerConnectQueue(magQueue); + BaroAltitudeConnectQueue(baroQueue); + GPSPositionConnectQueue(gpsQueue); + + return 0; +} + +MODULE_INITCALL(AttitudeInitialize, AttitudeStart) + +/** + * Module thread, should not return. + */ +static void AttitudeTask(void *parameters) +{ + AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); + + // Force settings update to make sure rotation loaded + settingsUpdatedCb(AttitudeSettingsHandle()); + + bool first_run = true; + + // Wait for all the sensors be to read + vTaskDelay(100); + + // Main task loop + while (1) { + + // This function blocks on data queue + if(1) + updateAttitudeComplimentary(first_run); + else + updateAttitudeINSGPS(first_run); + + if (first_run) + first_run = false; + + PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE); + } +} + +float accel_mag; +float qmag; +float attitudeDt; +float mag_err[3]; +float magKi = 0.000001f; +float magKp = 0.0001f; + +static int32_t updateAttitudeComplimentary(bool first_run) +{ + UAVObjEvent ev; + GyrosData gyrosData; + AccelsData accelsData; + static int32_t timeval; + float dT; + static uint8_t init = 0; + + // Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe + if ( xQueueReceive(gyroQueue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE ) + { + AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE,SYSTEMALARMS_ALARM_WARNING); + return -1; + } + if ( xQueueReceive(accelQueue, &ev, 0) != pdTRUE ) + { + // When one of these is updated so should the other + AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE,SYSTEMALARMS_ALARM_WARNING); + return -1; + } + + // During initialization and + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + if(first_run) + init = 0; + + if((init == 0 && xTaskGetTickCount() < 7000) && (xTaskGetTickCount() > 1000)) { + // For first 7 seconds use accels to get gyro bias + accelKp = 1; + accelKi = 0.9; + yawBiasRate = 0.23; + } else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) { + accelKp = 1; + accelKi = 0.9; + yawBiasRate = 0.23; + init = 0; + } else if (init == 0) { + // Reload settings (all the rates) + AttitudeSettingsAccelKiGet(&accelKi); + AttitudeSettingsAccelKpGet(&accelKp); + AttitudeSettingsYawBiasRateGet(&yawBiasRate); + init = 1; + } + + GyrosGet(&gyrosData); + AccelsGet(&accelsData); + + // Compute the dT using the cpu clock + dT = PIOS_DELAY_DiffuS(timeval) / 1000000.0f; + timeval = PIOS_DELAY_GetRaw(); + + float q[4]; + + AttitudeActualData attitudeActual; + AttitudeActualGet(&attitudeActual); + + float grot[3]; + float accel_err[3]; + + // Get the current attitude estimate + quat_copy(&attitudeActual.q1, q); + + // Rotate gravity to body frame and cross with accels + grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2])); + grot[1] = -(2 * (q[2] * q[3] + q[0] * q[1])); + grot[2] = -(q[0] * q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]); + CrossProduct((const float *) &accelsData.x, (const float *) grot, accel_err); + + // Account for accel magnitude + accel_mag = accelsData.x*accelsData.x + accelsData.y*accelsData.y + accelsData.z*accelsData.z; + accel_mag = sqrtf(accel_mag); + accel_err[0] /= accel_mag; + accel_err[1] /= accel_mag; + accel_err[2] /= accel_mag; + + if ( xQueueReceive(magQueue, &ev, 0) != pdTRUE ) + { + // Rotate gravity to body frame and cross with accels + float brot[3]; + float Rbe[3][3]; + MagnetometerData mag; + HomeLocationData home; + + Quaternion2R(q, Rbe); + MagnetometerGet(&mag); + HomeLocationGet(&home); + rot_mult(Rbe, home.Be, brot); + + float mag_len = sqrtf(mag.x * mag.x + mag.y * mag.y + mag.z * mag.z); + mag.x /= mag_len; + mag.y /= mag_len; + mag.z /= mag_len; + + float bmag = sqrtf(brot[0] * brot[0] + brot[1] * brot[1] + brot[2] * brot[2]); + brot[0] /= bmag; + brot[1] /= bmag; + brot[2] /= bmag; + + // Only compute if neither vector is null + if (bmag < 1 || mag_len < 1) + mag_err[0] = mag_err[1] = mag_err[2] = 0; + else + CrossProduct((const float *) &mag.x, (const float *) brot, mag_err); + } else { + mag_err[0] = mag_err[1] = mag_err[2] = 0; + } + + // Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s + GyrosBiasData gyrosBias; + GyrosBiasGet(&gyrosBias); + gyrosBias.x += accel_err[0] * accelKi; + gyrosBias.y += accel_err[1] * accelKi; + gyrosBias.z += mag_err[2] * magKi; + GyrosBiasSet(&gyrosBias); + + // Correct rates based on error, integral component dealt with in updateSensors + gyrosData.x += accel_err[0] * accelKp / dT; + gyrosData.y += accel_err[1] * accelKp / dT; + gyrosData.z += accel_err[2] * accelKp / dT + mag_err[2] * magKp / dT; + + // Work out time derivative from INSAlgo writeup + // Also accounts for the fact that gyros are in deg/s + float qdot[4]; + qdot[0] = (-q[1] * gyrosData.x - q[2] * gyrosData.y - q[3] * gyrosData.z) * dT * F_PI / 180 / 2; + qdot[1] = (q[0] * gyrosData.x - q[3] * gyrosData.y + q[2] * gyrosData.z) * dT * F_PI / 180 / 2; + qdot[2] = (q[3] * gyrosData.x + q[0] * gyrosData.y - q[1] * gyrosData.z) * dT * F_PI / 180 / 2; + qdot[3] = (-q[2] * gyrosData.x + q[1] * gyrosData.y + q[0] * gyrosData.z) * dT * F_PI / 180 / 2; + + // Take a time step + q[0] = q[0] + qdot[0]; + q[1] = q[1] + qdot[1]; + q[2] = q[2] + qdot[2]; + q[3] = q[3] + qdot[3]; + + if(q[0] < 0) { + q[0] = -q[0]; + q[1] = -q[1]; + q[2] = -q[2]; + q[3] = -q[3]; + } + + // Renomalize + qmag = sqrtf(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]); + q[0] = q[0] / qmag; + q[1] = q[1] / qmag; + q[2] = q[2] / qmag; + q[3] = q[3] / qmag; + + // If quaternion has become inappropriately short or is nan reinit. + // THIS SHOULD NEVER ACTUALLY HAPPEN + if((fabs(qmag) < 1.0e-3f) || (qmag != qmag)) { + q[0] = 1; + q[1] = 0; + q[2] = 0; + q[3] = 0; + } + + quat_copy(q, &attitudeActual.q1); + + // Convert into eueler degrees (makes assumptions about RPY order) + Quaternion2RPY(&attitudeActual.q1,&attitudeActual.Roll); + + AttitudeActualSet(&attitudeActual); + + // Flush these queues for avoid errors + if ( xQueueReceive(baroQueue, &ev, 0) != pdTRUE ) + { + } + if ( xQueueReceive(gpsQueue, &ev, 0) != pdTRUE ) + { + } + + AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); + + return 0; +} + +#include "insgps.h" +int32_t ins_failed = 0; +extern struct NavStruct Nav; +static int32_t updateAttitudeINSGPS(bool first_run) +{ + UAVObjEvent ev; + GyrosData gyrosData; + AccelsData accelsData; + MagnetometerData magData; + BaroAltitudeData baroData; + + static uint32_t ins_last_time = 0; + + static bool inited; + if (first_run) + inited = false; + + // Wait until the gyro and accel object is updated, if a timeout then go to failsafe + if ( (xQueueReceive(gyroQueue, &ev, 10 / portTICK_RATE_MS) != pdTRUE) || + (xQueueReceive(accelQueue, &ev, 10 / portTICK_RATE_MS) != pdTRUE) ) + { + AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE,SYSTEMALARMS_ALARM_WARNING); + return -1; + } + + // Get most recent data + // TODO: Acquire all data in a queue + GyrosGet(&gyrosData); + AccelsGet(&accelsData); + MagnetometerGet(&magData); + BaroAltitudeGet(&baroData); + + bool mag_updated; + bool baro_updated; + bool gps_updated; + + if (inited) { + mag_updated = 0; + baro_updated = 0; + } + + mag_updated |= xQueueReceive(magQueue, &ev, 0 / portTICK_RATE_MS) == pdTRUE; + baro_updated |= xQueueReceive(baroQueue, &ev, 0 / portTICK_RATE_MS) == pdTRUE; + gps_updated |= xQueueReceive(gpsQueue, &ev, 0 / portTICK_RATE_MS) == pdTRUE; + + if (!inited && (!mag_updated || !baro_updated || !gps_updated)) { + // Don't initialize until all sensors are read + return -1; + } else if (!inited ) { + inited = true; + + float Rbe[3][3], q[4]; + float ge[3]={0.0f,0.0f,-9.81f}; + float zeros[3]={0.0f,0.0f,0.0f}; + float Pdiag[16]={25.0f,25.0f,25.0f,5.0f,5.0f,5.0f,1e-5f,1e-5f,1e-5f,1e-5f,1e-5f,1e-5f,1e-5f,1e-4f,1e-4f,1e-4f}; + float vel[3], NED[3]; + + INSGPSInit(); + + HomeLocationData home; + HomeLocationGet(&home); + + GPSPositionData gpsPosition; + GPSPositionGet(&gpsPosition); + + vel[0] = gpsPosition.Groundspeed * cosf(gpsPosition.Heading * F_PI / 180.0f); + vel[1] = gpsPosition.Groundspeed * sinf(gpsPosition.Heading * F_PI / 180.0f); + vel[2] = 0; + + // convert from cm back to meters + float LLA[3] = {(float) gpsPosition.Latitude / 1e7f, (float) gpsPosition.Longitude / 1e7f, (float) (gpsPosition.GeoidSeparation + gpsPosition.Altitude)}; + // put in local NED frame + float ECEF[3] = {(float) (home.ECEF[0] / 100.0f), (float) (home.ECEF[1] / 100.0f), (float) (home.ECEF[2] / 100.0f)}; + LLA2Base(LLA, ECEF, (float (*)[3]) home.RNE, NED); + + RotFrom2Vectors(&accelsData.x, ge, &magData.x, home.Be, Rbe); + R2Quaternion(Rbe,q); + INSSetState(NED, vel, q, &gyrosData.x, zeros); + INSSetGyroBias(&gyrosData.x); + INSResetP(Pdiag); + + ins_last_time = PIOS_DELAY_GetRaw(); + return 0; + } + + // Perform the update + uint16_t sensors = 0; + float dT; + + dT = PIOS_DELAY_DiffuS(ins_last_time) / 1.0e6f; + ins_last_time = PIOS_DELAY_GetRaw(); + + // This should only happen at start up or at mode switches + if(dT > 0.01f) + dT = 0.01f; + else if(dT <= 0.001f) + dT = 0.001f; + + + GyrosBiasData gyrosBias; + GyrosBiasGet(&gyrosBias); + + float gyros[3] = {(gyrosData.x + gyrosBias.x) * F_PI / 180.0f, + (gyrosData.y + gyrosBias.y) * F_PI / 180.0f, + (gyrosData.z + gyrosBias.z) * F_PI / 180.0f}; + + // Advance the state estimate + INSStatePrediction(gyros, &accelsData.x, dT); + + // Copy the attitude into the UAVO + AttitudeActualData attitude; + AttitudeActualGet(&attitude); + attitude.q1 = Nav.q[0]; + attitude.q2 = Nav.q[1]; + attitude.q3 = Nav.q[2]; + attitude.q4 = Nav.q[3]; + Quaternion2RPY(&attitude.q1,&attitude.Roll); + AttitudeActualSet(&attitude); + + // Copy the gyro bias into the UAVO + gyrosBias.x = Nav.gyro_bias[0]; + gyrosBias.y = Nav.gyro_bias[1]; + gyrosBias.z = Nav.gyro_bias[2]; + GyrosBiasSet(&gyrosBias); + + // Advance the covariance estimate + INSCovariancePrediction(dT); + + if(mag_updated) + sensors |= MAG_SENSORS; + if(baro_updated) + sensors |= BARO_SENSOR; + + float NED[3] = {0,0,0}; + float vel[3] = {0,0,0}; + + if(gps_updated) + { + sensors = HORIZ_SENSORS | VERT_SENSORS; + GPSPositionData gpsPosition; + GPSPositionGet(&gpsPosition); + + vel[0] = gpsPosition.Groundspeed * cosf(gpsPosition.Heading * F_PI / 180.0f); + vel[1] = gpsPosition.Groundspeed * sinf(gpsPosition.Heading * F_PI / 180.0f); + vel[2] = 0; + + HomeLocationData home; + HomeLocationGet(&home); + + // convert from cm back to meters + float LLA[3] = {(float) gpsPosition.Latitude / 1e7f, (float) gpsPosition.Longitude / 1e7f, (float) (gpsPosition.GeoidSeparation + gpsPosition.Altitude)}; + // put in local NED frame + float ECEF[3] = {(float) (home.ECEF[0] / 100.0f), (float) (home.ECEF[1] / 100.0f), (float) (home.ECEF[2] / 100.0f)}; + LLA2Base(LLA, ECEF, (float (*)[3]) home.RNE, NED); + } + + /* + * TODO: Need to add a general sanity check for all the inputs to make sure their kosher + * although probably should occur within INS itself + */ + INSCorrection(&magData.x, NED, vel, baroData.Altitude, sensors); + + // Copy the position and velocity into the UAVO + PositionActualData positionActual; + PositionActualGet(&positionActual); + positionActual.North = Nav.Pos[0]; + positionActual.East = Nav.Pos[1]; + positionActual.Down = Nav.Pos[2]; + PositionActualSet(&positionActual); + + VelocityActualData velocityActual; + VelocityActualGet(&velocityActual); + velocityActual.North = Nav.Vel[0]; + velocityActual.East = Nav.Vel[1]; + velocityActual.Down = Nav.Vel[2]; + VelocityActualSet(&velocityActual); + + + if(fabs(Nav.gyro_bias[0]) > 0.1f || fabs(Nav.gyro_bias[1]) > 0.1f || fabs(Nav.gyro_bias[2]) > 0.1f) { + float zeros[3] = {0.0f,0.0f,0.0f}; + INSSetGyroBias(zeros); + } + + return 0; +} + +static void settingsUpdatedCb(UAVObjEvent * objEv) +{ + AttitudeSettingsData attitudeSettings; + AttitudeSettingsGet(&attitudeSettings); + + + accelKp = attitudeSettings.AccelKp; + accelKi = attitudeSettings.AccelKi; + yawBiasRate = attitudeSettings.YawBiasRate; + gyroGain = attitudeSettings.GyroGain; + + zero_during_arming = attitudeSettings.ZeroDuringArming == ATTITUDESETTINGS_ZERODURINGARMING_TRUE; + + accelbias[0] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_X]; + accelbias[1] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Y]; + accelbias[2] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Z]; + + GyrosBiasData gyrosBias; + GyrosBiasGet(&gyrosBias); + gyrosBias.x = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_X] / 100.0f; + gyrosBias.y = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_Y] / 100.0f; + gyrosBias.z = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_Z] / 100.0f; + GyrosBiasSet(&gyrosBias); + + // Indicates not to expend cycles on rotation + if(attitudeSettings.BoardRotation[0] == 0 && attitudeSettings.BoardRotation[1] == 0 && + attitudeSettings.BoardRotation[2] == 0) { + rotate = 0; + + // Shouldn't be used but to be safe + float rotationQuat[4] = {1,0,0,0}; + Quaternion2R(rotationQuat, R); + } else { + float rotationQuat[4]; + const float rpy[3] = {attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_ROLL], + attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_PITCH], + attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_YAW]}; + RPY2Quaternion(rpy, rotationQuat); + Quaternion2R(rotationQuat, R); + rotate = 1; + } +} +/** + * @} + * @} + */ diff --git a/flight/OpenPilot/Tests/test_common.c b/flight/Modules/Attitude/revolution/inc/attitude.h similarity index 74% rename from flight/OpenPilot/Tests/test_common.c rename to flight/Modules/Attitude/revolution/inc/attitude.h index 6f5046a61..3f90e56a6 100644 --- a/flight/OpenPilot/Tests/test_common.c +++ b/flight/Modules/Attitude/revolution/inc/attitude.h @@ -1,37 +1,37 @@ -/** - ****************************************************************************** - * - * @file test_common.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sets up ans runs main OpenPilot tasks. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* OpenPilot Includes */ -#include "openpilot.h" - -/** - * Called by the RTOS when a stack overflow is detected. - */ -void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed portCHAR *pcTaskName ) -{ - PIOS_DEBUG_Panic("STACK OVERFLOW"); -} - - +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup Attitude Attitude Module + * @{ + * + * @file attitude.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Acquires sensor data and fuses it into attitude estimate for CC + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ATTITUDE_H +#define ATTITUDE_H + +#include "openpilot.h" + +int32_t AttitudeInitialize(void); + +#endif // ATTITUDE_H diff --git a/flight/Modules/FirmwareIAP/firmwareiap.c b/flight/Modules/FirmwareIAP/firmwareiap.c index aaf2622bd..0a88046b8 100644 --- a/flight/Modules/FirmwareIAP/firmwareiap.c +++ b/flight/Modules/FirmwareIAP/firmwareiap.c @@ -66,8 +66,6 @@ static portTickType lastResetSysTime; // Private functions static void FirmwareIAPCallback(UAVObjEvent* ev); -FirmwareIAPObjData data; - static uint32_t get_time(void); // Private types @@ -96,6 +94,9 @@ int32_t FirmwareIAPInitialize() const struct pios_board_info * bdinfo = &pios_board_info_blob; + FirmwareIAPObjData data; + FirmwareIAPObjGet(&data); + data.BoardType= bdinfo->board_type; PIOS_BL_HELPER_FLASH_Read_Description(data.Description,FIRMWAREIAPOBJ_DESCRIPTION_NUMELEM); PIOS_SYS_SerialNumberGetBinary(data.CPUSerial); @@ -125,6 +126,9 @@ static void FirmwareIAPCallback(UAVObjEvent* ev) if(iap_state == IAP_STATE_RESETTING) return; + + FirmwareIAPObjData data; + FirmwareIAPObjGet(&data); if ( ev->obj == FirmwareIAPObjHandle() ) { // Get the input object data @@ -238,7 +242,10 @@ static void resetTask(UAVObjEvent * ev) #if defined (PIOS_LED_ALARM) PIOS_LED_Toggle(PIOS_LED_ALARM); #endif /* PIOS_LED_ALARM */ - + + FirmwareIAPObjData data; + FirmwareIAPObjGet(&data); + if((portTickType) (xTaskGetTickCount() - lastResetSysTime) > RESET_DELAY / portTICK_RATE_MS) { lastResetSysTime = xTaskGetTickCount(); data.BoardType=0xFF; diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index 1f93d6dba..716e47aa3 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -144,7 +144,6 @@ int32_t GPSInitialize(void) #ifdef PIOS_GPS_SETS_HOMELOCATION HomeLocationInitialize(); #endif - HwSettingsInitialize(); updateSettings(); gps_rx_buffer = pvPortMalloc(NMEA_MAX_PACKET_LENGTH); diff --git a/flight/Modules/GPS/NMEA.c b/flight/Modules/GPS/NMEA.c index 4f78b27a4..59593b807 100644 --- a/flight/Modules/GPS/NMEA.c +++ b/flight/Modules/GPS/NMEA.c @@ -216,7 +216,7 @@ static float NMEA_real_to_float(char *nmea_real) } /* Convert to float */ - return (((float)whole) + fract * pow(10, -fract_units)); + return (((float)whole) + fract * powf(10.0f, -fract_units)); } /* @@ -239,37 +239,38 @@ static bool NMEA_latlon_to_fixed_point(int32_t * latlon, char *nmea_latlon, bool } /* scale up the mmmm[mm] field apropriately depending on # of digits */ + /* not using 1eN notation because that forces fixed point and lost precision */ switch (units) { case 0: /* no digits, value is zero so no scaling */ break; case 1: /* m */ - num_m *= 1e6; /* m000000 */ + num_m *= 1000000; /* m000000 */ break; case 2: /* mm */ - num_m *= 1e5; /* mm00000 */ + num_m *= 100000; /* mm00000 */ break; case 3: /* mmm */ - num_m *= 1e4; /* mmm0000 */ + num_m *= 10000; /* mmm0000 */ break; case 4: /* mmmm */ - num_m *= 1e3; /* mmmm000 */ + num_m *= 1000; /* mmmm000 */ break; case 5: /* mmmmm */ - num_m *= 1e2; /* mmmmm00 */ + num_m *= 100; /* mmmmm00 */ break; case 6: /* mmmmmm */ - num_m *= 1e1; /* mmmmmm0 */ + num_m *= 10; /* mmmmmm0 */ break; default: /* unhandled format */ - num_m = 0; + num_m = 0.0f; break; } - *latlon = (num_DDDMM / 100) * 1e7; /* scale the whole degrees */ - *latlon += (num_DDDMM % 100) * 1e7 / 60; /* add in the scaled decimal whole minutes */ - *latlon += num_m / 60; /* add in the scaled decimal fractional minutes */ + *latlon = (num_DDDMM / 100) * 10000000; /* scale the whole degrees */ + *latlon += (num_DDDMM % 100) * 10000000 / 60; /* add in the scaled decimal whole minutes */ + *latlon += num_m / 60; /* add in the scaled decimal fractional minutes */ if (negative) *latlon *= -1; diff --git a/flight/Modules/Guidance/guidance.c b/flight/Modules/Guidance/guidance.c index b90303928..519abeeb2 100644 --- a/flight/Modules/Guidance/guidance.c +++ b/flight/Modules/Guidance/guidance.c @@ -192,9 +192,9 @@ static void guidanceTask(void *parameters) NedAccelData accelData; NedAccelGet(&accelData); // Convert from m/s to cm/s - accelData.North = accel_ned[0] * 100; - accelData.East = accel_ned[1] * 100; - accelData.Down = accel_ned[2] * 100; + accelData.North = accel_ned[0]; + accelData.East = accel_ned[1]; + accelData.Down = accel_ned[2]; NedAccelSet(&accelData); diff --git a/flight/Modules/ManualControl/inc/manualcontrol.h b/flight/Modules/ManualControl/inc/manualcontrol.h index 1215ca27d..f71cdebde 100644 --- a/flight/Modules/ManualControl/inc/manualcontrol.h +++ b/flight/Modules/ManualControl/inc/manualcontrol.h @@ -39,6 +39,7 @@ typedef enum {FLIGHTMODE_UNDEFINED = 0, FLIGHTMODE_MANUAL = 1, FLIGHTMODE_STABIL (x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED1) ? FLIGHTMODE_STABILIZED : \ (x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED2) ? FLIGHTMODE_STABILIZED : \ (x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) ? FLIGHTMODE_STABILIZED : \ + (x == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) ? FLIGHTMODE_GUIDANCE : FLIGHTMODE_UNDEFINED \ ) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index a4cd90f4a..cc188e602 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -44,20 +44,23 @@ #include "flightstatus.h" #include "accessorydesired.h" #include "receiveractivity.h" +#include "altitudeholddesired.h" +#include "positionactual.h" +#include "baroaltitude.h" // Private constants #if defined(PIOS_MANUAL_STACK_SIZE) #define STACK_SIZE_BYTES PIOS_MANUAL_STACK_SIZE #else -#define STACK_SIZE_BYTES 824 +#define STACK_SIZE_BYTES 1024 #endif #define TASK_PRIORITY (tskIDLE_PRIORITY+4) #define UPDATE_PERIOD_MS 20 -#define THROTTLE_FAILSAFE -0.1 -#define FLIGHT_MODE_LIMIT 1.0/3.0 +#define THROTTLE_FAILSAFE -0.1f +#define FLIGHT_MODE_LIMIT 1.0f/3.0f #define ARMED_TIME_MS 1000 -#define ARMED_THRESHOLD 0.50 +#define ARMED_THRESHOLD 0.50f //safe band to allow a bit of calibration error or trim offset (in microseconds) #define CONNECTION_OFFSET 150 @@ -79,6 +82,7 @@ static portTickType lastSysTime; // Private functions static void updateActuatorDesired(ManualControlCommandData * cmd); static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualControlSettingsData * settings); +static void altitudeHoldDesired(ManualControlCommandData * cmd); static void processFlightMode(ManualControlSettingsData * settings, float flightMode); static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData * settings); static void setArmedIfChanged(uint8_t val); @@ -197,7 +201,7 @@ static void manualControlTask(void *parameters) /* trying to fly via GCS and lost connection. fall back to transmitter */ UAVObjMetadata metadata; ManualControlCommandGetMetadata(&metadata); - metadata.access = ACCESS_READWRITE; + UAVObjSetAccess(&metadata, ACCESS_READWRITE); ManualControlCommandSetMetadata(&metadata); } } @@ -383,7 +387,13 @@ static void manualControlTask(void *parameters) updateStabilizationDesired(&cmd, &settings); break; case FLIGHTMODE_GUIDANCE: - // TODO: Implement + switch(flightStatus.FlightMode) { + case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD: + altitudeHoldDesired(&cmd); + break; + default: + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); + } break; } } @@ -576,6 +586,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Roll * stabSettings.RollMax : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : + (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Roll : 0; // this is an invalid mode ; stabilization.Pitch = (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Pitch : @@ -583,6 +594,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Pitch * stabSettings.PitchMax : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : + (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Pitch : 0; // this is an invalid mode stabilization.Yaw = (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Yaw : @@ -590,12 +602,59 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Yaw * stabSettings.YawMax : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : + (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Yaw : 0; // this is an invalid mode stabilization.Throttle = (cmd->Throttle < 0) ? -1 : cmd->Throttle; StabilizationDesiredSet(&stabilization); } +#if defined(REVOLUTION) +// TODO: Need compile flag to exclude this from copter control +static void altitudeHoldDesired(ManualControlCommandData * cmd) +{ + const float DEADBAND_HIGH = 0.55; + const float DEADBAND_LOW = 0.45; + + static portTickType lastSysTime; + static bool zeroed = false; + portTickType thisSysTime; + float dT; + AltitudeHoldDesiredData altitudeHoldDesired; + AltitudeHoldDesiredGet(&altitudeHoldDesired); + + StabilizationSettingsData stabSettings; + StabilizationSettingsGet(&stabSettings); + + thisSysTime = xTaskGetTickCount(); + dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f; + lastSysTime = thisSysTime; + + altitudeHoldDesired.Roll = cmd->Roll * stabSettings.RollMax; + altitudeHoldDesired.Pitch = cmd->Pitch * stabSettings.PitchMax; + altitudeHoldDesired.Yaw = cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW]; + + float currentDown; + PositionActualDownGet(¤tDown); + if(dT > 1) { + // After not being in this mode for a while init at current height + altitudeHoldDesired.Altitude = 0; + zeroed = false; + } else if (cmd->Throttle > DEADBAND_HIGH && zeroed) + altitudeHoldDesired.Altitude += (cmd->Throttle - DEADBAND_HIGH) * dT; + else if (cmd->Throttle < DEADBAND_LOW && zeroed) + altitudeHoldDesired.Altitude += (cmd->Throttle - DEADBAND_LOW) * dT; + else if (cmd->Throttle >= DEADBAND_LOW && cmd->Throttle <= DEADBAND_HIGH) // Require the stick to enter the dead band before they can move height + zeroed = true; + + AltitudeHoldDesiredSet(&altitudeHoldDesired); +} +#else +static void altitudeHoldDesired(ManualControlCommandData * cmd) +{ + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); +} +#endif /** * Convert channel from servo pulse duration (microseconds) to scaled -1/+1 range. */ diff --git a/flight/Modules/Osd/OsdEtStd/OsdEtStd.c b/flight/Modules/Osd/OsdEtStd/OsdEtStd.c index 69c4c222d..edd148942 100644 --- a/flight/Modules/Osd/OsdEtStd/OsdEtStd.c +++ b/flight/Modules/Osd/OsdEtStd/OsdEtStd.c @@ -248,7 +248,7 @@ static bool Read(uint32_t start, uint8_t length, uint8_t * buffer) cmd[3] = (uint8_t) (start >> 8); cmd[4] = length; - return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); + return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)) == 0; } static bool Write(uint32_t start, uint8_t length, const uint8_t * buffer) diff --git a/flight/PipXtreme/inc/crc.h b/flight/Modules/OveroSync/inc/overosync.h similarity index 59% rename from flight/PipXtreme/inc/crc.h rename to flight/Modules/OveroSync/inc/overosync.h index bb27dd5ad..183c08ee9 100644 --- a/flight/PipXtreme/inc/crc.h +++ b/flight/Modules/OveroSync/inc/overosync.h @@ -1,9 +1,19 @@ /** ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup TelemetryModule Telemetry Module + * @brief Main telemetry module + * Starts three tasks (RX, TX, and priority TX) that watch event queues + * and handle all the telemetry of the UAVobjects + * @{ * - * @file crc.h + * @file telemetry.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Serial communication port handling routines + * @brief Include file of the telemetry module. + * As with all modules only the initialize function is exposed all other + * interactions with the module take place through the event queue and + * objects. * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -23,21 +33,14 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef _CRC_H_ -#define _CRC_H_ +#ifndef TELEMETRY_H +#define TELEMETRY_H -#include "stm32f10x.h" +int32_t TelemetryInitialize(void); -// ******************************************************************** +#endif // TELEMETRY_H -uint16_t updateCRC16(uint16_t crc, uint8_t b); -uint16_t updateCRC16Data(uint16_t crc, void *data, uint32_t len); - -uint32_t updateCRC32(uint32_t crc, uint8_t b); -uint32_t updateCRC32Data(uint32_t crc, void *data, uint32_t len); - -void CRC_init(void); - -// ******************************************************************** - -#endif +/** + * @} + * @} + */ diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c new file mode 100644 index 000000000..bafb58ffa --- /dev/null +++ b/flight/Modules/OveroSync/overosync.c @@ -0,0 +1,371 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup TelemetryModule Telemetry Module + * @brief Main telemetry module + * Starts three tasks (RX, TX, and priority TX) that watch event queues + * and handle all the telemetry of the UAVobjects + * @{ + * + * @file telemetry.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Telemetry module, handles telemetry and UAVObject updates + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "overosync.h" +#include "overosyncstats.h" +#include "systemstats.h" + +// Private constants +#define OVEROSYNC_PACKET_SIZE 1024 +#define MAX_QUEUE_SIZE 10 +#define STACK_SIZE_BYTES 4096 +#define TASK_PRIORITY (tskIDLE_PRIORITY + 0) + +// Private types + +// Private variables +static xQueueHandle queue; +static UAVTalkConnection uavTalkCon; +static xTaskHandle overoSyncTaskHandle; +volatile bool buffer_swap_failed; +volatile uint32_t buffer_swap_timeval; + +// Private functions +static void overoSyncTask(void *parameters); +static int32_t packData(uint8_t * data, int32_t length); +static int32_t transmitData(); +static void transmitDataDone(bool crc_ok, uint8_t crc_val); +static void registerObject(UAVObjHandle obj); + +// External variables +extern int32_t pios_spi_overo_id; + +struct dma_transaction { + uint8_t tx_buffer[OVEROSYNC_PACKET_SIZE] __attribute__ ((aligned(4))); + uint8_t rx_buffer[OVEROSYNC_PACKET_SIZE] __attribute__ ((aligned(4))); +}; + +struct overosync { + struct dma_transaction transactions[2]; + uint32_t active_transaction_id; + uint32_t loading_transaction_id; + xSemaphoreHandle transaction_lock; + xSemaphoreHandle buffer_lock; + volatile bool transaction_done; + uint32_t sent_bytes; + uint32_t write_pointer; + uint32_t sent_objects; + uint32_t failed_objects; + uint32_t received_objects; + uint32_t framesync_error; +}; + +struct overosync *overosync; + +static void PIOS_OVERO_IRQHandler(); + +static const struct pios_exti_cfg pios_exti_overo_cfg __exti_config = { + .vector = PIOS_OVERO_IRQHandler, + .line = EXTI_Line15, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI15_10_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line15, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +/** + * On the rising edge of NSS schedule a new transaction. This cannot be + * done by the DMA complete because there is 150 us between that and the + * Overo deasserting the CS line. We don't want to spin that long in an + * isr + */ +void PIOS_OVERO_IRQHandler() +{ + // transmitData must not block to get semaphore for when we get out of + // frame and transaction is still running here. -1 indicates the transaction + // semaphore is blocked and we are still in a transaction, thus a framesync + // error occurred. This shouldn't happen. Race condition? + if(transmitData() == -1) + overosync->framesync_error++; +} + +/** + * Initialise the telemetry module + * \return -1 if initialisation failed + * \return 0 on success + */ +int32_t OveroSyncInitialize(void) +{ + if(pios_spi_overo_id == 0) + return -1; + + OveroSyncStatsInitialize(); + + PIOS_EXTI_Init(&pios_exti_overo_cfg); + // Create object queues + queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); + + // Initialise UAVTalk + uavTalkCon = UAVTalkInitialize(&packData); + + return 0; +} + +/** + * Initialise the telemetry module + * \return -1 if initialisation failed + * \return 0 on success + */ +int32_t OveroSyncStart(void) +{ + if(pios_spi_overo_id == 0) + return -1; + + overosync = (struct overosync *) pvPortMalloc(sizeof(*overosync)); + if(overosync == NULL) + return -1; + + overosync->transaction_lock = xSemaphoreCreateMutex(); + if(overosync->transaction_lock == NULL) + return -1; + + overosync->buffer_lock = xSemaphoreCreateMutex(); + if(overosync->buffer_lock == NULL) + return -1; + + overosync->active_transaction_id = 0; + overosync->loading_transaction_id = 0; + overosync->write_pointer = 0; + overosync->sent_bytes = 0; + overosync->framesync_error = 0; + + // Process all registered objects and connect queue for updates + UAVObjIterate(®isterObject); + + // Start telemetry tasks + xTaskCreate(overoSyncTask, (signed char *)"OveroSync", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &overoSyncTaskHandle); + + TaskMonitorAdd(TASKINFO_RUNNING_OVEROSYNC, overoSyncTaskHandle); + + return 0; +} + +MODULE_INITCALL(OveroSyncInitialize, OveroSyncStart) + +/** + * Register a new object, adds object to local list and connects the queue depending on the object's + * telemetry settings. + * \param[in] obj Object to connect + */ +static void registerObject(UAVObjHandle obj) +{ + int32_t eventMask; + eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if (UAVObjIsMetaobject(obj)) { + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + } + UAVObjConnectQueue(obj, queue, eventMask); +} + +/** + * Telemetry transmit task, regular priority + * + * Logic: We need to double buffer the DMA transfers. Pack the buffer until either + * 1) it is full (and then we should record the number of missed events then) + * 2) the current transaction is done (we should immediately schedule since we are slave) + * when done packing the buffer we should call PIOS_SPI_TransferBlock, change the active buffer + * and then take the semaphrore + */ +static void overoSyncTask(void *parameters) +{ + UAVObjEvent ev; + + // Kick off SPI transfers (once one is completed another will automatically transmit) + overosync->transaction_done = true; + overosync->sent_objects = 0; + overosync->failed_objects = 0; + overosync->received_objects = 0; + + portTickType lastUpdateTime = xTaskGetTickCount(); + portTickType updateTime; + + // Loop forever + while (1) { + // Wait for queue message + if (xQueueReceive(queue, &ev, portMAX_DELAY) == pdTRUE) { + // Process event. This calls transmitData + UAVTalkSendObject(uavTalkCon, ev.obj, ev.instId, false, 0); + + updateTime = xTaskGetTickCount(); + if(((portTickType) (updateTime - lastUpdateTime)) > 1000) { + // Update stats. This will trigger a local send event too + OveroSyncStatsData syncStats; + syncStats.Send = overosync->sent_bytes; + syncStats.Received = 0; + syncStats.Connected = syncStats.Send > 500 ? OVEROSYNCSTATS_CONNECTED_TRUE : OVEROSYNCSTATS_CONNECTED_FALSE; + syncStats.DroppedUpdates = overosync->failed_objects; + OveroSyncStatsSet(&syncStats); + overosync->failed_objects = 0; + overosync->sent_bytes = 0; + lastUpdateTime = updateTime; + } + } + } +} + +static void transmitDataDone(bool crc_ok, uint8_t crc_val) +{ + uint8_t *rx_buffer; + static signed portBASE_TYPE xHigherPriorityTaskWoken; + + rx_buffer = overosync->transactions[overosync->active_transaction_id].rx_buffer; + + // Release the semaphore and start another transaction (which grabs semaphore again but then + // returns instantly). Because this is called by the DMA ISR we need to be aware of context + // switches. + xSemaphoreGiveFromISR(overosync->transaction_lock, &xHigherPriorityTaskWoken); + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); + + overosync->transaction_done = true; + + // Parse the data from overo + for (uint32_t i = 0; rx_buffer[0] != 0 && i < sizeof(rx_buffer) ; i++) + UAVTalkProcessInputStream(uavTalkCon, rx_buffer[i]); +} + +/** + * Transmit data buffer to the modem or USB port. + * \param[in] data Data buffer to send + * \param[in] length Length of buffer + * \return -1 on failure + * \return number of bytes transmitted on success + */ +uint32_t too_long = 0; +static int32_t packData(uint8_t * data, int32_t length) +{ + uint8_t *tx_buffer; + + portTickType tickTime = xTaskGetTickCount(); + + // Get the lock for manipulating the buffer + xSemaphoreTake(overosync->buffer_lock, portMAX_DELAY); + + // Check this packet will fit + if ((overosync->write_pointer + length + sizeof(tickTime)) > + sizeof(overosync->transactions[overosync->loading_transaction_id].tx_buffer)) { + overosync->failed_objects ++; + xSemaphoreGive(overosync->buffer_lock); + return -1; + } + + // Get offset into buffer and copy contents + tx_buffer = overosync->transactions[overosync->loading_transaction_id].tx_buffer + + overosync->write_pointer; + memcpy(tx_buffer, &tickTime, sizeof(tickTime)); + memcpy(tx_buffer + sizeof(tickTime),data,length); + overosync->write_pointer += length + sizeof(tickTime); + overosync->sent_bytes += length; + overosync->sent_objects++; + + xSemaphoreGive(overosync->buffer_lock); + + // When the NSS line rises while we are packing data then a transaction doesn't start + // because that means we will be here very shortly afterwards (priority of task making that + // not always perfectly true) schedule the transaction here. + if (buffer_swap_failed && (PIOS_DELAY_DiffuS(buffer_swap_timeval) < 50)) { + buffer_swap_failed = false; + transmitData(); + } else if (buffer_swap_failed) { + buffer_swap_failed = false; + too_long++; + } + + return length; +} + +static int32_t transmitData() +{ + uint8_t *tx_buffer, *rx_buffer; + static signed portBASE_TYPE xHigherPriorityTaskWoken; + + // Get this lock first so we don't swap buffers and then fail + // to start + if (xSemaphoreTake(overosync->transaction_lock, 0) == pdFALSE) + return -1; + + // Get lock to manipulate buffers + if(xSemaphoreTake(overosync->buffer_lock, 0) == pdFALSE) { + xSemaphoreGiveFromISR(overosync->transaction_lock, &xHigherPriorityTaskWoken); + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); + buffer_swap_failed = true; + buffer_swap_timeval = PIOS_DELAY_GetRaw(); + return -2; + } + + overosync->transaction_done = false; + + // Swap buffers + overosync->active_transaction_id = overosync->loading_transaction_id; + overosync->loading_transaction_id = (overosync->loading_transaction_id + 1) % + NELEMENTS(overosync->transactions); + + tx_buffer = overosync->transactions[overosync->active_transaction_id].tx_buffer; + rx_buffer = overosync->transactions[overosync->active_transaction_id].rx_buffer; + + // Prepare the new loading buffer + memset(overosync->transactions[overosync->loading_transaction_id].tx_buffer, 0xff, + sizeof(overosync->transactions[overosync->loading_transaction_id].tx_buffer)); + overosync->write_pointer = 0; + + xSemaphoreGiveFromISR(overosync->buffer_lock, &xHigherPriorityTaskWoken); + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); + + return PIOS_SPI_TransferBlock(pios_spi_overo_id, (uint8_t *) tx_buffer, (uint8_t *) rx_buffer, sizeof(overosync->transactions[overosync->active_transaction_id].tx_buffer), &transmitDataDone) == 0 ? 0 : -3; +} + +/** + * @} + * @} + */ diff --git a/flight/Modules/PipXtreme/inc/pipxtrememod.h b/flight/Modules/PipXtreme/inc/pipxtrememod.h new file mode 100644 index 000000000..01c8a3964 --- /dev/null +++ b/flight/Modules/PipXtreme/inc/pipxtrememod.h @@ -0,0 +1,35 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup PipXtremeModule PipXtreme Module + * @{ + * + * @file pipxtrememod.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief The PipXtreme system module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef PIPXTREMEMOD_H +#define PIPXTREMEMOD_H + +int32_t PipXtremeModInitialize(void); + +#endif // PIPXTREMEMOD_H diff --git a/flight/Modules/PipXtreme/pipxtrememod.c b/flight/Modules/PipXtreme/pipxtrememod.c new file mode 100644 index 000000000..5165e1781 --- /dev/null +++ b/flight/Modules/PipXtreme/pipxtrememod.c @@ -0,0 +1,201 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @brief The OpenPilot Modules do the majority of the control in OpenPilot. The + * @ref PipXtremeModule The PipXtreme Module is the equivalanet of the System + * Module for the PipXtreme modem. it starts all the other modules. + # This is done through the @ref PIOS "PIOS Hardware abstraction layer", + # which then contains hardware specific implementations + * (currently only STM32 supported) + * + * @{ + * @addtogroup PipXtremeModule PipXtreme Module + * @brief Initializes PIOS and other modules runs monitoring + * After initializing all the modules runs basic monitoring and + * alarms. + * @{ + * + * @file pipxtrememod.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief System module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include +#include +#include +#include "systemmod.h" + +// Private constants +#define SYSTEM_UPDATE_PERIOD_MS 1000 +#define LED_BLINK_RATE_HZ 5 + +#if defined(PIOS_SYSTEM_STACK_SIZE) +#define STACK_SIZE_BYTES PIOS_SYSTEM_STACK_SIZE +#else +#define STACK_SIZE_BYTES 924 +#endif + +#define TASK_PRIORITY (tskIDLE_PRIORITY+2) + +// Private types + +// Private variables +static uint32_t idleCounter; +static uint32_t idleCounterClear; +static xTaskHandle systemTaskHandle; +static bool stackOverflow; +static bool mallocFailed; + +// Private functions +static void systemTask(void *parameters); + +/** + * Create the module task. + * \returns 0 on success or -1 if initialization failed + */ +int32_t PipXtremeModStart(void) +{ + // Initialize vars + stackOverflow = false; + mallocFailed = false; + // Create pipxtreme system task + xTaskCreate(systemTask, (signed char *)"PipXtreme", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &systemTaskHandle); + // Register task + TaskMonitorAdd(TASKINFO_RUNNING_SYSTEM, systemTaskHandle); + + return 0; +} + +/** + * Initialize the module, called on startup. + * \returns 0 on success or -1 if initialization failed + */ +int32_t PipXtremeModInitialize(void) +{ + + // Must registers objects here for system thread because ObjectManager started in OpenPilotInit + + // Initialize out status object. + PipXStatusInitialize(); + PipXStatusData pipxStatus; + PipXStatusGet(&pipxStatus); + + // Get our hardware information. + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + pipxStatus.BoardType= bdinfo->board_type; + PIOS_BL_HELPER_FLASH_Read_Description(pipxStatus.Description, PIPXSTATUS_DESCRIPTION_NUMELEM); + PIOS_SYS_SerialNumberGetBinary(pipxStatus.CPUSerial); + pipxStatus.BoardRevision= bdinfo->board_rev; + + // Update the object + PipXStatusSet(&pipxStatus); + + // Call the module start function. + PipXtremeModStart(); + + return 0; +} + +MODULE_INITCALL(PipXtremeModInitialize, 0) + +/** + * System task, periodically executes every SYSTEM_UPDATE_PERIOD_MS + */ +static void systemTask(void *parameters) +{ + portTickType lastSysTime; + + /* create all modules thread */ + MODULE_TASKCREATE_ALL; + + if (mallocFailed) { + /* We failed to malloc during task creation, + * system behaviour is undefined. Reset and let + * the BootFault code recover for us. + */ + PIOS_SYS_Reset(); + } + + // Initialize vars + idleCounter = 0; + idleCounterClear = 0; + lastSysTime = xTaskGetTickCount(); + + // Main system loop + while (1) { + + // Flash the heartbeat LED +#if defined(PIOS_LED_HEARTBEAT) + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); +#endif /* PIOS_LED_HEARTBEAT */ + + // Wait until next period + vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS); + } +} + +/** + * Called by the RTOS when the CPU is idle, used to measure the CPU idle time. + */ +void vApplicationIdleHook(void) +{ + // Called when the scheduler has no tasks to run + if (idleCounterClear == 0) { + ++idleCounter; + } else { + idleCounter = 0; + idleCounterClear = 0; + } +} + +/** + * Called by the RTOS when a stack overflow is detected. + */ +#define DEBUG_STACK_OVERFLOW 0 +void vApplicationStackOverflowHook(xTaskHandle * pxTask, signed portCHAR * pcTaskName) +{ + stackOverflow = true; +#if DEBUG_STACK_OVERFLOW + static volatile bool wait_here = true; + while(wait_here); + wait_here = true; +#endif +} + +/** + * Called by the RTOS when a malloc call fails. + */ +#define DEBUG_MALLOC_FAILURES 0 +void vApplicationMallocFailedHook(void) +{ + mallocFailed = true; +#if DEBUG_MALLOC_FAILURES + static volatile bool wait_here = true; + while(wait_here); + wait_here = true; +#endif +} + +/** + * @} + * @} + */ diff --git a/flight/Modules/RadioComBridge/RadioComBridge.c b/flight/Modules/RadioComBridge/RadioComBridge.c new file mode 100644 index 000000000..ceb547fd1 --- /dev/null +++ b/flight/Modules/RadioComBridge/RadioComBridge.c @@ -0,0 +1,1083 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup RadioComBridgeModule Com Port to Radio Bridge Module + * @brief Bridge Com and Radio ports + * @{ + * + * @file RadioComBridge.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Bridges selected Com Port to the COM VCP emulated serial port + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +// **************** + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#if defined(PIOS_INCLUDE_FLASH_EEPROM) +#include +#endif + +#include + +// **************** +// Private constants + +#define TEMP_BUFFER_SIZE 25 +#define STACK_SIZE_BYTES 150 +#define TASK_PRIORITY (tskIDLE_PRIORITY + 1) +#define BRIDGE_BUF_LEN 512 +#define MAX_RETRIES 2 +#define RETRY_TIMEOUT_MS 20 +#define STATS_UPDATE_PERIOD_MS 500 +#define RADIOSTATS_UPDATE_PERIOD_MS 250 +#define MAX_LOST_CONTACT_TIME 4 +#define PACKET_QUEUE_SIZE 10 +#define MAX_PORT_DELAY 200 +#define EV_PACKET_RECEIVED 0x20 +#define EV_SEND_ACK 0x40 +#define EV_SEND_NACK 0x80 + +// **************** +// Private types + +typedef struct { + uint32_t pairID; + uint16_t retries; + uint16_t errors; + uint16_t uavtalk_errors; + uint16_t resets; + uint16_t dropped; + int8_t rssi; + uint8_t lastContact; +} PairStats; + +typedef struct { + // The task handles. + xTaskHandle comUAVTalkTaskHandle; + xTaskHandle radioReceiveTaskHandle; + xTaskHandle sendPacketTaskHandle; + xTaskHandle sendDataTaskHandle; + xTaskHandle radioStatusTaskHandle; + xTaskHandle transparentCommTaskHandle; + xTaskHandle ppmInputTaskHandle; + + // The UAVTalk connection on the com side. + UAVTalkConnection inUAVTalkCon; + UAVTalkConnection outUAVTalkCon; + + // Queue handles. + xQueueHandle sendPacketQueue; + xQueueHandle objEventQueue; + + // Error statistics. + uint32_t comTxErrors; + uint32_t comTxRetries; + uint32_t comRxErrors; + uint32_t radioTxErrors; + uint32_t radioTxRetries; + uint32_t radioRxErrors; + uint32_t UAVTalkErrors; + uint32_t packetErrors; + uint32_t droppedPackets; + uint16_t txBytes; + uint16_t rxBytes; + + // The destination ID + uint32_t destination_id; + + // The packet timeout. + portTickType send_timeout; + uint16_t min_packet_size; + + // Track other radios that are in range. + PairStats pairStats[PIPXSTATUS_PAIRIDS_NUMELEM]; + + // The RSSI of the last packet received. + int8_t RSSI; + +} RadioComBridgeData; + +typedef struct { + uint32_t com_port; + uint8_t *buffer; + uint16_t length; + uint16_t index; + uint16_t data_length; +} ReadBuffer, *BufferedReadHandle; + +// **************** +// Private functions + +static void comUAVTalkTask(void *parameters); +static void radioReceiveTask(void *parameters); +static void sendPacketTask(void *parameters); +static void sendDataTask(void *parameters); +static void transparentCommTask(void * parameters); +static void radioStatusTask(void *parameters); +static void ppmInputTask(void *parameters); +static int32_t transmitData(uint8_t * data, int32_t length); +static int32_t transmitPacket(PHPacketHandle packet); +static void receiveData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc); +static void StatusHandler(PHStatusPacketHandle p, int8_t rssi, int8_t afc); +static void PPMHandler(uint16_t *channels); +static BufferedReadHandle BufferedReadInit(uint32_t com_port, uint16_t buffer_length); +static bool BufferedRead(BufferedReadHandle h, uint8_t *value, uint32_t timeout_ms); +static void BufferedReadSetCom(BufferedReadHandle h, uint32_t com_port); +static void updateSettings(); + +// **************** +// Private variables + +static RadioComBridgeData *data; + +/** + * Start the module + * \return -1 if initialisation failed + * \return 0 on success + */ +static int32_t RadioComBridgeStart(void) +{ + if(data) { + // Start the tasks + xTaskCreate(comUAVTalkTask, (signed char *)"ComUAVTalk", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->comUAVTalkTaskHandle)); + if(PIOS_COM_TRANS_COM) + xTaskCreate(transparentCommTask, (signed char *)"transparentComm", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->transparentCommTaskHandle)); + xTaskCreate(radioReceiveTask, (signed char *)"RadioReceive", STACK_SIZE_BYTES, NULL, TASK_PRIORITY+ 2, &(data->radioReceiveTaskHandle)); + xTaskCreate(sendPacketTask, (signed char *)"SendPacketTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->sendPacketTaskHandle)); + xTaskCreate(sendDataTask, (signed char *)"SendDataTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY+ 2, &(data->sendDataTaskHandle)); + xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle)); + if(PIOS_PPM_RECEIVER) + xTaskCreate(ppmInputTask, (signed char *)"PPMInputTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->ppmInputTaskHandle)); +#ifdef PIOS_INCLUDE_WDG + PIOS_WDG_RegisterFlag(PIOS_WDG_COMUAVTALK); + if(PIOS_COM_TRANS_COM) + PIOS_WDG_RegisterFlag(PIOS_WDG_TRANSCOMM); + PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORECEIVE); + //PIOS_WDG_RegisterFlag(PIOS_WDG_SENDPACKET); + //PIOS_WDG_RegisterFlag(PIOS_WDG_SENDDATA); + if(PIOS_PPM_RECEIVER) + PIOS_WDG_RegisterFlag(PIOS_WDG_PPMINPUT); +#endif + return 0; + } + + return -1; +} + +/** + * Initialise the module + * \return -1 if initialisation failed + * \return 0 on success + */ +static int32_t RadioComBridgeInitialize(void) +{ + + // allocate and initialize the static data storage only if module is enabled + data = (RadioComBridgeData *)pvPortMalloc(sizeof(RadioComBridgeData)); + if (!data) + return -1; + + // Initialize the UAVObjects that we use + GCSReceiverInitialize(); + PipXStatusInitialize(); + ObjectPersistenceInitialize(); + updateSettings(); + + // Initialise UAVTalk + data->inUAVTalkCon = UAVTalkInitialize(0); + data->outUAVTalkCon = UAVTalkInitialize(&transmitData); + + // Initialize the queues. + data->sendPacketQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(PHPacketHandle)); + data->objEventQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(UAVObjEvent)); + + // Initialize the statistics. + data->radioTxErrors = 0; + data->radioTxRetries = 0; + data->radioRxErrors = 0; + data->comTxErrors = 0; + data->comTxRetries = 0; + data->comRxErrors = 0; + data->UAVTalkErrors = 0; + data->packetErrors = 0; + data->RSSI = -127; + + // Register the callbacks with the packet handler + PHRegisterOutputStream(pios_packet_handler, transmitPacket); + PHRegisterDataHandler(pios_packet_handler, receiveData); + PHRegisterStatusHandler(pios_packet_handler, StatusHandler); + PHRegisterPPMHandler(pios_packet_handler, PPMHandler); + + // Initialize the packet send timeout + data->send_timeout = 25; // ms + data->min_packet_size = 50; + + // Initialize the detected device statistics. + for (uint8_t i = 0; i < PIPXSTATUS_PAIRIDS_NUMELEM; ++i) + { + data->pairStats[i].pairID = 0; + data->pairStats[i].rssi = -127; + data->pairStats[i].retries = 0; + data->pairStats[i].errors = 0; + data->pairStats[i].uavtalk_errors = 0; + data->pairStats[i].resets = 0; + data->pairStats[i].dropped = 0; + data->pairStats[i].lastContact = 0; + } + // The first slot is reserved for our current pairID + PipXSettingsPairIDGet(&(data->pairStats[0].pairID)); + + // Configure our UAVObjects for updates. + UAVObjConnectQueue(UAVObjGetByName("PipXStatus"), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ); + UAVObjConnectQueue(UAVObjGetByName("GCSReceiver"), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ); + UAVObjConnectQueue(UAVObjGetByName("ObjectPersistence"), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL); + + return 0; +} +MODULE_INITCALL(RadioComBridgeInitialize, RadioComBridgeStart) + +/** + * Reads UAVTalk messages froma com port and creates packets out of them. + */ +static void comUAVTalkTask(void *parameters) +{ + PHPacketHandle p = NULL; + + // Create the buffered reader. + BufferedReadHandle f = BufferedReadInit(PIOS_COM_UAVTALK, TEMP_BUFFER_SIZE); + + while (1) { + +#ifdef PIOS_INCLUDE_WDG + // Update the watchdog timer. + PIOS_WDG_UpdateFlag(PIOS_WDG_COMUAVTALK); +#endif /* PIOS_INCLUDE_WDG */ + + // Receive from USB HID if available, otherwise UAVTalk com if it's available. +#if defined(PIOS_INCLUDE_USB) + // Determine input port (USB takes priority over telemetry port) + if (PIOS_USB_CheckAvailable(0)) + BufferedReadSetCom(f, PIOS_COM_USB_HID); + else +#endif /* PIOS_INCLUDE_USB */ + { + if (PIOS_COM_UAVTALK) + BufferedReadSetCom(f, PIOS_COM_UAVTALK); + else + { + vTaskDelay(5); + continue; + } + } + + // Read the next byte + uint8_t rx_byte; + if(!BufferedRead(f, &rx_byte, MAX_PORT_DELAY)) + continue; + + // Get a TX packet from the packet handler if required. + if (p == NULL) + { + + // Wait until we receive a sync. + UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(data->inUAVTalkCon, rx_byte); + if (state != UAVTALK_STATE_TYPE) + continue; + + // Get a packet when we see the sync + p = PHGetTXPacket(pios_packet_handler); + + // No packets available? + if (p == NULL) + { + data->droppedPackets++; + continue; + } + + // Initialize the packet. + p->header.destination_id = data->destination_id; + p->header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id); + //p->header.type = PACKET_TYPE_ACKED_DATA; + p->header.type = PACKET_TYPE_DATA; + p->data[0] = rx_byte; + p->header.data_size = 1; + continue; + } + + // Insert this byte. + p->data[p->header.data_size++] = rx_byte; + + // Keep reading until we receive a completed packet. + UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(data->inUAVTalkCon, rx_byte); + UAVTalkConnectionData *connection = (UAVTalkConnectionData*)(data->inUAVTalkCon); + UAVTalkInputProcessor *iproc = &(connection->iproc); + + if (state == UAVTALK_STATE_COMPLETE) + { + // Is this a local UAVObject? + // We only generate GcsReceiver ojects, we don't consume them. + if ((iproc->obj != NULL) && (iproc->objId != GCSRECEIVER_OBJID)) + { + // We treat the ObjectPersistence object differently + if(iproc->objId == OBJECTPERSISTENCE_OBJID) + { + // Unpack object, if the instance does not exist it will be created! + UAVObjUnpack(iproc->obj, iproc->instId, connection->rxBuffer); + + // Get the ObjectPersistence object. + ObjectPersistenceData obj_per; + ObjectPersistenceGet(&obj_per); + + // Is this concerning or setting object? + if (obj_per.ObjectID == PIPXSETTINGS_OBJID) + { + // Queue up the ACK. + UAVObjEvent ev; + ev.obj = iproc->obj; + ev.instId = iproc->instId; + ev.event = EV_SEND_ACK; + xQueueSend(data->objEventQueue, &ev, MAX_PORT_DELAY); + + // Is this a save, load, or delete? + bool success = true; + switch (obj_per.Operation) + { + case OBJECTPERSISTENCE_OPERATION_LOAD: + { +#if defined(PIOS_INCLUDE_FLASH_EEPROM) + // Load the settings. + PipXSettingsData pipxSettings; + if (PIOS_EEPROM_Load((uint8_t*)&pipxSettings, sizeof(PipXSettingsData)) == 0) + PipXSettingsSet(&pipxSettings); + else + success = false; +#endif + break; + } + case OBJECTPERSISTENCE_OPERATION_SAVE: + { +#if defined(PIOS_INCLUDE_FLASH_EEPROM) + // Save the settings. + PipXSettingsData pipxSettings; + PipXSettingsGet(&pipxSettings); + int32_t ret = PIOS_EEPROM_Save((uint8_t*)&pipxSettings, sizeof(PipXSettingsData)); + if (ret != 0) + success = false; +#endif + break; + } + default: + break; + } + if (success == true) + { + obj_per.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED; + ObjectPersistenceSet(&obj_per); + } + + // Release the packet, since we don't need it. + PHReleaseTXPacket(pios_packet_handler, p); + } + else + { + // Otherwise, queue the packet for transmission. + xQueueSend(data->sendPacketQueue, &p, MAX_PORT_DELAY); + } + } + else + { + UAVObjEvent ev; + ev.obj = iproc->obj; + ev.instId = 0; + switch (iproc->type) + { + case UAVTALK_TYPE_OBJ: + // Unpack object, if the instance does not exist it will be created! + UAVObjUnpack(iproc->obj, iproc->instId, connection->rxBuffer); + break; + case UAVTALK_TYPE_OBJ_REQ: + // Queue up an object send request. + ev.event = EV_UPDATE_REQ; + xQueueSend(data->objEventQueue, &ev, MAX_PORT_DELAY); + break; + case UAVTALK_TYPE_OBJ_ACK: + if (UAVObjUnpack(iproc->obj, iproc->instId, connection->rxBuffer) == 0) + { + // Queue up an ACK + ev.event = EV_SEND_ACK; + xQueueSend(data->objEventQueue, &ev, MAX_PORT_DELAY); + } + break; + } + + // Release the packet, since we don't need it. + PHReleaseTXPacket(pios_packet_handler, p); + } + } + else + { + // Queue the packet for transmission. + xQueueSend(data->sendPacketQueue, &p, MAX_PORT_DELAY); + } + p = NULL; + + } else if(state == UAVTALK_STATE_ERROR) { + DEBUG_PRINTF(1, "UAVTalk FAILED!\n\r"); + data->UAVTalkErrors++; + + // Send a NACK if required. + if((iproc->obj) && (iproc->type == UAVTALK_TYPE_OBJ_ACK)) + { + // Queue up a NACK + UAVObjEvent ev; + ev.obj = iproc->obj; + ev.event = EV_SEND_NACK; + xQueueSend(data->objEventQueue, &ev, MAX_PORT_DELAY); + + // Release the packet and start over again. + PHReleaseTXPacket(pios_packet_handler, p); + } + else + { + // Transmit the packet anyway... + xQueueSend(data->sendPacketQueue, &p, MAX_PORT_DELAY); + } + p = NULL; + } + } +} + +/** + * The radio to com bridge task. + */ +static void radioReceiveTask(void *parameters) +{ + PHPacketHandle p = NULL; + + /* Handle radio -> usart/usb direction */ + while (1) { + uint32_t rx_bytes; + +#ifdef PIOS_INCLUDE_WDG + // Update the watchdog timer. + PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORECEIVE); +#endif /* PIOS_INCLUDE_WDG */ + + // Get a RX packet from the packet handler if required. + if (p == NULL) + p = PHGetRXPacket(pios_packet_handler); + + if(p == NULL) { + DEBUG_PRINTF(2, "RX Packet Unavailable.!\n\r"); + // Wait a bit for a packet to come available. + vTaskDelay(5); + continue; + } + + // Receive data from the radio port + rx_bytes = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, (uint8_t*)p, PIOS_PH_MAX_PACKET, MAX_PORT_DELAY); + if(rx_bytes == 0) + continue; + data->rxBytes += rx_bytes; + + // Verify that the packet is valid and pass it on. + if(PHVerifyPacket(pios_packet_handler, p, rx_bytes) > 0) { + UAVObjEvent ev; + ev.obj = (UAVObjHandle)p; + ev.event = EV_PACKET_RECEIVED; + xQueueSend(data->objEventQueue, &ev, portMAX_DELAY); + } else + { + data->packetErrors++; + PHReceivePacket(pios_packet_handler, p, true); + } + p = NULL; + } +} + +/** + * Send packets to the radio. + */ +static void sendPacketTask(void *parameters) +{ + PHPacketHandle p; + + // Loop forever + while (1) { +#ifdef PIOS_INCLUDE_WDG + // Update the watchdog timer. + //PIOS_WDG_UpdateFlag(PIOS_WDG_SENDPACKET); +#endif /* PIOS_INCLUDE_WDG */ + // Wait for a packet on the queue. + if (xQueueReceive(data->sendPacketQueue, &p, MAX_PORT_DELAY) == pdTRUE) { + // Send the packet. + if(!PHTransmitPacket(pios_packet_handler, p)) + PHReleaseTXPacket(pios_packet_handler, p); + } + } +} + +/** + * Send packets to the radio. + */ +static void sendDataTask(void *parameters) +{ + UAVObjEvent ev; + + // Loop forever + while (1) { +#ifdef PIOS_INCLUDE_WDG + // Update the watchdog timer. + // NOTE: this is temporarily turned off becase PIOS_Com_SendBuffer appears to block for an uncontrollable time, + // and SendBufferNonBlocking doesn't seem to be working in this case. + //PIOS_WDG_UpdateFlag(PIOS_WDG_SENDDATA); +#endif /* PIOS_INCLUDE_WDG */ + // Wait for a packet on the queue. + if (xQueueReceive(data->objEventQueue, &ev, MAX_PORT_DELAY) == pdTRUE) { + if ((ev.event == EV_UPDATED) || (ev.event == EV_UPDATE_REQ)) + { + // Send update (with retries) + uint32_t retries = 0; + int32_t success = -1; + while (retries < MAX_RETRIES && success == -1) { + success = UAVTalkSendObject(data->outUAVTalkCon, ev.obj, 0, 0, RETRY_TIMEOUT_MS); + ++retries; + } + data->comTxRetries += retries; + } + else if(ev.event == EV_SEND_ACK) + { + // Send the ACK + uint32_t retries = 0; + int32_t success = -1; + while (retries < MAX_RETRIES && success == -1) { + success = UAVTalkSendAck(data->outUAVTalkCon, ev.obj, ev.instId); + ++retries; + } + data->comTxRetries += retries; + } + else if(ev.event == EV_SEND_NACK) + { + // Send the NACK + uint32_t retries = 0; + int32_t success = -1; + while (retries < MAX_RETRIES && success == -1) { + success = UAVTalkSendNack(data->outUAVTalkCon, UAVObjGetID(ev.obj)); + ++retries; + } + data->comTxRetries += retries; + } + else if(ev.event == EV_PACKET_RECEIVED) + { + // Receive the packet. + PHReceivePacket(pios_packet_handler, (PHPacketHandle)ev.obj, false); + } + } + } +} + +/** + * The com to radio bridge task. + */ +static void transparentCommTask(void * parameters) +{ + portTickType packet_start_time = 0; + uint32_t timeout = MAX_PORT_DELAY; + PHPacketHandle p = NULL; + + /* Handle usart/usb -> radio direction */ + while (1) { + +#ifdef PIOS_INCLUDE_WDG + // Update the watchdog timer. + PIOS_WDG_UpdateFlag(PIOS_WDG_TRANSCOMM); +#endif /* PIOS_INCLUDE_WDG */ + + // Get a TX packet from the packet handler if required. + if (p == NULL) + { + p = PHGetTXPacket(pios_packet_handler); + + // No packets available? + if (p == NULL) + { + data->droppedPackets++; + // Wait a bit for a packet to come available. + vTaskDelay(5); + continue; + } + + // Initialize the packet. + p->header.destination_id = data->destination_id; + p->header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id); + //p->header.type = PACKET_TYPE_ACKED_DATA; + p->header.type = PACKET_TYPE_DATA; + p->header.data_size = 0; + } + + // Receive data from the com port + uint32_t cur_rx_bytes = PIOS_COM_ReceiveBuffer(PIOS_COM_TRANS_COM, p->data + p->header.data_size, + PH_MAX_DATA - p->header.data_size, timeout); + + // Do we have an data to send? + p->header.data_size += cur_rx_bytes; + if (p->header.data_size > 0) { + + // Check how long since last update + portTickType cur_sys_time = xTaskGetTickCount(); + + // Is this the start of a packet? + if(packet_start_time == 0) + packet_start_time = cur_sys_time; + + // Just send the packet on wraparound + bool send_packet = (cur_sys_time < packet_start_time); + if (!send_packet) + { + portTickType dT = (cur_sys_time - packet_start_time) / portTICK_RATE_MS; + if (dT > data->send_timeout) + send_packet = true; + else + timeout = data->send_timeout - dT; + } + + // Also send the packet if the size is over the minimum. + send_packet |= (p->header.data_size > data->min_packet_size); + + // Should we send this packet? + if (send_packet) + { + // Queue the packet for transmission. + xQueueSend(data->sendPacketQueue, &p, MAX_PORT_DELAY); + + // Reset the timeout + timeout = MAX_PORT_DELAY; + p = NULL; + packet_start_time = 0; + } + } + } +} + +/** + * The stats update task. + */ +static void radioStatusTask(void *parameters) +{ + PHStatusPacket status_packet; + + while (1) { + PipXStatusData pipxStatus; + uint32_t pairID; + + // Get object data + PipXStatusGet(&pipxStatus); + PipXSettingsPairIDGet(&pairID); + + // Update the status + pipxStatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); + pipxStatus.Retries = data->comTxRetries; + pipxStatus.Errors = data->packetErrors; + pipxStatus.UAVTalkErrors = data->UAVTalkErrors; + pipxStatus.Dropped = data->droppedPackets; + pipxStatus.Resets = PIOS_RFM22B_Resets(pios_rfm22b_id); + pipxStatus.TXRate = (uint16_t)((float)(data->txBytes * 1000) / STATS_UPDATE_PERIOD_MS); + data->txBytes = 0; + pipxStatus.RXRate = (uint16_t)((float)(data->rxBytes * 1000) / STATS_UPDATE_PERIOD_MS); + data->rxBytes = 0; + pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_DISCONNECTED; + pipxStatus.RSSI = data->RSSI; + LINK_LED_OFF; + + // Update the potential pairing contacts + for (uint8_t i = 0; i < PIPXSTATUS_PAIRIDS_NUMELEM; ++i) + { + pipxStatus.PairIDs[i] = data->pairStats[i].pairID; + pipxStatus.PairSignalStrengths[i] = data->pairStats[i].rssi; + data->pairStats[i].lastContact++; + // Remove this device if it's stale. + if(data->pairStats[i].lastContact > MAX_LOST_CONTACT_TIME) + { + data->pairStats[i].pairID = 0; + data->pairStats[i].rssi = -127; + data->pairStats[i].retries = 0; + data->pairStats[i].errors = 0; + data->pairStats[i].uavtalk_errors = 0; + data->pairStats[i].resets = 0; + data->pairStats[i].dropped = 0; + data->pairStats[i].lastContact = 0; + } + // Add the paired devices statistics to ours. + if(pairID && (data->pairStats[i].pairID == pairID) && (data->pairStats[i].rssi > -127)) + { + pipxStatus.Retries += data->pairStats[i].retries; + pipxStatus.Errors += data->pairStats[i].errors; + pipxStatus.UAVTalkErrors += data->pairStats[i].uavtalk_errors; + pipxStatus.Dropped += data->pairStats[i].dropped; + pipxStatus.Resets += data->pairStats[i].resets; + pipxStatus.Dropped += data->pairStats[i].dropped; + pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_CONNECTED; + LINK_LED_ON; + } + } + + // Update the object + PipXStatusSet(&pipxStatus); + + // Broadcast the status. + { + static uint16_t cntr = 0; + if(cntr++ == RADIOSTATS_UPDATE_PERIOD_MS / STATS_UPDATE_PERIOD_MS) + { + // Queue the status message + status_packet.header.destination_id = 0xffffffff; + status_packet.header.type = PACKET_TYPE_STATUS; + status_packet.header.data_size = PH_STATUS_DATA_SIZE(&status_packet); + status_packet.header.source_id = pipxStatus.DeviceID; + status_packet.retries = data->comTxRetries; + status_packet.errors = data->packetErrors; + status_packet.uavtalk_errors = data->UAVTalkErrors; + status_packet.dropped = data->droppedPackets; + status_packet.resets = PIOS_RFM22B_Resets(pios_rfm22b_id); + PHPacketHandle sph = (PHPacketHandle)&status_packet; + xQueueSend(data->sendPacketQueue, &sph, MAX_PORT_DELAY); + cntr = 0; + } + } + + // Delay until the next update period. + vTaskDelay(STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS); + } +} + +/** + * The PPM input task. + */ +static void ppmInputTask(void *parameters) +{ + PHPpmPacket ppm_packet; + PHPacketHandle pph = (PHPacketHandle)&ppm_packet; + + while (1) { + +#ifdef PIOS_INCLUDE_WDG + // Update the watchdog timer. + PIOS_WDG_UpdateFlag(PIOS_WDG_PPMINPUT); +#endif /* PIOS_INCLUDE_WDG */ + + // Send the PPM packet + for (uint8_t i = 1; i <= PIOS_PPM_NUM_INPUTS; ++i) + ppm_packet.channels[i - 1] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i); + + // Send the packet. + ppm_packet.header.destination_id = data->destination_id; + ppm_packet.header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id); + ppm_packet.header.type = PACKET_TYPE_PPM; + ppm_packet.header.data_size = PH_PPM_DATA_SIZE(&ppm_packet); + xQueueSend(data->sendPacketQueue, &pph, MAX_PORT_DELAY); + + // Delay until the next update period. + vTaskDelay(PIOS_PPM_PACKET_UPDATE_PERIOD_MS / portTICK_RATE_MS); + } +} + +/** + * Transmit data buffer to the com port. + * \param[in] buf Data buffer to send + * \param[in] length Length of buffer + * \return -1 on failure + * \return number of bytes transmitted on success + */ +static int32_t transmitData(uint8_t *buf, int32_t length) +{ + uint32_t outputPort = PIOS_COM_UAVTALK; +#if defined(PIOS_INCLUDE_USB) + // Determine output port (USB takes priority over telemetry port) + if (PIOS_USB_CheckAvailable(0) && PIOS_COM_USB_HID) + outputPort = PIOS_COM_USB_HID; +#endif /* PIOS_INCLUDE_USB */ + if(outputPort) + return PIOS_COM_SendBuffer(outputPort, buf, length); + else + return -1; +} + +/** + * Transmit a packet to the radio port. + * \param[in] buf Data buffer to send + * \param[in] length Length of buffer + * \return -1 on failure + * \return number of bytes transmitted on success + */ +static int32_t transmitPacket(PHPacketHandle p) +{ + data->txBytes += PH_PACKET_SIZE(p); + return PIOS_COM_SendBuffer(PIOS_COM_RADIO, (uint8_t*)p, PH_PACKET_SIZE(p)); +} + +/** + * Receive a packet + * \param[in] buf The received data buffer + * \param[in] length Length of buffer + */ +static void receiveData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc) +{ + data->RSSI = rssi; + + // Packet data should go to transparent com if it's configured, + // USB HID if it's connected, otherwise, UAVTalk com if it's configured. + uint32_t outputPort = PIOS_COM_TRANS_COM; + if (!outputPort) + { + outputPort = PIOS_COM_UAVTALK; +#if defined(PIOS_INCLUDE_USB) + // Determine output port (USB takes priority over telemetry port) + if (PIOS_USB_CheckAvailable(0) && PIOS_COM_USB_HID) + outputPort = PIOS_COM_USB_HID; +#endif /* PIOS_INCLUDE_USB */ + } + if (!outputPort) + return; + + // Send the received data to the com port + if (PIOS_COM_SendBuffer(outputPort, buf, len) != len) + // Error on transmit + data->comTxErrors++; +} + +/** + * Receive a status packet + * \param[in] status The status structure + */ +static void StatusHandler(PHStatusPacketHandle status, int8_t rssi, int8_t afc) +{ + uint32_t id = status->header.source_id; + bool found = false; + // Have we seen this device recently? + uint8_t id_idx = 0; + for ( ; id_idx < PIPXSTATUS_PAIRIDS_NUMELEM; ++id_idx) + if(data->pairStats[id_idx].pairID == id) + { + found = true; + break; + } + + // If we have seen it, update the RSSI and reset the last contact couter + if(found) + { + data->pairStats[id_idx].rssi = rssi; + data->pairStats[id_idx].retries = status->retries; + data->pairStats[id_idx].errors = status->errors; + data->pairStats[id_idx].uavtalk_errors = status->uavtalk_errors; + data->pairStats[id_idx].resets = status->resets; + data->pairStats[id_idx].dropped = status->dropped; + data->pairStats[id_idx].lastContact = 0; + } + + // If we haven't seen it, find a slot to put it in. + if (!found) + { + uint32_t pairID; + PipXSettingsPairIDGet(&pairID); + + uint8_t min_idx = 0; + if(id != pairID) + { + int8_t min_rssi = data->pairStats[0].rssi; + for (id_idx = 1; id_idx < PIPXSTATUS_PAIRIDS_NUMELEM; ++id_idx) + { + if(data->pairStats[id_idx].rssi < min_rssi) + { + min_rssi = data->pairStats[id_idx].rssi; + min_idx = id_idx; + } + } + } + data->pairStats[min_idx].pairID = id; + data->pairStats[min_idx].rssi = rssi; + data->pairStats[min_idx].retries = status->retries; + data->pairStats[min_idx].errors = status->errors; + data->pairStats[min_idx].uavtalk_errors = status->uavtalk_errors; + data->pairStats[min_idx].resets = status->resets; + data->pairStats[min_idx].dropped = status->dropped; + data->pairStats[min_idx].lastContact = 0; + } +} + +/** + * Receive a ppm packet + * \param[in] channels The ppm channels + */ +static void PPMHandler(uint16_t *channels) +{ + GCSReceiverData rcvr; + + // Copy the receiver channels into the GCSReceiver object. + for (uint8_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; ++i) + rcvr.Channel[i] = channels[i]; + + // Set the GCSReceiverData object. + GCSReceiverSet(&rcvr); +} + +static BufferedReadHandle BufferedReadInit(uint32_t com_port, uint16_t buffer_length) +{ + BufferedReadHandle h = (BufferedReadHandle)pvPortMalloc(sizeof(ReadBuffer)); + if (!h) + return NULL; + + h->com_port = com_port; + h->buffer = (uint8_t*)pvPortMalloc(buffer_length); + h->length = buffer_length; + h->index = 0; + h->data_length = 0; + + if (h->buffer == NULL) + return NULL; + + return h; +} + +static bool BufferedRead(BufferedReadHandle h, uint8_t *value, uint32_t timeout_ms) +{ + // Read some data if required. + if(h->index == h->data_length) + { + uint32_t rx_bytes = PIOS_COM_ReceiveBuffer(h->com_port, h->buffer, h->length, timeout_ms); + if (rx_bytes == 0) + return false; + h->index = 0; + h->data_length = rx_bytes; + } + + // Return the next byte. + *value = h->buffer[h->index++]; + return true; +} + +static void BufferedReadSetCom(BufferedReadHandle h, uint32_t com_port) +{ + h->com_port = com_port; +} + +/** + * Update the telemetry settings, called on startup. + * FIXME: This should be in the TelemetrySettings object. But objects + * have too much overhead yet. Also the telemetry has no any specific + * settings, etc. Thus the HwSettings object which contains the + * telemetry port speed is used for now. + */ +static void updateSettings() +{ + + // Get the settings. + PipXSettingsData pipxSettings; + PipXSettingsGet(&pipxSettings); + + // Initialize the destination ID + data->destination_id = pipxSettings.PairID ? pipxSettings.PairID : 0xffffffff; + DEBUG_PRINTF(2, "PairID: %x\n\r", data->destination_id); + + if (PIOS_COM_TELEMETRY) { + switch (pipxSettings.TelemetrySpeed) { + case PIPXSETTINGS_TELEMETRYSPEED_2400: + PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 2400); + break; + case PIPXSETTINGS_TELEMETRYSPEED_4800: + PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 4800); + break; + case PIPXSETTINGS_TELEMETRYSPEED_9600: + PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 9600); + break; + case PIPXSETTINGS_TELEMETRYSPEED_19200: + PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 19200); + break; + case PIPXSETTINGS_TELEMETRYSPEED_38400: + PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 38400); + break; + case PIPXSETTINGS_TELEMETRYSPEED_57600: + PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 57600); + break; + case PIPXSETTINGS_TELEMETRYSPEED_115200: + PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 115200); + break; + } + } + if (PIOS_COM_FLEXI) { + switch (pipxSettings.FlexiSpeed) { + case PIPXSETTINGS_TELEMETRYSPEED_2400: + PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 2400); + break; + case PIPXSETTINGS_TELEMETRYSPEED_4800: + PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 4800); + break; + case PIPXSETTINGS_TELEMETRYSPEED_9600: + PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 9600); + break; + case PIPXSETTINGS_TELEMETRYSPEED_19200: + PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 19200); + break; + case PIPXSETTINGS_TELEMETRYSPEED_38400: + PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 38400); + break; + case PIPXSETTINGS_TELEMETRYSPEED_57600: + PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 57600); + break; + case PIPXSETTINGS_TELEMETRYSPEED_115200: + PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 115200); + break; + } + } + if (PIOS_COM_VCP) { + switch (pipxSettings.VCPSpeed) { + case PIPXSETTINGS_TELEMETRYSPEED_2400: + PIOS_COM_ChangeBaud(PIOS_COM_VCP, 2400); + break; + case PIPXSETTINGS_TELEMETRYSPEED_4800: + PIOS_COM_ChangeBaud(PIOS_COM_VCP, 4800); + break; + case PIPXSETTINGS_TELEMETRYSPEED_9600: + PIOS_COM_ChangeBaud(PIOS_COM_VCP, 9600); + break; + case PIPXSETTINGS_TELEMETRYSPEED_19200: + PIOS_COM_ChangeBaud(PIOS_COM_VCP, 19200); + break; + case PIPXSETTINGS_TELEMETRYSPEED_38400: + PIOS_COM_ChangeBaud(PIOS_COM_VCP, 38400); + break; + case PIPXSETTINGS_TELEMETRYSPEED_57600: + PIOS_COM_ChangeBaud(PIOS_COM_VCP, 57600); + break; + case PIPXSETTINGS_TELEMETRYSPEED_115200: + PIOS_COM_ChangeBaud(PIOS_COM_VCP, 115200); + break; + } + } +} diff --git a/flight/PipXtreme/inc/gpio_in.h b/flight/Modules/RadioComBridge/inc/radiocombridge.h similarity index 75% rename from flight/PipXtreme/inc/gpio_in.h rename to flight/Modules/RadioComBridge/inc/radiocombridge.h index 7bfd53375..cb9862b9a 100644 --- a/flight/PipXtreme/inc/gpio_in.h +++ b/flight/Modules/RadioComBridge/inc/radiocombridge.h @@ -1,41 +1,39 @@ -/** - ****************************************************************************** - * - * @file gpio_in.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief GPIO functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef __GPIO_IN_H__ -#define __GPIO_IN_H__ - -// ***************************************************************** - -void GPIO_IN_Init(void); -bool GPIO_IN(uint8_t num); - -// ***************************************************************** - -#endif - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup RadioComBridgeModule Com Port to Radio Bridge Module + * @brief Bridge Com and Radio ports + * @{ + * + * @file radiocombridge.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the telemetry module. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef RADIOCOMBRIDGE_H +#define RADIOCOMBRIDGE_H + +#endif // RADIOCOMBRIDGE_H + +/** + * @} + * @} + */ diff --git a/flight/Bootloaders/AHRS/inc/ahrs_spi_program_slave.h b/flight/Modules/Sensors/inc/sensors.h similarity index 72% rename from flight/Bootloaders/AHRS/inc/ahrs_spi_program_slave.h rename to flight/Modules/Sensors/inc/sensors.h index 683bfa0f6..d816a5827 100644 --- a/flight/Bootloaders/AHRS/inc/ahrs_spi_program_slave.h +++ b/flight/Modules/Sensors/inc/sensors.h @@ -1,35 +1,37 @@ -/** - ****************************************************************************** - * - * @file ahrs_spi_program_slave.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief AHRS programming over SPI link - slave(AHRS) end. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef AHRS_SPI_PROGRAM_SLAVE_H -#define AHRS_SPI_PROGRAM_SLAVE_H - -/** Check if OpenPilot is trying to program AHRS - * If so, it will program the FLASH then return - * If not it just returns. - */ -void AhrsProgramReceive(uint32_t spi_id); -#endif //AHRS_PROGRAM_SLAVE_H +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup Sensors Sensors Module + * @{ + * + * @file attitude.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Acquires sensor data and fuses it into attitude estimate for CC + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef SENSORS_H +#define SENSORS_H + +#include "openpilot.h" + +int32_t SensorsInitialize(void); + +#endif // SENSORS_H diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c new file mode 100644 index 000000000..2e097d0c6 --- /dev/null +++ b/flight/Modules/Sensors/sensors.c @@ -0,0 +1,480 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup Sensors + * @brief Acquires sensor data + * Specifically updates the the @ref Gyros, @ref Accels, and @ref Magnetometer objects + * @{ + * + * @file sensors.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Module to handle all comms to the AHRS on a periodic basis. + * + * @see The GNU Public License (GPL) Version 3 + * + ******************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/** + * Input objects: None, takes sensor data via pios + * Output objects: @ref Gyros @ref Accels @ref Magnetometer + * + * The module executes in its own thread. + * + * UAVObjects are automatically generated by the UAVObjectGenerator from + * the object definition XML file. + * + * Modules have no API, all communication to other modules is done through UAVObjects. + * However modules may use the API exposed by shared libraries. + * See the OpenPilot wiki for more details. + * http://www.openpilot.org/OpenPilot_Application_Architecture + * + */ + +#include "pios.h" +#include "attitude.h" +#include "magnetometer.h" +#include "accels.h" +#include "gyros.h" +#include "gyrosbias.h" +#include "attitudeactual.h" +#include "attitudesettings.h" +#include "revocalibration.h" +#include "flightstatus.h" +#include "gpsposition.h" +#include "baroaltitude.h" +#include "CoordinateConversions.h" + +#include + +// Private constants +#define STACK_SIZE_BYTES 1540 +#define TASK_PRIORITY (tskIDLE_PRIORITY+3) +#define SENSOR_PERIOD 2 + +#define F_PI 3.14159265358979323846f +#define PI_MOD(x) (fmodf(x + F_PI, F_PI * 2) - F_PI) +// Private types + +// Private variables +static xTaskHandle sensorsTaskHandle; +static bool gps_updated = false; +static bool baro_updated = false; + +// Private functions +static void SensorsTask(void *parameters); +static void settingsUpdatedCb(UAVObjEvent * objEv); +static void sensorsUpdatedCb(UAVObjEvent * objEv); + +// These values are initialized by settings but can be updated by the attitude algorithm +static bool bias_correct_gyro = true; + +static float mag_bias[3] = {0,0,0}; +static float mag_scale[3] = {0,0,0}; +static float accel_bias[3] = {0,0,0}; +static float accel_scale[3] = {0,0,0}; + +static float R[3][3] = {{0}}; +static int8_t rotate = 0; + +/** + * API for sensor fusion algorithms: + * Configure(xQueueHandle gyro, xQueueHandle accel, xQueueHandle mag, xQueueHandle baro) + * Stores all the queues the algorithm will pull data from + * FinalizeSensors() -- before saving the sensors modifies them based on internal state (gyro bias) + * Update() -- queries queues and updates the attitude estiamte + */ + + +/** + * Initialise the module. Called before the start function + * \returns 0 on success or -1 if initialisation failed + */ +int32_t SensorsInitialize(void) +{ + GyrosInitialize(); + GyrosBiasInitialize(); + AccelsInitialize(); + MagnetometerInitialize(); + RevoCalibrationInitialize(); + AttitudeSettingsInitialize(); + + rotate = 0; + + RevoCalibrationConnectCallback(&settingsUpdatedCb); + AttitudeSettingsConnectCallback(&settingsUpdatedCb); + + return 0; +} + +/** + * Start the task. Expects all objects to be initialized by this point. + * \returns 0 on success or -1 if initialisation failed + */ +int32_t SensorsStart(void) +{ + // Start main task + xTaskCreate(SensorsTask, (signed char *)"Sensors", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &sensorsTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_SENSORS, sensorsTaskHandle); + PIOS_WDG_RegisterFlag(PIOS_WDG_SENSORS); + + return 0; +} + +MODULE_INITCALL(SensorsInitialize, SensorsStart) + +int32_t accel_test; +int32_t gyro_test; +int32_t mag_test; +//int32_t pressure_test; + + +/** + * The sensor task. This polls the gyros at 500 Hz and pumps that data to + * stabilization and to the attitude loop + * + * This function has a lot of if/defs right now to allow these configurations: + * 1. BMA180 accel and MPU6000 gyro + * 2. MPU6000 gyro and accel + * 3. BMA180 accel and L3GD20 gyro + */ + +uint32_t sensor_dt_us; +static void SensorsTask(void *parameters) +{ + portTickType lastSysTime; + uint32_t accel_samples = 0; + uint32_t gyro_samples = 0; + int32_t accel_accum[3] = {0, 0, 0}; + int32_t gyro_accum[3] = {0,0,0}; + float gyro_scaling = 0; + float accel_scaling = 0; + static int32_t timeval; + + AlarmsClear(SYSTEMALARMS_ALARM_SENSORS); + + UAVObjEvent ev; + settingsUpdatedCb(&ev); + + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + switch(bdinfo->board_rev) { + case 0x01: +#if defined(PIOS_INCLUDE_L3GD20) + gyro_test = PIOS_L3GD20_Test(); +#endif +#if defined(PIOS_INCLUDE_BMA180) + accel_test = PIOS_BMA180_Test(); +#endif + break; + case 0x02: +#if defined(PIOS_INCLUDE_MPU6000) + gyro_test = PIOS_MPU6000_Test(); + accel_test = gyro_test; +#endif + break; + default: + PIOS_DEBUG_Assert(0); + } + +#if defined(PIOS_INCLUDE_HMC5883) + mag_test = PIOS_HMC5883_Test(); +#endif + + if(accel_test < 0 || gyro_test < 0 || mag_test < 0) { + AlarmsSet(SYSTEMALARMS_ALARM_SENSORS, SYSTEMALARMS_ALARM_CRITICAL); + while(1) { + PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS); + vTaskDelay(10); + } + } + + // If debugging connect callback + if(pios_com_aux_id != 0) { + BaroAltitudeConnectCallback(&sensorsUpdatedCb); + GPSPositionConnectCallback(&sensorsUpdatedCb); + } + + // Main task loop + lastSysTime = xTaskGetTickCount(); + bool error = false; + uint32_t mag_update_time = PIOS_DELAY_GetRaw(); + while (1) { + // TODO: add timeouts to the sensor reads and set an error if the fail + sensor_dt_us = PIOS_DELAY_DiffuS(timeval); + timeval = PIOS_DELAY_GetRaw(); + + if (error) { + PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS); + lastSysTime = xTaskGetTickCount(); + vTaskDelayUntil(&lastSysTime, SENSOR_PERIOD / portTICK_RATE_MS); + AlarmsSet(SYSTEMALARMS_ALARM_SENSORS, SYSTEMALARMS_ALARM_CRITICAL); + error = false; + } else { + AlarmsClear(SYSTEMALARMS_ALARM_SENSORS); + } + + int32_t read_good; + int32_t count; + + for (int i = 0; i < 3; i++) { + accel_accum[i] = 0; + gyro_accum[i] = 0; + } + accel_samples = 0; + gyro_samples = 0; + + AccelsData accelsData; + GyrosData gyrosData; + + switch(bdinfo->board_rev) { + case 0x01: // L3GD20 + BMA180 board +#if defined(PIOS_INCLUDE_BMA180) + { + struct pios_bma180_data accel; + + count = 0; + while((read_good = PIOS_BMA180_ReadFifo(&accel)) != 0 && !error) + error = ((xTaskGetTickCount() - lastSysTime) > SENSOR_PERIOD) ? true : error; + if (error) { + // Unfortunately if the BMA180 ever misses getting read, then it will not + // trigger more interrupts. In this case we must force a read to kickstarts + // it. + struct pios_bma180_data data; + PIOS_BMA180_ReadAccels(&data); + continue; + } + while(read_good == 0) { + count++; + + accel_accum[0] += accel.x; + accel_accum[1] += accel.y; + accel_accum[2] += accel.z; + + read_good = PIOS_BMA180_ReadFifo(&accel); + } + accel_samples = count; + accel_scaling = PIOS_BMA180_GetScale(); + + // Get temp from last reading + accelsData.temperature = 25.0f + ((float) accel.temperature - 2.0f) / 2.0f; + } +#endif +#if defined(PIOS_INCLUDE_L3GD20) + { + struct pios_l3gd20_data gyro; + gyro_samples = 0; + xQueueHandle gyro_queue = PIOS_L3GD20_GetQueue(); + + if(xQueueReceive(gyro_queue, (void *) &gyro, 4) == errQUEUE_EMPTY) { + error = true; + continue; + } + + gyro_samples = 1; + gyro_accum[0] += gyro.gyro_x; + gyro_accum[1] += gyro.gyro_y; + gyro_accum[2] += gyro.gyro_z; + + gyro_scaling = PIOS_L3GD20_GetScale(); + + // Get temp from last reading + gyrosData.temperature = gyro.temperature; + } +#endif + break; + case 0x02: // MPU6000 board +#if defined(PIOS_INCLUDE_MPU6000) + { + struct pios_mpu6000_data mpu6000_data; + xQueueHandle queue = PIOS_MPU6000_GetQueue(); + + while(xQueueReceive(queue, (void *) &mpu6000_data, gyro_samples == 0 ? 10 : 0) != errQUEUE_EMPTY) + { + gyro_accum[0] += mpu6000_data.gyro_x; + gyro_accum[1] += mpu6000_data.gyro_y; + gyro_accum[2] += mpu6000_data.gyro_z; + + accel_accum[0] += mpu6000_data.accel_x; + accel_accum[1] += mpu6000_data.accel_y; + accel_accum[2] += mpu6000_data.accel_z; + + gyro_samples ++; + accel_samples ++; + } + + if (gyro_samples == 0) { + PIOS_MPU6000_ReadGyros(&mpu6000_data); + error = true; + continue; + } + + gyro_scaling = PIOS_MPU6000_GetScale(); + accel_scaling = PIOS_MPU6000_GetAccelScale(); + + gyrosData.temperature = 35.0f + ((float) mpu6000_data.temperature + 512.0f) / 340.0f; + accelsData.temperature = 35.0f + ((float) mpu6000_data.temperature + 512.0f) / 340.0f; + } +#endif /* PIOS_INCLUDE_MPU6000 */ + break; + default: + PIOS_DEBUG_Assert(0); + } + + // Scale the accels + float accels[3] = {(float) accel_accum[1] / accel_samples, + (float) accel_accum[0] / accel_samples, + -(float) accel_accum[2] / accel_samples}; + float accels_out[3] = {accels[0] * accel_scaling * accel_scale[0] - accel_bias[0], + accels[1] * accel_scaling * accel_scale[1] - accel_bias[1], + accels[2] * accel_scaling * accel_scale[2] - accel_bias[2]}; + if (rotate) { + rot_mult(R, accels_out, accels); + accelsData.x = accels[0]; + accelsData.y = accels[1]; + accelsData.z = accels[2]; + } else { + accelsData.x = accels_out[0]; + accelsData.y = accels_out[1]; + accelsData.z = accels_out[2]; + } + AccelsSet(&accelsData); + + // Scale the gyros + float gyros[3] = {(float) gyro_accum[1] / gyro_samples, + (float) gyro_accum[0] / gyro_samples, + -(float) gyro_accum[2] / gyro_samples}; + float gyros_out[3] = {gyros[0] * gyro_scaling, + gyros[1] * gyro_scaling, + gyros[2] * gyro_scaling}; + if (rotate) { + rot_mult(R, gyros_out, gyros); + gyrosData.x = gyros[0]; + gyrosData.y = gyros[1]; + gyrosData.z = gyros[2]; + } else { + gyrosData.x = gyros_out[0]; + gyrosData.y = gyros_out[1]; + gyrosData.z = gyros_out[2]; + } + + if (bias_correct_gyro) { + // Apply bias correction to the gyros + GyrosBiasData gyrosBias; + GyrosBiasGet(&gyrosBias); + gyrosData.x += gyrosBias.x; + gyrosData.y += gyrosBias.y; + gyrosData.z += gyrosBias.z; + } + GyrosSet(&gyrosData); + + // Because most crafts wont get enough information from gravity to zero yaw gyro, we try + // and make it average zero (weakly) + +#if defined(PIOS_INCLUDE_HMC5883) + MagnetometerData mag; + if (PIOS_HMC5883_NewDataAvailable() || PIOS_DELAY_DiffuS(mag_update_time) > 150000) { + int16_t values[3]; + PIOS_HMC5883_ReadMag(values); + float mags[3] = {(float) values[1] * mag_scale[0] - mag_bias[0], + (float) values[0] * mag_scale[1] - mag_bias[1], + -(float) values[2] * mag_scale[2] - mag_bias[2]}; + if (rotate) { + float mag_out[3]; + rot_mult(R, mags, mag_out); + mag.x = mag_out[0]; + mag.y = mag_out[1]; + mag.z = mag_out[2]; + } else { + mag.x = mags[0]; + mag.y = mags[1]; + mag.z = mags[2]; + } + MagnetometerSet(&mag); + mag_update_time = PIOS_DELAY_GetRaw(); + } +#endif + + PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS); + + switch(bdinfo->board_rev) { + case 0x01: // L3GD20 + BMA180 board + lastSysTime = xTaskGetTickCount(); + break; + case 0x02: + vTaskDelayUntil(&lastSysTime, SENSOR_PERIOD / portTICK_RATE_MS); + break; + default: + PIOS_DEBUG_Assert(0); + } + } +} + +/** + * Indicate that these sensors have been updated + */ +static void sensorsUpdatedCb(UAVObjEvent * objEv) +{ + if(objEv->obj == GPSPositionHandle()) + gps_updated = true; + if(objEv->obj == BaroAltitudeHandle()) + baro_updated = true; +} + +/** + * Locally cache some variables from the AtttitudeSettings object + */ +static void settingsUpdatedCb(UAVObjEvent * objEv) { + RevoCalibrationData cal; + RevoCalibrationGet(&cal); + + mag_bias[0] = cal.mag_bias[REVOCALIBRATION_MAG_BIAS_X]; + mag_bias[1] = cal.mag_bias[REVOCALIBRATION_MAG_BIAS_Y]; + mag_bias[2] = cal.mag_bias[REVOCALIBRATION_MAG_BIAS_Z]; + mag_scale[0] = cal.mag_scale[REVOCALIBRATION_MAG_SCALE_X]; + mag_scale[1] = cal.mag_scale[REVOCALIBRATION_MAG_SCALE_Y]; + mag_scale[2] = cal.mag_scale[REVOCALIBRATION_MAG_SCALE_Z]; + accel_bias[0] = cal.accel_bias[REVOCALIBRATION_ACCEL_BIAS_X]; + accel_bias[1] = cal.accel_bias[REVOCALIBRATION_ACCEL_BIAS_Y]; + accel_bias[2] = cal.accel_bias[REVOCALIBRATION_ACCEL_BIAS_Z]; + accel_scale[0] = cal.accel_scale[REVOCALIBRATION_ACCEL_SCALE_X]; + accel_scale[1] = cal.accel_scale[REVOCALIBRATION_ACCEL_SCALE_Y]; + accel_scale[2] = cal.accel_scale[REVOCALIBRATION_ACCEL_SCALE_Z]; + + AttitudeSettingsData attitudeSettings; + AttitudeSettingsGet(&attitudeSettings); + + // Indicates not to expend cycles on rotation + if(attitudeSettings.BoardRotation[0] == 0 && attitudeSettings.BoardRotation[1] == 0 && + attitudeSettings.BoardRotation[2] == 0) { + rotate = 0; + } else { + float rotationQuat[4]; + const float rpy[3] = {attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_ROLL], + attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_PITCH], + attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_YAW]}; + RPY2Quaternion(rpy, rotationQuat); + Quaternion2R(rotationQuat, R); + rotate = 1; + } + +} +/** + * @} + * @} + */ diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index ffc3c53be..b08a90076 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -38,7 +38,7 @@ #include "ratedesired.h" #include "stabilizationdesired.h" #include "attitudeactual.h" -#include "attituderaw.h" +#include "gyros.h" #include "flightstatus.h" #include "manualcontrol.h" // Just to get a macro #include "CoordinateConversions.h" @@ -55,7 +55,7 @@ #define TASK_PRIORITY (tskIDLE_PRIORITY+4) #define FAILSAFE_TIMEOUT_MS 30 -enum {PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_MAX}; +enum {PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_VBAR_ROLL, PID_VBAR_PITCH, PID_VBAR_YAW, PID_MAX}; enum {ROLL,PITCH,YAW,MAX_AXES}; @@ -74,21 +74,24 @@ typedef struct { static xTaskHandle taskHandle; static StabilizationSettingsData settings; static xQueueHandle queue; -float dT = 1; float gyro_alpha = 0; float gyro_filtered[3] = {0,0,0}; float axis_lock_accum[3] = {0,0,0}; +float vbar_sensitivity[3] = {1, 1, 1}; uint8_t max_axis_lock = 0; uint8_t max_axislock_rate = 0; float weak_leveling_kp = 0; uint8_t weak_leveling_max = 0; bool lowThrottleZeroIntegral; - +float vbar_integral[3] = {0, 0, 0}; +float vbar_decay = 0.991f; pid_type pids[PID_MAX]; +int8_t vbar_gyros_suppress; +bool vbar_piro_comp = false; // Private functions static void stabilizationTask(void* parameters); -static float ApplyPid(pid_type * pid, const float err); +static float ApplyPid(pid_type * pid, const float err, float dT); static float bound(float val); static void ZeroPids(void); static void SettingsUpdatedCb(UAVObjEvent * ev); @@ -99,6 +102,15 @@ static void SettingsUpdatedCb(UAVObjEvent * ev); int32_t StabilizationStart() { // Initialize variables + // Create object queue + queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); + + // Listen for updates. + // AttitudeActualConnectQueue(queue); + GyrosConnectQueue(queue); + + StabilizationSettingsConnectCallback(SettingsUpdatedCb); + SettingsUpdatedCb(StabilizationSettingsHandle()); // Start main task xTaskCreate(stabilizationTask, (signed char*)"Stabilization", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); @@ -119,17 +131,6 @@ int32_t StabilizationInitialize() RateDesiredInitialize(); #endif - // Create object queue - queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); - - // Listen for updates. - // AttitudeActualConnectQueue(queue); - AttitudeRawConnectQueue(queue); - - StabilizationSettingsConnectCallback(SettingsUpdatedCb); - SettingsUpdatedCb(StabilizationSettingsHandle()); - // Start main task - return 0; } @@ -140,24 +141,24 @@ MODULE_INITCALL(StabilizationInitialize, StabilizationStart) */ static void stabilizationTask(void* parameters) { - portTickType lastSysTime; - portTickType thisSysTime; UAVObjEvent ev; + uint32_t timeval = PIOS_DELAY_GetRaw(); ActuatorDesiredData actuatorDesired; StabilizationDesiredData stabDesired; RateDesiredData rateDesired; AttitudeActualData attitudeActual; - AttitudeRawData attitudeRaw; + GyrosData gyrosData; FlightStatusData flightStatus; SettingsUpdatedCb((UAVObjEvent *) NULL); // Main task loop - lastSysTime = xTaskGetTickCount(); ZeroPids(); while(1) { + float dT; + PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION); // Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe @@ -167,16 +168,13 @@ static void stabilizationTask(void* parameters) continue; } - // Check how long since last update - thisSysTime = xTaskGetTickCount(); - if(thisSysTime > lastSysTime) // reuse dt in case of wraparound - dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f; - lastSysTime = thisSysTime; + dT = PIOS_DELAY_DiffuS(timeval) * 1.0e-6f; + timeval = PIOS_DELAY_GetRaw(); FlightStatusGet(&flightStatus); StabilizationDesiredGet(&stabDesired); AttitudeActualGet(&attitudeActual); - AttitudeRawGet(&attitudeRaw); + GyrosGet(&gyrosData); #if defined(DIAGNOSTICS) RateDesiredGet(&rateDesired); @@ -216,13 +214,13 @@ static void stabilizationTask(void* parameters) float local_error[3] = {stabDesired.Roll - attitudeActual.Roll, stabDesired.Pitch - attitudeActual.Pitch, stabDesired.Yaw - attitudeActual.Yaw}; - local_error[2] = fmod(local_error[2] + 180, 360) - 180; + local_error[2] = fmodf(local_error[2] + 180, 360) - 180; #endif - for(uint8_t i = 0; i < MAX_AXES; i++) { - gyro_filtered[i] = gyro_filtered[i] * gyro_alpha + attitudeRaw.gyros[i] * (1 - gyro_alpha); - } + gyro_filtered[0] = gyro_filtered[0] * gyro_alpha + gyrosData.x * (1 - gyro_alpha); + gyro_filtered[1] = gyro_filtered[1] * gyro_alpha + gyrosData.y * (1 - gyro_alpha); + gyro_filtered[2] = gyro_filtered[2] * gyro_alpha + gyrosData.z * (1 - gyro_alpha); float *attitudeDesiredAxis = &stabDesired.Roll; float *actuatorDesiredAxis = &actuatorDesired.Roll; @@ -234,6 +232,7 @@ static void stabilizationTask(void* parameters) switch(stabDesired.StabilizationMode[i]) { case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE: + case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR: rateDesiredAxis[i] = attitudeDesiredAxis[i]; // Zero attitude and axis lock accumulators @@ -258,7 +257,7 @@ static void stabilizationTask(void* parameters) break; } case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: - rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i]); + rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT); if(rateDesiredAxis[i] > settings.MaximumRate[i]) rateDesiredAxis[i] = settings.MaximumRate[i]; @@ -282,7 +281,7 @@ static void stabilizationTask(void* parameters) else if(axis_lock_accum[i] < -max_axis_lock) axis_lock_accum[i] = -max_axis_lock; - rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i]); + rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i], dT); } if(rateDesiredAxis[i] > settings.MaximumRate[i]) @@ -294,42 +293,78 @@ static void stabilizationTask(void* parameters) } } + // Piro compensation rotates the virtual flybar by yaw step to keep it + // rotated to external world + if (vbar_piro_comp) { + const float F_PI = 3.14159f; + float cy = cosf(gyro_filtered[2] / 180.0f * F_PI * dT); + float sy = sinf(gyro_filtered[2] / 180.0f * F_PI * dT); + + float vbar_pitch = cy * vbar_integral[1] - sy * vbar_integral[0]; + float vbar_roll = sy * vbar_integral[1] + cy * vbar_integral[0]; + + vbar_integral[1] = vbar_pitch; + vbar_integral[0] = vbar_roll; + } + uint8_t shouldUpdate = 1; #if defined(DIAGNOSTICS) RateDesiredSet(&rateDesired); #endif ActuatorDesiredGet(&actuatorDesired); //Calculate desired command - for(int8_t ct=0; ct< MAX_AXES; ct++) + for(uint32_t i = 0; i < MAX_AXES; i++) { - switch(stabDesired.StabilizationMode[ct]) + switch(stabDesired.StabilizationMode[i]) { case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE: case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK: case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING: { - float command = ApplyPid(&pids[PID_RATE_ROLL + ct], rateDesiredAxis[ct] - gyro_filtered[ct]); - actuatorDesiredAxis[ct] = bound(command); + float command = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); + actuatorDesiredAxis[i] = bound(command); + break; + } + case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR: + { + // Track the angle of the virtual flybar which includes a slow decay + vbar_integral[i] = vbar_integral[i] * vbar_decay + gyro_filtered[i] * dT; + if (vbar_integral[i] > settings.VbarMaxAngle) + vbar_integral[i] = settings.VbarMaxAngle; + if (-vbar_integral[i] < -settings.VbarMaxAngle) + vbar_integral[i] = -settings.VbarMaxAngle; + + // Command signal is composed of stick input added to the gyro and virtual flybar + float gyro_gain = 1.0f; + if (vbar_gyros_suppress > 0) { + gyro_gain = (1.0f - fabs(rateDesiredAxis[i]) * vbar_gyros_suppress / 100.0f); + gyro_gain = (gyro_gain < 0) ? 0 : gyro_gain; + } + float command = rateDesiredAxis[i] * vbar_sensitivity[i] - gyro_gain * ( + vbar_integral[i] * pids[PID_VBAR_ROLL + i].i + + gyro_filtered[i] * pids[PID_VBAR_ROLL + i].p); + + actuatorDesiredAxis[i] = bound(command); break; } case STABILIZATIONDESIRED_STABILIZATIONMODE_NONE: - switch (ct) + switch (i) { case ROLL: - actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]); + actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]); shouldUpdate = 1; pids[PID_RATE_ROLL].iAccumulator = 0; pids[PID_ROLL].iAccumulator = 0; break; case PITCH: - actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]); + actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]); shouldUpdate = 1; pids[PID_RATE_PITCH].iAccumulator = 0; pids[PID_PITCH].iAccumulator = 0; break; case YAW: - actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]); + actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]); shouldUpdate = 1; pids[PID_RATE_YAW].iAccumulator = 0; pids[PID_YAW].iAccumulator = 0; @@ -367,30 +402,30 @@ static void stabilizationTask(void* parameters) } } -float ApplyPid(pid_type * pid, const float err) +float ApplyPid(pid_type * pid, const float err, float dT) { float diff = (err - pid->lastErr); pid->lastErr = err; // Scale up accumulator by 1000 while computing to avoid losing precision - pid->iAccumulator += err * (pid->i * dT * 1000); - if(pid->iAccumulator > (pid->iLim * 1000)) { - pid->iAccumulator = pid->iLim * 1000; - } else if (pid->iAccumulator < -(pid->iLim * 1000)) { - pid->iAccumulator = -pid->iLim * 1000; + pid->iAccumulator += err * (pid->i * dT * 1000.0f); + if(pid->iAccumulator > (pid->iLim * 1000.0f)) { + pid->iAccumulator = pid->iLim * 1000.0f; + } else if (pid->iAccumulator < -(pid->iLim * 1000.0f)) { + pid->iAccumulator = -pid->iLim * 1000.0f; } - return ((err * pid->p) + pid->iAccumulator / 1000 + (diff * pid->d / dT)); + return ((err * pid->p) + pid->iAccumulator / 1000.0f + (diff * pid->d / dT)); } static void ZeroPids(void) { for(int8_t ct = 0; ct < PID_MAX; ct++) { - pids[ct].iAccumulator = 0; - pids[ct].lastErr = 0; + pids[ct].iAccumulator = 0.0f; + pids[ct].lastErr = 0.0f; } for(uint8_t i = 0; i < 3; i++) - axis_lock_accum[i] = 0; + axis_lock_accum[i] = 0.0f; } @@ -399,52 +434,68 @@ static void ZeroPids(void) */ static float bound(float val) { - if(val < -1) { - val = -1; - } else if(val > 1) { - val = 1; + if(val < -1.0f) { + val = -1.0f; + } else if(val > 1.0f) { + val = 1.0f; } return val; } - static void SettingsUpdatedCb(UAVObjEvent * ev) { memset(pids,0,sizeof (pid_type) * PID_MAX); StabilizationSettingsGet(&settings); // Set the roll rate PID constants - pids[0].p = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP]; - pids[0].i = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI]; - pids[0].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD]; - pids[0].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT]; + pids[PID_RATE_ROLL].p = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP]; + pids[PID_RATE_ROLL].i = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI]; + pids[PID_RATE_ROLL].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD]; + pids[PID_RATE_ROLL].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT]; // Set the pitch rate PID constants - pids[1].p = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP]; - pids[1].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI]; - pids[1].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD]; - pids[1].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT]; + pids[PID_RATE_PITCH].p = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP]; + pids[PID_RATE_PITCH].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI]; + pids[PID_RATE_PITCH].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD]; + pids[PID_RATE_PITCH].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT]; // Set the yaw rate PID constants - pids[2].p = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP]; - pids[2].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI]; - pids[2].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD]; - pids[2].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT]; + pids[PID_RATE_YAW].p = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP]; + pids[PID_RATE_YAW].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI]; + pids[PID_RATE_YAW].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD]; + pids[PID_RATE_YAW].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT]; // Set the roll attitude PI constants - pids[3].p = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP]; - pids[3].i = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI]; - pids[3].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT]; + pids[PID_ROLL].p = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP]; + pids[PID_ROLL].i = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI]; + pids[PID_ROLL].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT]; // Set the pitch attitude PI constants - pids[4].p = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP]; - pids[4].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI]; - pids[4].iLim = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT]; + pids[PID_PITCH].p = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP]; + pids[PID_PITCH].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI]; + pids[PID_PITCH].iLim = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT]; // Set the yaw attitude PI constants - pids[5].p = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP]; - pids[5].i = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI]; - pids[5].iLim = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT]; + pids[PID_YAW].p = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP]; + pids[PID_YAW].i = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI]; + pids[PID_YAW].iLim = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT]; + + // Set the roll attitude PI constants + pids[PID_VBAR_ROLL].p = settings.VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KP]; + pids[PID_VBAR_ROLL].i = settings.VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KI]; + + // Set the pitch attitude PI constants + pids[PID_VBAR_PITCH].p = settings.VbarPitchPI[STABILIZATIONSETTINGS_VBARPITCHPI_KP]; + pids[PID_VBAR_PITCH].i = settings.VbarPitchPI[STABILIZATIONSETTINGS_VBARPITCHPI_KI]; + + // Set the yaw attitude PI constants + pids[PID_VBAR_YAW].p = settings.VbarYawPI[STABILIZATIONSETTINGS_VBARYAWPI_KP]; + pids[PID_VBAR_YAW].i = settings.VbarYawPI[STABILIZATIONSETTINGS_VBARYAWPI_KI]; + + // Need to store the vbar sensitivity + vbar_sensitivity[0] = settings.VbarSensitivity[0]; + vbar_sensitivity[1] = settings.VbarSensitivity[1]; + vbar_sensitivity[2] = settings.VbarSensitivity[2]; // Maximum deviation to accumulate for axis lock max_axis_lock = settings.MaxAxisLock; @@ -466,7 +517,12 @@ static void SettingsUpdatedCb(UAVObjEvent * ev) if(settings.GyroTau < 0.0001) gyro_alpha = 0; // not trusting this to resolve to 0 else - gyro_alpha = exp(-fakeDt / settings.GyroTau); + gyro_alpha = expf(-fakeDt / settings.GyroTau); + + // Compute time constant for vbar decay term based on a tau + vbar_decay = expf(-fakeDt / settings.VbarTau); + vbar_gyros_suppress = settings.VbarGyroSuppress; + vbar_piro_comp = settings.VbarPiroComp == STABILIZATIONSETTINGS_VBARPIROCOMP_TRUE; } diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index cae6af590..827b264d2 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -65,7 +65,7 @@ #define STACK_SIZE_BYTES 924 #endif -#define TASK_PRIORITY (tskIDLE_PRIORITY+2) +#define TASK_PRIORITY (tskIDLE_PRIORITY+1) // Private types @@ -215,7 +215,7 @@ static void objectUpdatedCb(UAVObjEvent * ev) // Get object data ObjectPersistenceGet(&objper); - int retval = -1; + int retval = 1; // Execute action if (objper.Operation == OBJECTPERSISTENCE_OPERATION_LOAD) { if (objper.Selection == OBJECTPERSISTENCE_SELECTION_SINGLEOBJECT) { @@ -242,6 +242,13 @@ static void objectUpdatedCb(UAVObjEvent * ev) } // Save selected instance retval = UAVObjSave(obj, objper.InstanceID); + + // Not sure why this is needed + vTaskDelay(10); + + // Verify saving worked + if (retval == 0) + retval = UAVObjLoad(obj, objper.InstanceID); } else if (objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLSETTINGS || objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) { retval = UAVObjSaveSettings(); @@ -271,9 +278,17 @@ static void objectUpdatedCb(UAVObjEvent * ev) retval = PIOS_FLASHFS_Format(); #endif } - if(retval == 0) { - objper.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED; - ObjectPersistenceSet(&objper); + switch(retval) { + case 0: + objper.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED; + ObjectPersistenceSet(&objper); + break; + case -1: + objper.Operation = OBJECTPERSISTENCE_OPERATION_ERROR; + ObjectPersistenceSet(&objper); + break; + default: + break; } } } @@ -384,7 +399,7 @@ static void updateStats() if (now > lastTickCount) { uint32_t dT = (xTaskGetTickCount() - lastTickCount) * portTICK_RATE_MS; // in ms stats.CPULoad = - 100 - (uint8_t) round(100.0 * ((float)idleCounter / ((float)dT / 1000.0)) / (float)IDLE_COUNTS_PER_SEC_AT_NO_LOAD); + 100 - (uint8_t) roundf(100.0f * ((float)idleCounter / ((float)dT / 1000.0f)) / (float)IDLE_COUNTS_PER_SEC_AT_NO_LOAD); } //else: TickCount has wrapped, do not calc now lastTickCount = now; idleCounterClear = 1; @@ -457,11 +472,21 @@ static void updateSystemAlarms() EventGetStats(&evStats); UAVObjClearStats(); EventClearStats(); - if (objStats.eventErrors > 0 || evStats.eventErrors > 0) { + if (objStats.eventCallbackErrors > 0 || objStats.eventQueueErrors > 0 || evStats.eventErrors > 0) { AlarmsSet(SYSTEMALARMS_ALARM_EVENTSYSTEM, SYSTEMALARMS_ALARM_WARNING); } else { AlarmsClear(SYSTEMALARMS_ALARM_EVENTSYSTEM); } + + if (objStats.lastCallbackErrorID || objStats.lastQueueErrorID || evStats.lastErrorID) { + SystemStatsData sysStats; + SystemStatsGet(&sysStats); + sysStats.EventSystemWarningID = evStats.lastErrorID; + sysStats.ObjectManagerCallbackID = objStats.lastCallbackErrorID; + sysStats.ObjectManagerQueueID = objStats.lastQueueErrorID; + SystemStatsSet(&sysStats); + } + } /** diff --git a/flight/Modules/Telemetry/telemetry.c b/flight/Modules/Telemetry/telemetry.c index 12818529f..2b04e0545 100644 --- a/flight/Modules/Telemetry/telemetry.c +++ b/flight/Modules/Telemetry/telemetry.c @@ -73,7 +73,7 @@ static void telemetryTxTask(void *parameters); static void telemetryRxTask(void *parameters); static int32_t transmitData(uint8_t * data, int32_t length); static void registerObject(UAVObjHandle obj); -static void updateObject(UAVObjHandle obj); +static void updateObject(UAVObjHandle obj, int32_t eventType); static int32_t addObject(UAVObjHandle obj); static int32_t setUpdatePeriod(UAVObjHandle obj, int32_t updatePeriodMs); static void processObjEvent(UAVObjEvent * ev); @@ -158,32 +158,34 @@ static void registerObject(UAVObjHandle obj) addObject(obj); // Setup object for telemetry updates - updateObject(obj); + updateObject(obj, EV_NONE); } /** * Update object's queue connections and timer, depending on object's settings * \param[in] obj Object to updates */ -static void updateObject(UAVObjHandle obj) +static void updateObject(UAVObjHandle obj, int32_t eventType) { UAVObjMetadata metadata; + UAVObjUpdateMode updateMode; int32_t eventMask; // Get metadata UAVObjGetMetadata(obj, &metadata); + updateMode = UAVObjGetTelemetryUpdateMode(&metadata); // Setup object depending on update mode - if (metadata.telemetryUpdateMode == UPDATEMODE_PERIODIC) { + if (updateMode == UPDATEMODE_PERIODIC) { // Set update period setUpdatePeriod(obj, metadata.telemetryUpdatePeriod); // Connect queue - eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; + eventMask = EV_UPDATED_PERIODIC | EV_UPDATED_MANUAL | EV_UPDATE_REQ; if (UAVObjIsMetaobject(obj)) { eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) } UAVObjConnectQueue(obj, priorityQueue, eventMask); - } else if (metadata.telemetryUpdateMode == UPDATEMODE_ONCHANGE) { + } else if (updateMode == UPDATEMODE_ONCHANGE) { // Set update period setUpdatePeriod(obj, 0); // Connect queue @@ -192,7 +194,22 @@ static void updateObject(UAVObjHandle obj) eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) } UAVObjConnectQueue(obj, priorityQueue, eventMask); - } else if (metadata.telemetryUpdateMode == UPDATEMODE_MANUAL) { + } else if (updateMode == UPDATEMODE_THROTTLED) { + if ((eventType == EV_UPDATED_PERIODIC) || (eventType == EV_NONE)) { + // If we received a periodic update, we can change back to update on change + eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ; + // Set update period on initialization and metadata change + if (eventType == EV_NONE) + setUpdatePeriod(obj, metadata.telemetryUpdatePeriod); + } else { + // Otherwise, we just received an object update, so switch to periodic for the timeout period to prevent more updates + eventMask = EV_UPDATED_PERIODIC | EV_UPDATED_MANUAL | EV_UPDATE_REQ; + } + if (UAVObjIsMetaobject(obj)) { + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + } + UAVObjConnectQueue(obj, priorityQueue, eventMask); + } else if (updateMode == UPDATEMODE_MANUAL) { // Set update period setUpdatePeriod(obj, 0); // Connect queue @@ -201,11 +218,6 @@ static void updateObject(UAVObjHandle obj) eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) } UAVObjConnectQueue(obj, priorityQueue, eventMask); - } else if (metadata.telemetryUpdateMode == UPDATEMODE_NEVER) { - // Set update period - setUpdatePeriod(obj, 0); - // Disconnect queue - UAVObjDisconnectQueue(obj, priorityQueue); } } @@ -215,6 +227,7 @@ static void updateObject(UAVObjHandle obj) static void processObjEvent(UAVObjEvent * ev) { UAVObjMetadata metadata; + UAVObjUpdateMode updateMode; FlightTelemetryStatsData flightStats; int32_t retries; int32_t success; @@ -226,16 +239,17 @@ static void processObjEvent(UAVObjEvent * ev) } else { // Only process event if connected to GCS or if object FlightTelemetryStats is updated FlightTelemetryStatsGet(&flightStats); + // Get object metadata + UAVObjGetMetadata(ev->obj, &metadata); + updateMode = UAVObjGetTelemetryUpdateMode(&metadata); if (flightStats.Status == FLIGHTTELEMETRYSTATS_STATUS_CONNECTED || ev->obj == FlightTelemetryStatsHandle()) { - // Get object metadata - UAVObjGetMetadata(ev->obj, &metadata); // Act on event retries = 0; success = -1; - if (ev->event == EV_UPDATED || ev->event == EV_UPDATED_MANUAL) { + if (ev->event == EV_UPDATED || ev->event == EV_UPDATED_MANUAL || ((ev->event == EV_UPDATED_PERIODIC) && (updateMode != UPDATEMODE_THROTTLED))) { // Send update to GCS (with retries) while (retries < MAX_RETRIES && success == -1) { - success = UAVTalkSendObject(uavTalkCon, ev->obj, ev->instId, metadata.telemetryAcked, REQ_TIMEOUT_MS); // call blocks until ack is received or timeout + success = UAVTalkSendObject(uavTalkCon, ev->obj, ev->instId, UAVObjGetTelemetryAcked(&metadata), REQ_TIMEOUT_MS); // call blocks until ack is received or timeout ++retries; } // Update stats @@ -257,9 +271,13 @@ static void processObjEvent(UAVObjEvent * ev) } // If this is a metaobject then make necessary telemetry updates if (UAVObjIsMetaobject(ev->obj)) { - updateObject(UAVObjGetLinkedObj(ev->obj)); // linked object will be the actual object the metadata are for + updateObject(UAVObjGetLinkedObj(ev->obj), EV_NONE); // linked object will be the actual object the metadata are for } } + if((updateMode == UPDATEMODE_THROTTLED) && !UAVObjIsMetaobject(ev->obj)) { + // If this is UPDATEMODE_THROTTLED, the event mask changes on every event. + updateObject(ev->obj, ev->event); + } } } @@ -376,7 +394,7 @@ static int32_t addObject(UAVObjHandle obj) // Add object for periodic updates ev.obj = obj; ev.instId = UAVOBJ_ALL_INSTANCES; - ev.event = EV_UPDATED_MANUAL; + ev.event = EV_UPDATED_PERIODIC; return EventPeriodicQueueCreate(&ev, queue, 0); } @@ -394,7 +412,7 @@ static int32_t setUpdatePeriod(UAVObjHandle obj, int32_t updatePeriodMs) // Add object for periodic updates ev.obj = obj; ev.instId = UAVOBJ_ALL_INSTANCES; - ev.event = EV_UPDATED_MANUAL; + ev.event = EV_UPDATED_PERIODIC; return EventPeriodicQueueUpdate(&ev, queue, updatePeriodMs); } @@ -513,8 +531,8 @@ static void updateTelemetryStats() */ static void updateSettings() { + if (telemetryPort) { - // Retrieve settings uint8_t speed; HwSettingsTelemetrySpeedGet(&speed); diff --git a/flight/Modules/TxPID/txpid.c b/flight/Modules/TxPID/txpid.c index cff9c1d9e..fd350c0d4 100644 --- a/flight/Modules/TxPID/txpid.c +++ b/flight/Modules/TxPID/txpid.c @@ -275,6 +275,9 @@ static void updatePIDs(UAVObjEvent* ev) case TXPIDSETTINGS_PIDS_YAWATTITUDEILIMIT: needsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT], value); break; + case TXPIDSETTINGS_PIDS_GYROTAU: + needsUpdate |= update(&stab.GyroTau, value); + break; default: PIOS_Assert(0); } diff --git a/flight/OpenPilot/Makefile.posix b/flight/OpenPilot/Makefile.posix deleted file mode 100644 index 5fbc66b4b..000000000 --- a/flight/OpenPilot/Makefile.posix +++ /dev/null @@ -1,665 +0,0 @@ - ##### - # Project: OpenPilot - # - # - # Makefile for OpenPilot project build PiOS and the AP. - # - # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. - # - # - # This program is free software; you can redistribute it and/or modify - # it under the terms of the GNU General Public License as published by - # the Free Software Foundation; either version 3 of the License, or - # (at your option) any later version. - # - # This program is distributed in the hope that it will be useful, but - # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - # for more details. - # - # You should have received a copy of the GNU General Public License along - # with this program; if not, write to the Free Software Foundation, Inc., - # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - ##### - - -# Set developer code and compile options -# Set to YES to compile for debugging -DEBUG ?= YES - -# Include objects that are just nice information to show -DIAGNOSTICS ?= YES - -# Set to YES to use the Servo output pins for debugging via scope or logic analyser -ENABLE_DEBUG_PINS ?= NO - -# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs -ENABLE_AUX_UART ?= NO - -# -USE_BOOTLOADER ?= NO - - -# Set to YES when using Code Sourcery toolchain -CODE_SOURCERY ?= NO - -# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe) -TCHAIN_PREFIX ?= "" - -# Remove command is different for Code Sourcery on Windows -REMOVE_CMD ?= rm - -FLASH_TOOL = OPENOCD - -# YES enables -mthumb option to flags for source-files listed -# in SRC and CPPSRC -USE_THUMB_MODE = YES - -# List of modules to include -OPTMODULES = CameraStab GPS -MODULES = Telemetry Actuator Stabilization Guidance ManualControl -#MODULES = Telemetry ManualControl Actuator Attitude Stabilization -#MODULES = Telemetry Example -#MODULES = Telemetry MK/MKSerial -PYMODULES = FlightPlan - -#MODULES += Osd/OsdEtStd - - -# MCU name, submodel and board -# - MCU used for compiler-option (-mtune) -# - MODEL used for linker-script name (-T) and passed as define -# - BOARD just passed as define (optional) -MCU = i686 -#CHIP = STM32F103RET -#BOARD = STM3210E_OP -MODEL = HD -ifeq ($(USE_BOOTLOADER), YES) -BOOT_MODEL = $(MODEL)_BL - -else -BOOT_MODEL = $(MODEL)_NB -endif - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR = ../../build/sitl_posix - -# Target file name (without extension). -TARGET = OpenPilot - -# Paths -OPSYSTEM = ./System -OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../UAVTalk -OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../UAVObjects -OPUAVOBJINC = $(OPUAVOBJ)/inc -OPTESTS = ./Tests -OPMODULEDIR = ../Modules -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = $(FLIGHTLIB)/inc -PIOS = ../PiOS.posix -PIOSINC = $(PIOS)/inc -PIOSPOSIX = $(PIOS)/posix -APPLIBDIR = $(PIOSPOSIX)/Libraries -RTOSDIR = $(APPLIBDIR)/FreeRTOS -RTOSSRCDIR = $(RTOSDIR)/Source -RTOSINCDIR = $(RTOSSRCDIR)/include -DOXYGENDIR = ../Doc/Doxygen -AHRSBOOTLOADER = ../Bootloaders/AHRS/ -AHRSBOOTLOADERINC = $(AHRSBOOTLOADER)/inc -PYMITE = $(FLIGHTLIB)/PyMite -PYMITELIB = $(PYMITE)/lib -PYMITEPLAT = $(PYMITE)/platform/openpilot_sitl -PYMITETOOLS = $(PYMITE)/tools -PYMITEVM = $(PYMITE)/vm -PYMITEINC = $(PYMITEVM) -PYMITEINC += $(PYMITEPLAT) -PYMITEINC += $(OUTDIR) -FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib -FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans - -UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight -UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python - -# List C source files here. (C dependencies are automatically generated.) -# use file-extension c for "c-only"-files - -MODNAMES = $(notdir ${MODULES}) -MODNAMES += $(notdir ${OPTMODULES}) - -ifndef TESTAPP - -## PyMite files -SRC += $(OUTDIR)/pmlib_img.c -SRC += $(OUTDIR)/pmlib_nat.c -SRC += $(OUTDIR)/pmlibusr_img.c -SRC += $(OUTDIR)/pmlibusr_nat.c -PYSRC += $(wildcard ${PYMITEVM}/*.c) -PYSRC += $(wildcard ${PYMITEPLAT}/*.c) -PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} -SRC += $(PYSRC) - -## MODULES -SRC += ${foreach MOD, ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} -SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} -SRC += ${OUTDIR}/InitMods.c -## OPENPILOT CORE: -SRC += ${OPMODULEDIR}/System/systemmod.c -SRC += $(OPSYSTEM)/openpilot.c -SRC += $(OPSYSTEM)/pios_board_posix.c -SRC += $(OPSYSTEM)/alarms.c -SRC += $(OPUAVTALK)/uavtalk.c -SRC += $(OPUAVOBJ)/uavobjectmanager.c -SRC += $(OPUAVOBJ)/eventdispatcher.c -SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c -else -## TESTCODE -SRC += $(OPTESTS)/test_common.c -SRC += $(OPTESTS)/$(TESTAPP).c -endif - - - -## UAVOBJECTS -ifndef TESTAPP -#include $(UAVOBJSYNTHDIR)/Makefile.inc -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) -CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) -endif - -## PIOS Hardware (posix) -SRC += $(PIOSPOSIX)/pios_crc.c -SRC += $(PIOSPOSIX)/pios_sys.c -SRC += $(PIOSPOSIX)/pios_led.c -SRC += $(PIOSPOSIX)/pios_irq.c -SRC += $(PIOSPOSIX)/pios_delay.c -SRC += $(PIOSPOSIX)/pios_sdcard.c -SRC += $(PIOSPOSIX)/pios_udp.c -SRC += $(PIOSPOSIX)/pios_com.c -SRC += $(PIOSPOSIX)/pios_servo.c -SRC += $(PIOSPOSIX)/pios_wdg.c -SRC += $(PIOSPOSIX)/pios_debug.c - -SRC += $(PIOSPOSIX)/pios_rcvr.c - -## Libraries for flight calculations -SRC += $(FLIGHTLIB)/fifo_buffer.c -SRC += $(FLIGHTLIB)/WorldMagModel.c -SRC += $(FLIGHTLIB)/CoordinateConversions.c -SRC += $(FLIGHTLIB)/taskmonitor.c -## RTOS and RTOS Portable -SRC += $(RTOSSRCDIR)/list.c -SRC += $(RTOSSRCDIR)/queue.c -UNAME := $(shell uname) -ifeq ($(UNAME), Linux) - SRC += $(RTOSSRCDIR)/tasks_linux.c - SRC += $(RTOSSRCDIR)/portable/GCC/Posix/port_linux.c -else - SRC += $(RTOSSRCDIR)/tasks_posix.c - SRC += $(RTOSSRCDIR)/portable/GCC/Posix/port_posix.c -endif -SRC += $(RTOSSRCDIR)/portable/MemMang/heap_3.c - - - -# List C source files here which must be compiled in ARM-Mode (no -mthumb). -# use file-extension c for "c-only"-files -## just for testing, timer.c could be compiled in thumb-mode too -SRCARM = - -# List C++ source files here. -# use file-extension .cpp for C++-files (not .C) -CPPSRC = - -# List C++ source files here which must be compiled in ARM-Mode. -# use file-extension .cpp for C++-files (not .C) -#CPPSRCARM = $(TARGET).cpp -CPPSRCARM = - - -# List any extra directories to look for include files here. -# Each directory must be seperated by a space. -EXTRAINCDIRS = $(OPSYSTEM) -EXTRAINCDIRS += $(OPSYSTEMINC) -EXTRAINCDIRS += $(OPUAVTALK) -EXTRAINCDIRS += $(OPUAVTALKINC) -EXTRAINCDIRS += $(OPUAVOBJ) -EXTRAINCDIRS += $(OPUAVOBJINC) -EXTRAINCDIRS += $(UAVOBJSYNTHDIR) -EXTRAINCDIRS += $(PIOS) -EXTRAINCDIRS += $(PIOSINC) -EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(PIOSPOSIX) -EXTRAINCDIRS += $(RTOSINCDIR) -EXTRAINCDIRS += $(APPLIBDIR) -EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Posix -EXTRAINCDIRS += $(PYMITEINC) - -EXTRAINCDIRS += ${foreach MOD, ${PYMODULES} ${OPTMODULES} ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc - - -# List any extra directories to look for library files here. -# Also add directories where the linker should search for -# includes from linker-script to the list -# Each directory must be seperated by a space. -EXTRA_LIBDIRS = - -# Extra Libraries -# Each library-name must be seperated by a space. -# i.e. to link with libxyz.a, libabc.a and libefsl.a: -# EXTRA_LIBS = xyz abc efsl -# for newlib-lpc (file: libnewlibc-lpc.a): -# EXTRA_LIBS = newlib-lpc -EXTRA_LIBS = - -# Path to Linker-Scripts -LINKERSCRIPTPATH = $(PIOSSTM32F10X) - -# Optimization level, can be [0, 1, 2, 3, s]. -# 0 = turn off optimization. s = optimize for size. -# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) - -ifeq ($(DEBUG),YES) -OPT = 0 -else -OPT = s -endif - -# Output format. (can be ihex or binary or both) -# binary to create a load-image in raw-binary format i.e. for SAM-BA, -# ihex to create a load-image in Intel hex format -#LOADFORMAT = ihex -#LOADFORMAT = binary -LOADFORMAT = both - -# Debugging format. -#DEBUGF = dwarf-2 - -# Place project-specific -D (define) and/or -# -U options for C here. -ifeq ($(ENABLE_DEBUG_PINS), YES) -CDEFS += -DPIOS_ENABLE_DEBUG_PINS -endif -ifeq ($(ENABLE_AUX_UART), YES) -CDEFS += -DPIOS_ENABLE_AUX_UART -endif -ifeq ($(USE_BOOTLOADER), YES) -CDEFS += -DUSE_BOOTLOADER -endif - - - -# Compiler flag to set the C Standard level. -# c89 - "ANSI" C -# gnu89 - c89 plus GCC extensions -# c99 - ISO C99 standard (not yet fully implemented) -# gnu99 - c99 plus GCC extensions -CSTANDARD = -std=gnu99 - -#----- - -# Compiler flags. - -# -g*: generate debugging information -# -O*: optimization level -# -f...: tuning, see GCC manual and avr-libc documentation -# -Wall...: warning level -# -Wa,...: tell GCC to pass this to the assembler. -# -adhlns...: create assembler listing -# -# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) - -ifeq ($(DEBUG),YES) -CFLAGS = -g$(DEBUGF) -DDEBUG -endif - -ifeq ($(DIAGNOSTICS),YES) -CFLAGS = -DDIAGNOSTICS -endif - -CFLAGS += $(CFLAGS_UAVOBJECTS) -CFLAGS += -DARCH_POSIX -CFLAGS += -O$(OPT) -CFLAGS += -mtune=$(MCU) -CFLAGS += $(CDEFS) -CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. - -CFLAGS += -fomit-frame-pointer -ifeq ($(CODE_SOURCERY), YES) -CFLAGS += -fpromote-loop-indices -endif - -CFLAGS += -Wall -CFLAGS += -Werror -# Compiler flags to generate dependency files: -CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d - -# flags only for C -#CONLYFLAGS += -Wnested-externs -CONLYFLAGS += $(CSTANDARD) - -# Assembler flags. -# -Wa,...: tell GCC to pass this to the assembler. -# -ahlns: create listing -ASFLAGS = -mtune=$(MCU) -I. -x assembler-with-cpp -ASFLAGS += $(ADEFS) -ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) -ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) - -MATH_LIB = -lm - -# Linker flags. -# -Wl,...: tell GCC to pass this to linker. -# -Map: create map file -# --cref: add cross reference to map file -LDFLAGS += -lpthread -LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) -LDFLAGS += -lc -LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) -LDFLAGS += $(MATH_LIB) -LDFLAGS += -lc -lgcc - - - - -# Define programs and commands. -CC = $(TCHAIN_PREFIX)gcc -CPP = $(TCHAIN_PREFIX)g++ -AR = $(TCHAIN_PREFIX)ar -OBJCOPY = $(TCHAIN_PREFIX)objcopy -OBJDUMP = $(TCHAIN_PREFIX)objdump -SIZE = $(TCHAIN_PREFIX)size -NM = $(TCHAIN_PREFIX)nm -REMOVE = $(REMOVE_CMD) -f -PYTHON = python -###SHELL = sh -###COPY = cp - - - -# Define Messages -# English -MSG_ERRORS_NONE = Errors: none -MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote} -MSG_END = ${quote}-------- end --------${quote} -MSG_MODINIT = ${quote}**** Generating ModInit.c${quote} -MSG_SIZE_BEFORE = ${quote}Size before:${quote} -MSG_SIZE_AFTER = ${quote}Size after build:${quote} -MSG_LOAD_FILE = ${quote}Creating load file:${quote} -MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote} -MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote} -MSG_LINKING = ${quote}**** Linking :${quote} -MSG_COMPILING = ${quote}**** Compiling C :${quote} -MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote} -MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote} -MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote} -MSG_ASSEMBLING = ${quote}**** Assembling:${quote} -MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote} -MSG_CLEANING = ${quote}Cleaning project:${quote} -MSG_FORMATERROR = ${quote}Can not handle output-format${quote} -MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote} -MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote} -MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote} - -# List of all source files. -ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) -# List of all source files without directory and file-extension. -ALLSRCBASE = $(notdir $(basename $(ALLSRC))) - -# Define all object files. -ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) - -# Define all listing files (used for make clean). -LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) -# Define all depedency-files (used for make clean). -DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) - -elf: $(OUTDIR)/$(TARGET).elf -lss: $(OUTDIR)/$(TARGET).lss -sym: $(OUTDIR)/$(TARGET).sym -hex: $(OUTDIR)/$(TARGET).hex -bin: $(OUTDIR)/$(TARGET).bin - -# Default target. -#all: begin gccversion sizebefore build sizeafter finished end -#all: begin gencode gccversion build sizeafter finished end -all: elf - -ifeq ($(LOADFORMAT),ihex) -build: elf hex lss sym -else -ifeq ($(LOADFORMAT),binary) -build: elf bin lss sym -else -ifeq ($(LOADFORMAT),both) -build: elf hex bin lss sym -else -$(error "$(MSG_FORMATERROR) $(FORMAT)") -endif -endif -endif - -# Test if quotes are needed for the echo-command -result = ${shell echo "test"} -ifeq (${result}, test) - quote = ' -else - quote = -endif - -# Generate code for module initialization -${OUTDIR}/InitMods.c: Makefile.posix - @echo ${MSG_MODINIT} - @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Start(void);}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c - -# Generate code for PyMite -${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) - @echo $(MSG_PYMITEINIT) $(call toprel, $@) - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) - @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py - -# Eye candy. -begin: -## @echo - @echo $(MSG_BEGIN) - -finished: -## @echo $(MSG_ERRORS_NONE) - -end: - @echo $(MSG_END) -## @echo - -# Display sizes of sections. -ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf -##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf -sizebefore: -# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi - -sizeafter: -# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi - @echo $(MSG_SIZE_AFTER) - $(ELFSIZE) - -# Display compiler version information. -gccversion : - @$(CC) --version -# @echo $(ALLOBJ) - -# Program the device. -ifeq ($(USE_BOOTLOADER), YES) -# Program the device with OP Upload Tool". -program: $(OUTDIR)/$(TARGET).bin - @echo ${quote}Programming with OP Upload Tool${quote} - ../../ground/src/experimental/upload-build-desktop/debug/OPUploadTool -d 0 -p $(OUTDIR)/$(TARGET).bin -else -ifeq ($(FLASH_TOOL),OPENOCD) -# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script". -program: $(OUTDIR)/$(TARGET).elf - @echo ${quote}Programming with OPENOCD${quote} - $(OOCD_EXE) $(OOCD_CL) -endif -endif - -# Create final output file (.hex) from ELF output file. -%.hex: %.elf -## @echo - @echo $(MSG_LOAD_FILE) $@ - $(OBJCOPY) -O ihex $< $@ - -# Create final output file (.bin) from ELF output file. -%.bin: %.elf -## @echo - @echo $(MSG_LOAD_FILE) $@ - $(OBJCOPY) -O binary $< $@ - -# Create extended listing file/disassambly from ELF output file. -# using objdump testing: option -C -%.lss: %.elf -## @echo - @echo $(MSG_EXTENDED_LISTING) $@ - $(OBJDUMP) -h -S -C -r $< > $@ -# $(OBJDUMP) -x -S $< > $@ - -# Create a symbol table from ELF output file. -%.sym: %.elf -## @echo - @echo $(MSG_SYMBOL_TABLE) $@ - $(NM) -n $< > $@ - -# Link: create ELF output file from object files. -.SECONDARY : $(TARGET).elf -.PRECIOUS : $(ALLOBJ) -%.elf: $(ALLOBJ) - @echo $(MSG_LINKING) $@ -# use $(CC) for C-only projects or $(CPP) for C++-projects: - $(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) -# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) - - -# Assemble: create object files from assembler source files. -define ASSEMBLE_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_ASSEMBLING) $$< to $$@ - $(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@ -endef -$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) - -# Assemble: create object files from assembler source files. ARM-only -define ASSEMBLE_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_ASSEMBLING_ARM) $$< to $$@ - $(CC) -c $$(ASFLAGS) $$< -o $$@ -endef -$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) - - -# Compile: create object files from C source files. -define COMPILE_C_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILING) $$< to $$@ - $(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ -endef -$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) - -# Compile: create object files from C source files. ARM-only -define COMPILE_C_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILING_ARM) $$< to $$@ - $(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ -endef -$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) - - -# Compile: create object files from C++ source files. -define COMPILE_CPP_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILINGCPP) $$< to $$@ - $(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ -endef -$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) - -# Compile: create object files from C++ source files. ARM-only -define COMPILE_CPP_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILINGCPP_ARM) $$< to $$@ - $(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ -endef -$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) - - -# Compile: create assembler files from C source files. ARM/Thumb -$(SRC:.c=.s) : %.s : %.c - @echo $(MSG_ASMFROMC) $< to $@ - $(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ - -# Compile: create assembler files from C source files. ARM only -$(SRCARM:.c=.s) : %.s : %.c - @echo $(MSG_ASMFROMC_ARM) $< to $@ - $(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ - -# Generate Doxygen documents -docs: - doxygen $(DOXYGENDIR)/doxygen.cfg - -# Target: clean project. -clean: begin clean_list finished end - -clean_list : -## @echo - @echo $(MSG_CLEANING) - $(REMOVE) $(OUTDIR)/$(TARGET).map - $(REMOVE) $(OUTDIR)/$(TARGET).elf - $(REMOVE) $(OUTDIR)/$(TARGET).hex - $(REMOVE) $(OUTDIR)/$(TARGET).bin - $(REMOVE) $(OUTDIR)/$(TARGET).sym - $(REMOVE) $(OUTDIR)/$(TARGET).lss - $(REMOVE) $(wildcard $(OUTDIR)/*.c) - $(REMOVE) $(wildcard $(OUTDIR)/*.h) - $(REMOVE) $(ALLOBJ) - $(REMOVE) $(LSTFILES) - $(REMOVE) $(DEPFILES) - $(REMOVE) $(SRC:.c=.s) - $(REMOVE) $(SRCARM:.c=.s) - $(REMOVE) $(CPPSRC:.cpp=.s) - $(REMOVE) $(CPPSRCARM:.cpp=.s) - - -# Create output files directory -# all known MS Windows OS define the ComSpec environment variable -ifdef ComSpec -$(shell md $(OUTDIR) 2>NUL) -else -$(shell mkdir $(OUTDIR) 2>/dev/null) -endif - -# Include the dependency files. -ifdef ComSpec --include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) -else --include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) -endif - - - -# Listing of phony targets. -.PHONY : all begin finish end sizebefore sizeafter gccversion \ -build elf hex bin lss sym clean clean_list program - diff --git a/flight/OpenPilot/Makefile.win32 b/flight/OpenPilot/Makefile.win32 deleted file mode 100644 index 261e4abfb..000000000 --- a/flight/OpenPilot/Makefile.win32 +++ /dev/null @@ -1,637 +0,0 @@ - ##### - # Project: OpenPilot - # - # - # Makefile for OpenPilot project build PiOS and the AP. - # - # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. - # - # - # This program is free software; you can redistribute it and/or modify - # it under the terms of the GNU General Public License as published by - # the Free Software Foundation; either version 3 of the License, or - # (at your option) any later version. - # - # This program is distributed in the hope that it will be useful, but - # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - # for more details. - # - # You should have received a copy of the GNU General Public License along - # with this program; if not, write to the Free Software Foundation, Inc., - # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - ##### - - -# Set developer code and compile options -# Set to YES to compile for debugging -DEBUG ?= YES - -# Set to YES to use the Servo output pins for debugging via scope or logic analyser -ENABLE_DEBUG_PINS ?= NO - -# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs -ENABLE_AUX_UART ?= NO - -# -USE_BOOTLOADER ?= NO - - -# Set to YES when using Code Sourcery toolchain -CODE_SOURCERY ?= NO - -# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe) -TCHAIN_PREFIX ?= mingw32- - -# Remove command is different for Code Sourcery on Windows -REMOVE_CMD ?= rm - -FLASH_TOOL = OPENOCD - -# YES enables -mthumb option to flags for source-files listed -# in SRC and CPPSRC -USE_THUMB_MODE = YES - -# List of modules to include -MODULES = Telemetry Actuator Stabilization Guidance ManualControl FlightPlan -#MODULES = Telemetry GPS ManualControl Actuator Altitude Attitude Stabilization -#MODULES = Telemetry Example -#MODULES = Telemetry MK/MKSerial - -#MODULES += Osd/OsdEtStd - - -# MCU name, submodel and board -# - MCU used for compiler-option (-mtune) -# - MODEL used for linker-script name (-T) and passed as define -# - BOARD just passed as define (optional) -MCU = i686 -#CHIP = STM32F103RET -#BOARD = STM3210E_OP -ifeq ($(USE_BOOTLOADER), YES) -MODEL = HD_BL - -else -MODEL = HD_NB -endif - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR = ../../build/sitl_win32 - -# Target file name (without extension). -TARGET = OpenPilot - -# Paths -OPSYSTEM = ./System -OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../UAVTalk -OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../UAVObjects -OPUAVOBJINC = $(OPUAVOBJ)/inc -OPTESTS = ./Tests -OPMODULEDIR = ../Modules -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = ../Libraries/inc -PIOS = ../PiOS.win32 -PIOSINC = $(PIOS)/inc -PIOSWIN32 = $(PIOS)/win32 -APPLIBDIR = $(PIOSWIN32)/Libraries -RTOSDIR = $(APPLIBDIR)/FreeRTOS -RTOSSRCDIR = $(RTOSDIR)/Source -RTOSINCDIR = $(RTOSSRCDIR)/include -DOXYGENDIR = ../Doc/Doxygen -PYMITE = $(FLIGHTLIB)/PyMite -PYMITELIB = $(PYMITE)/lib -PYMITEPLAT = $(PYMITE)/platform/openpilot_sitl -PYMITETOOLS = $(PYMITE)/tools -PYMITEVM = $(PYMITE)/vm -PYMITEINC = $(PYMITEVM) -PYMITEINC += $(PYMITEPLAT) -PYMITEINC += $(OUTDIR) -FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib -FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans -UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight - -# List C source files here. (C dependencies are automatically generated.) -# use file-extension c for "c-only"-files - -MODNAMES = $(notdir ${MODULES}) - -ifndef TESTAPP - -## PyMite files -SRC += $(OUTDIR)/pmlib_img.c -SRC += $(OUTDIR)/pmlib_nat.c -SRC += $(OUTDIR)/pmlibusr_img.c -SRC += $(OUTDIR)/pmlibusr_nat.c -SRC += $(wildcard ${PYMITEVM}/*.c) -SRC += $(wildcard ${PYMITEPLAT}/*.c) - -## MODULES -SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} -SRC += ${OUTDIR}/InitMods.c -## OPENPILOT CORE: -SRC += ${OPMODULEDIR}/System/systemmod.c -SRC += $(OPSYSTEM)/openpilot.c -SRC += $(OPSYSTEM)/pios_board_posix.c -SRC += $(OPSYSTEM)/alarms.c -SRC += $(OPSYSTEM)/taskmonitor.c -SRC += $(OPUAVTALK)/uavtalk.c -SRC += $(OPUAVOBJ)/uavobjectmanager.c -SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c -SRC += $(OPUAVOBJ)/eventdispatcher.c -SRC += $(FLIGHTLIB)/CoordinateConversions.c - -else -## TESTCODE -SRC += $(OPTESTS)/test_common.c -SRC += $(OPTESTS)/$(TESTAPP).c -endif - - -## UAVOBJECTS -ifndef TESTAPP -#include $(UAVOBJSYNTHDIR)/Makefile.inc -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) -CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) -endif - -## PIOS Hardware (win32) -SRC += $(PIOSWIN32)/pios_sys.c -SRC += $(PIOSWIN32)/pios_led.c -SRC += $(PIOSWIN32)/pios_delay.c -SRC += $(PIOSWIN32)/pios_sdcard.c -SRC += $(PIOSWIN32)/pios_udp.c -SRC += $(PIOSWIN32)/pios_com.c -SRC += $(PIOSWIN32)/pios_servo.c -SRC += $(PIOSWIN32)/pios_wdg.c -SRC += $(PIOSWIN32)/pios_crc.c -# -## RTOS -SRC += $(RTOSSRCDIR)/list.c -SRC += $(RTOSSRCDIR)/queue.c -SRC += $(RTOSSRCDIR)/tasks.c -# -## RTOS Portable -SRC += $(RTOSSRCDIR)/portable/GCC/Win32/port.c -SRC += $(RTOSSRCDIR)/portable/MemMang/heap_3.c - - -# List C source files here which must be compiled in ARM-Mode (no -mthumb). -# use file-extension c for "c-only"-files -## just for testing, timer.c could be compiled in thumb-mode too -SRCARM = - -# List C++ source files here. -# use file-extension .cpp for C++-files (not .C) -CPPSRC = - -# List C++ source files here which must be compiled in ARM-Mode. -# use file-extension .cpp for C++-files (not .C) -#CPPSRCARM = $(TARGET).cpp -CPPSRCARM = - - -# List any extra directories to look for include files here. -# Each directory must be seperated by a space. -EXTRAINCDIRS = $(PIOSINC) -EXTRAINCDIRS += $(OPSYSTEM) -EXTRAINCDIRS += $(OPSYSTEMINC) -EXTRAINCDIRS += $(OPUAVTALK) -EXTRAINCDIRS += $(OPUAVTALKINC) -EXTRAINCDIRS += $(OPUAVOBJ) -EXTRAINCDIRS += $(OPUAVOBJINC) -EXTRAINCDIRS += $(PIOS) -EXTRAINCDIRS += $(PIOSWIN32) -EXTRAINCDIRS += $(MININIDIR) -EXTRAINCDIRS += $(RTOSINCDIR) -EXTRAINCDIRS += $(APPLIBDIR) -EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Win32 -EXTRAINCDIRS += $(FLIGHTLIB) -EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(PYMITEINC) -EXTRAINCDIRS += $(UAVOBJSYNTHDIR) - -EXTRAINCDIRS += ${foreach MOD, ${MODULES}, ${OPMODULEDIR}/${MOD}/inc} ${OPMODULEDIR}/System/inc - - -# List any extra directories to look for library files here. -# Also add directories where the linker should search for -# includes from linker-script to the list -# Each directory must be seperated by a space. -EXTRA_LIBDIRS = - -# Extra Libraries -# Each library-name must be seperated by a space. -# i.e. to link with libxyz.a, libabc.a and libefsl.a: -# EXTRA_LIBS = xyz abc efsl -# for newlib-lpc (file: libnewlibc-lpc.a): -# EXTRA_LIBS = newlib-lpc -EXTRA_LIBS = WS2_32 Winmm - -# Path to Linker-Scripts -LINKERSCRIPTPATH = $(PIOSSTM32F10X) - -# Optimization level, can be [0, 1, 2, 3, s]. -# 0 = turn off optimization. s = optimize for size. -# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) - -ifeq ($(DEBUG),YES) -OPT = 0 -else -OPT = s -endif - -# Output format. (can be ihex or binary or both) -# binary to create a load-image in raw-binary format i.e. for SAM-BA, -# ihex to create a load-image in Intel hex format -#LOADFORMAT = ihex -#LOADFORMAT = binary -LOADFORMAT = both - -# Debugging format. -#DEBUGF = dwarf-2 - -# Place project-specific -D (define) and/or -# -U options for C here. -ifeq ($(ENABLE_DEBUG_PINS), YES) -CDEFS += -DPIOS_ENABLE_DEBUG_PINS -endif -ifeq ($(ENABLE_AUX_UART), YES) -CDEFS += -DPIOS_ENABLE_AUX_UART -endif -ifeq ($(USE_BOOTLOADER), YES) -CDEFS += -DUSE_BOOTLOADER -endif - - - -# Compiler flag to set the C Standard level. -# c89 - "ANSI" C -# gnu89 - c89 plus GCC extensions -# c99 - ISO C99 standard (not yet fully implemented) -# gnu99 - c99 plus GCC extensions -CSTANDARD = -std=gnu99 - -#----- - -# Compiler flags. - -# -g*: generate debugging information -# -O*: optimization level -# -f...: tuning, see GCC manual and avr-libc documentation -# -Wall...: warning level -# -Wa,...: tell GCC to pass this to the assembler. -# -adhlns...: create assembler listing -# -# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) - -ifeq ($(DEBUG),YES) -CFLAGS = -g -endif - -CFLAGS += $(CFLAGS_UAVOBJECTS) -CFLAGS += -DARCH_WIN32 -CFLAGS += -O$(OPT) -CFLAGS += -mtune=$(MCU) -CFLAGS += $(CDEFS) -CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. - -CFLAGS += -fomit-frame-pointer -ifeq ($(CODE_SOURCERY), YES) -CFLAGS += -fpromote-loop-indices -endif - -CFLAGS += -Wall -CFLAGS += -Werror -# Compiler flags to generate dependency files: -CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d - -# flags only for C -#CONLYFLAGS += -Wnested-externs -CONLYFLAGS += $(CSTANDARD) - -# Assembler flags. -# -Wa,...: tell GCC to pass this to the assembler. -# -ahlns: create listing -ASFLAGS = -mtune=$(MCU) -I. -x assembler-with-cpp -ASFLAGS += $(ADEFS) -ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) -ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) - -MATH_LIB = -lm - -# Linker flags. -# -Wl,...: tell GCC to pass this to linker. -# -Map: create map file -# --cref: add cross reference to map file -#LDFLAGS += -lpthread -LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) -#LDFLAGS += -lc -LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) -LDFLAGS += $(MATH_LIB) -LDFLAGS += -lgcc - - - - -# Define programs and commands. -CC = $(TCHAIN_PREFIX)gcc -CPP = $(TCHAIN_PREFIX)g++ -AR = ar -OBJCOPY = objcopy -OBJDUMP = objdump -SIZE = size -NM = nm -REMOVE = $(REMOVE_CMD) -f -PYTHON = python -###SHELL = sh -###COPY = cp - - - -# Define Messages -# English -MSG_ERRORS_NONE = Errors: none -MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote} -MSG_END = ${quote}-------- end --------${quote} -MSG_MODINIT = ${quote}**** Generating ModInit.c${quote} -MSG_SIZE_BEFORE = ${quote}Size before:${quote} -MSG_SIZE_AFTER = ${quote}Size after build:${quote} -MSG_LOAD_FILE = ${quote}Creating load file:${quote} -MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote} -MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote} -MSG_LINKING = ${quote}**** Linking :${quote} -MSG_COMPILING = ${quote}**** Compiling C :${quote} -MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote} -MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote} -MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote} -MSG_ASSEMBLING = ${quote}**** Assembling:${quote} -MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote} -MSG_CLEANING = ${quote}Cleaning project:${quote} -MSG_FORMATERROR = ${quote}Can not handle output-format${quote} -MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote} -MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote} -MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote} - -# List of all source files. -ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) -# List of all source files without directory and file-extension. -ALLSRCBASE = $(notdir $(basename $(ALLSRC))) - -# Define all object files. -ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) - -# Define all listing files (used for make clean). -LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) -# Define all depedency-files (used for make clean). -DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) - -elf: $(OUTDIR)/$(TARGET).elf -lss: $(OUTDIR)/$(TARGET).lss -sym: $(OUTDIR)/$(TARGET).sym -hex: $(OUTDIR)/$(TARGET).hex -bin: $(OUTDIR)/$(TARGET).bin -exe: $(OUTDIR)/$(TARGET).exe - -# Default target. -#all: begin gccversion sizebefore build sizeafter finished end -#all: begin gccversion build sizeafter finished end -#all: elf -all: gencode exe - -ifeq ($(LOADFORMAT),ihex) -build: elf hex lss sym -else -ifeq ($(LOADFORMAT),binary) -build: elf bin lss sym -else -ifeq ($(LOADFORMAT),both) -build: elf hex bin lss sym -else -$(error "$(MSG_FORMATERROR) $(FORMAT)") -endif -endif -endif - -# Test if quotes are needed for the echo-command -result = ${shell echo "test"} -ifeq (${result}, test) - quote = ' -else - quote = -endif - -# Generate intermediate code -gencode: ${OUTDIR}/InitMods.c $(OUTDIR)/pmlib_img.c $(OUTDIR)/pmlib_nat.c $(OUTDIR)/pmlibusr_img.c $(OUTDIR)/pmlibusr_nat.c $(OUTDIR)/pmfeatures.h - -${OUTDIR}/InitMods.c: Makefile.win32 - @echo ${MSG_MODINIT} - @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c - -#Generate code for PyMite -$(OUTDIR)/pmlib_img.c $(OUTDIR)/pmlib_nat.c $(OUTDIR)/pmlibusr_img.c $(OUTDIR)/pmlibusr_nat.c $(OUTDIR)/pmfeatures.h $(OPMODULEDIR)/FlightPlan/flightplan.c: $(wildcard $(PYMITELIB)/*.py) $(wildcard $(PYMITEPLAT)/*.py) $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(FLIGHTPLANS)/*.py) - @echo ${MSG_PYMITEINIT} - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) - @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py - -# Eye candy. -begin: -## @echo - @echo $(MSG_BEGIN) - -finished: -## @echo $(MSG_ERRORS_NONE) - -end: - @echo $(MSG_END) -## @echo - -# Display sizes of sections. -ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf -##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf -sizebefore: -# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi - -sizeafter: -# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi - @echo $(MSG_SIZE_AFTER) - $(ELFSIZE) - -# Display compiler version information. -gccversion : - @$(CC) --version -# @echo $(ALLOBJ) - -# Program the device. -ifeq ($(FLASH_TOOL),OPENOCD) -# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script". -program: $(OUTDIR)/$(TARGET).elf - @echo ${quote}Programming with OPENOCD${quote} - $(OOCD_EXE) $(OOCD_CL) -endif - -# Create final output file (.hex) from ELF output file. -%.hex: %.elf -## @echo - @echo $(MSG_LOAD_FILE) $@ - $(OBJCOPY) -O ihex $< $@ - -# Create final output file (.bin) from ELF output file. -%.bin: %.elf -## @echo - @echo $(MSG_LOAD_FILE) $@ - $(OBJCOPY) -O binary $< $@ - -# Create extended listing file/disassambly from ELF output file. -# using objdump testing: option -C -%.lss: %.elf -## @echo - @echo $(MSG_EXTENDED_LISTING) $@ - $(OBJDUMP) -h -S -C -r $< > $@ -# $(OBJDUMP) -x -S $< > $@ - -# Create a symbol table from ELF output file. -%.sym: %.elf -## @echo - @echo $(MSG_SYMBOL_TABLE) $@ - $(NM) -n $< > $@ - -# Link: create ELF output file from object files. -.SECONDARY : $(TARGET).elf -.PRECIOUS : $(ALLOBJ) -%.elf: $(ALLOBJ) - @echo $(MSG_LINKING) $@ -# use $(CC) for C-only projects or $(CPP) for C++-projects: - $(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) -# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) - -# Link: create EXE output file from object files. -.SECONDARY : $(TARGET).exe -.PRECIOUS : $(ALLOBJ) -%.exe: $(ALLOBJ) - @echo $(MSG_LINKING) $@ -# use $(CC) for C-only projects or $(CPP) for C++-projects: - $(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) -# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) - -# Assemble: create object files from assembler source files. -define ASSEMBLE_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_ASSEMBLING) $$< to $$@ - $(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@ -endef -$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) - -# Assemble: create object files from assembler source files. ARM-only -define ASSEMBLE_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_ASSEMBLING_ARM) $$< to $$@ - $(CC) -c $$(ASFLAGS) $$< -o $$@ -endef -$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) - - -# Compile: create object files from C source files. -define COMPILE_C_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILING) $$< to $$@ - $(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ -endef -$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) - -# Compile: create object files from C source files. ARM-only -define COMPILE_C_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILING_ARM) $$< to $$@ - $(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ -endef -$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) - - -# Compile: create object files from C++ source files. -define COMPILE_CPP_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILINGCPP) $$< to $$@ - $(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ -endef -$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) - -# Compile: create object files from C++ source files. ARM-only -define COMPILE_CPP_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILINGCPP_ARM) $$< to $$@ - $(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ -endef -$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) - - -# Compile: create assembler files from C source files. ARM/Thumb -$(SRC:.c=.s) : %.s : %.c - @echo $(MSG_ASMFROMC) $< to $@ - $(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ - -# Compile: create assembler files from C source files. ARM only -$(SRCARM:.c=.s) : %.s : %.c - @echo $(MSG_ASMFROMC_ARM) $< to $@ - $(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ - -# Generate Doxygen documents -docs: - doxygen $(DOXYGENDIR)/doxygen.cfg - -# Target: clean project. -clean: begin clean_list finished end - -clean_list : -## @echo - @echo $(MSG_CLEANING) - $(REMOVE) $(OUTDIR)/$(TARGET).map - $(REMOVE) $(OUTDIR)/$(TARGET).elf - $(REMOVE) $(OUTDIR)/$(TARGET).hex - $(REMOVE) $(OUTDIR)/$(TARGET).bin - $(REMOVE) $(OUTDIR)/$(TARGET).sym - $(REMOVE) $(OUTDIR)/$(TARGET).lss - $(REMOVE) $(OUTDIR)/$(TARGET).exe - $(REMOVE) $(ALLOBJ) - $(REMOVE) $(LSTFILES) - $(REMOVE) $(DEPFILES) - $(REMOVE) $(SRC:.c=.s) - $(REMOVE) $(SRCARM:.c=.s) - $(REMOVE) $(CPPSRC:.cpp=.s) - $(REMOVE) $(CPPSRCARM:.cpp=.s) - - -# Create output files directory -# all known MS Windows OS define the ComSpec environment variable -ifdef ComSpec -$(shell md $(OUTDIR) 2>NUL) -else -$(shell mkdir $(OUTDIR) 2>/dev/null) -endif - -# Include the dependency files. -ifdef ComSpec --include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) -else --include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) -endif - - - -# Listing of phony targets. -.PHONY : all begin gencode finish end sizebefore sizeafter gccversion \ -build exe elf hex bin lss sym clean clean_list program - diff --git a/flight/OpenPilot/System/inc/pios_config_posix.h b/flight/OpenPilot/System/inc/pios_config_posix.h deleted file mode 100644 index 1148a497c..000000000 --- a/flight/OpenPilot/System/inc/pios_config_posix.h +++ /dev/null @@ -1,78 +0,0 @@ -/** - ****************************************************************************** - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * Central compile time config for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_CONFIG_POSIX_H -#define PIOS_CONFIG_POSIX_H - - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SDCARD -#define PIOS_INCLUDE_FREERTOS -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_GPS -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_TELEMETRY_RF -#define PIOS_INCLUDE_UDP -#define PIOS_INCLUDE_SERVO -#define PIOS_INCLUDE_RCVR - -#define PIOS_RCVR_MAX_CHANNELS 12 -#define PIOS_RCVR_MAX_DEVS 3 - -/* Defaults for Logging */ -#define LOG_FILENAME "PIOS.LOG" -#define STARTUP_LOG_ENABLED 1 - -#define TELEM_QUEUE_SIZE 20 -#define PIOS_TELEM_STACK_SIZE 2048 - -/* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 4000 -#define HEAP_LIMIT_CRITICAL 1000 -#define IRQSTACK_LIMIT_WARNING 150 -#define IRQSTACK_LIMIT_CRITICAL 80 -#define CPULOAD_LIMIT_WARNING 80 -#define CPULOAD_LIMIT_CRITICAL 95 - -/* Stabilization options */ -#define PIOS_QUATERNION_STABILIZATION - -/* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 4000 -#define HEAP_LIMIT_CRITICAL 1000 -#define IRQSTACK_LIMIT_WARNING 150 -#define IRQSTACK_LIMIT_CRITICAL 80 -#define CPULOAD_LIMIT_WARNING 80 -#define CPULOAD_LIMIT_CRITICAL 95 - -/* GPS options */ -#define PIOS_GPS_SETS_HOMELOCATION - -#endif /* PIOS_CONFIG_POSIX_H */ diff --git a/flight/OpenPilot/System/openpilot.c b/flight/OpenPilot/System/openpilot.c deleted file mode 100644 index affe65926..000000000 --- a/flight/OpenPilot/System/openpilot.c +++ /dev/null @@ -1,338 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @brief These files are the core system files of OpenPilot. - * They are the ground layer just above PiOS. In practice, OpenPilot actually starts - * in the main() function of openpilot.c - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @brief This is where the OP firmware starts. Those files also define the compile-time - * options of the firmware. - * @{ - * @file openpilot.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sets up and runs main OpenPilot tasks. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* OpenPilot Includes */ -#include "openpilot.h" -#include "uavobjectsinit.h" -#include "systemmod.h" - -/* Task Priorities */ -#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) - -/* Global Variables */ - -/* Local Variables */ -#define INCLUDE_TEST_TASKS 0 -#if INCLUDE_TEST_TASKS -static uint8_t sdcard_available; -#endif -FILEINFO File; -char Buffer[1024]; -uint32_t Cache; - -/* Function Prototypes */ -#if INCLUDE_TEST_TASKS -static void TaskTick(void *pvParameters); -static void TaskTesting(void *pvParameters); -static void TaskHIDTest(void *pvParameters); -static void TaskServos(void *pvParameters); -static void TaskSDCard(void *pvParameters); -#endif -int32_t CONSOLE_Parse(uint8_t port, char c); -void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value); - -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void Stack_Change(void); -static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change"))); - -/** -* OpenPilot Main function: -* -* Initialize PiOS
-* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
-* Start FreeRTOS Scheduler (vTaskStartScheduler)
-* If something goes wrong, blink LED1 and LED2 every 100ms -* -*/ -int main() -{ - /* NOTE: Do NOT modify the following start-up sequence */ - /* Any new initialization functions should be added in OpenPilotInit() */ - - /* Brings up System using CMSIS functions, enables the LEDs. */ - PIOS_SYS_Init(); - - /* Architecture dependant Hardware and - * core subsystem initialisation - * (see pios_board.c for your arch) - * */ - PIOS_Board_Init(); - - /* Initialize modules */ - MODULE_INITIALISE_ALL - -#if INCLUDE_TEST_TASKS - /* Create test tasks */ - xTaskCreate(TaskTesting, (signed portCHAR *)"Testing", configMINIMAL_STACK_SIZE , NULL, 4, NULL); - xTaskCreate(TaskHIDTest, (signed portCHAR *)"HIDTest", configMINIMAL_STACK_SIZE , NULL, 3, NULL); - xTaskCreate(TaskServos, (signed portCHAR *)"Servos", configMINIMAL_STACK_SIZE , NULL, 3, NULL); - xTaskCreate(TaskSDCard, (signed portCHAR *)"SDCard", configMINIMAL_STACK_SIZE, NULL, (tskIDLE_PRIORITY + 2), NULL); -#endif - - /* swap the stack to use the IRQ stack (does nothing in sim mode) */ - Stack_Change_Weak(); - - /* Start the FreeRTOS scheduler which should never returns.*/ - vTaskStartScheduler(); - - /* If all is well we will never reach here as the scheduler will now be running. */ - - /* Do some indication to user that something bad just happened */ - while (1) { -#if defined(PIOS_LED_HEARTBEAT) - PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); -#endif /* PIOS_LED_HEARTBEAT */ - PIOS_DELAY_WaitmS(100); - } -} - - -#if INCLUDE_TEST_TASKS -static void TaskTesting(void *pvParameters) -{ - portTickType xDelay = 250 / portTICK_RATE_MS; - portTickType xTimeout = 10 / portTICK_RATE_MS; - - //PIOS_BMP085_Init(); - - for(;;) - { - /* This blocks the task until the BMP085 EOC */ - /* - PIOS_BMP085_StartADC(TemperatureConv); - xSemaphoreTake(PIOS_BMP085_EOC, xTimeout); - PIOS_BMP085_ReadADC(); - PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u\r", PIOS_BMP085_GetTemperature()); - - PIOS_BMP085_StartADC(PressureConv); - xSemaphoreTake(PIOS_BMP085_EOC, xTimeout); - PIOS_BMP085_ReadADC(); - PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u\r", PIOS_BMP085_GetPressure()); - */ - -#if defined(PIOS_INCLUDE_DSM) - PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_DSM_Get(0), PIOS_DSM_Get(1), PIOS_DSM_Get(2), PIOS_DSM_Get(3), PIOS_DSM_Get(4), PIOS_DSM_Get(5), PIOS_DSM_Get(6), PIOS_DSM_Get(7)); -#endif -#if defined(PIOS_INCLUDE_SBUS) - PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_SBus_Get(0), PIOS_SBus_Get(1), PIOS_SBus_Get(2), PIOS_SBus_Get(3), PIOS_SBus_Get(4), PIOS_SBus_Get(5), PIOS_SBus_Get(6), PIOS_SBus_Get(7)); -#endif -#if defined(PIOS_INCLUDE_PWM) - PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u uS\r", PIOS_PWM_Get(0), PIOS_PWM_Get(1), PIOS_PWM_Get(2), PIOS_PWM_Get(3), PIOS_PWM_Get(4), PIOS_PWM_Get(5), PIOS_PWM_Get(6), PIOS_PWM_Get(7)); -#endif -#if defined(PIOS_INCLUDE_PPM) - PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u uS\r", PIOS_PPM_Get(0), PIOS_PPM_Get(1), PIOS_PPM_Get(2), PIOS_PPM_Get(3), PIOS_PPM_Get(4), PIOS_PPM_Get(5), PIOS_PPM_Get(6), PIOS_PPM_Get(7)); -#endif - - /* This blocks the task until there is something on the buffer */ - /*xSemaphoreTake(PIOS_USART1_Buffer, portMAX_DELAY); - int32_t len = PIOS_COM_ReceiveBufferUsed(COM_USART1); - for(int32_t i = 0; i < len; i++) { - PIOS_COM_SendFormattedString(COM_DEBUG_USART, ">%c\r", PIOS_COM_ReceiveBuffer(COM_USART1)); - }*/ - - //int32_t state = PIOS_USB_CableConnected(); - //PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "State: %d\r", state); - - //PIOS_I2C_Transfer(I2C_Write_WithoutStop, 0x57, (uint8_t *)50, 1); - - /* Test ADC pins */ - //temp = ((1.43 - ((Vsense / 4096) * 3.3)) / 4.3) + 25; - //uint32_t vsense = PIOS_ADC_PinGet(0); - //uint32_t Temp = (1.42 - vsense * 3.3 / 4096) * 1000 / 4.35 + 25; - //PIOS_COM_SendFormattedString(COM_DEBUG_USART, "Temp: %d, CS_I: %d, CS_V: %d, 5v: %d\r", PIOS_ADC_PinGet(0), PIOS_ADC_PinGet(1), PIOS_ADC_PinGet(2), PIOS_ADC_PinGet(3)); - //PIOS_COM_SendFormattedString(COM_DEBUG_USART, "AUX1: %d, AUX2: %d, AUX3: %d\r", PIOS_ADC_PinGet(4), PIOS_ADC_PinGet(5), PIOS_ADC_PinGet(6)); - - vTaskDelay(xDelay); - } -} -#endif - -#if INCLUDE_TEST_TASKS -static void TaskHIDTest(void *pvParameters) -{ - uint8_t byte; - uint8_t line_buffer[128]; - uint16_t line_ix = 0; - - for(;;) - { - /* HID Loopback Test */ -#if 0 - if(PIOS_COM_ReceiveBufferUsed(COM_USB_HID) != 0) { - byte = PIOS_COM_ReceiveBuffer(COM_USB_HID); - if(byte == '\r' || byte == '\n' || byte == 0) { - PIOS_COM_SendFormattedString(COM_USB_HID, "RX: %s\r", line_buffer); - PIOS_COM_SendFormattedString(COM_DEBUG_USART, "RX: %s\r", line_buffer); - line_ix = 0; - } else if(line_ix < sizeof(line_buffer)) { - line_buffer[line_ix++] = byte; - line_buffer[line_ix] = 0; - } - } -#endif - - /* HID Loopback Test */ - if(PIOS_COM_ReceiveBufferUsed(COM_USART2) != 0) { - byte = PIOS_COM_ReceiveBuffer(COM_USART2); -#if 0 - if(byte == '\r' || byte == '\n' || byte == 0) { - PIOS_COM_SendFormattedString(COM_DEBUG_USART, "RX: %s\r", line_buffer); - line_ix = 0; - } else if(line_ix < sizeof(line_buffer)) { - line_buffer[line_ix++] = byte; - line_buffer[line_ix] = 0; - } -#endif - PIOS_COM_SendChar(COM_DEBUG_USART, (char)byte); - } - } -} -#endif - -#if INCLUDE_TEST_TASKS -static void TaskServos(void *pvParameters) -{ - /* For testing servo outputs */ - portTickType xDelay; - - /* Used to test servos, cycles all servos from one side to the other */ - for(;;) { - /*xDelay = 250 / portTICK_RATE_MS; - PIOS_Servo_Set(0, 2000); - vTaskDelay(xDelay); - PIOS_Servo_Set(1, 2000); - vTaskDelay(xDelay); - PIOS_Servo_Set(2, 2000); - vTaskDelay(xDelay); - PIOS_Servo_Set(3, 2000); - vTaskDelay(xDelay); - PIOS_Servo_Set(4, 2000); - vTaskDelay(xDelay); - PIOS_Servo_Set(5, 2000); - vTaskDelay(xDelay); - PIOS_Servo_Set(6, 2000); - vTaskDelay(xDelay); - PIOS_Servo_Set(7, 2000); - vTaskDelay(xDelay); - - PIOS_Servo_Set(7, 1000); - vTaskDelay(xDelay); - PIOS_Servo_Set(6, 1000); - vTaskDelay(xDelay); - PIOS_Servo_Set(5, 1000); - vTaskDelay(xDelay); - PIOS_Servo_Set(4, 1000); - vTaskDelay(xDelay); - PIOS_Servo_Set(3, 1000); - vTaskDelay(xDelay); - PIOS_Servo_Set(2, 1000); - vTaskDelay(xDelay); - PIOS_Servo_Set(1, 1000); - vTaskDelay(xDelay); - PIOS_Servo_Set(0, 1000); - vTaskDelay(xDelay);*/ - - xDelay = 1 / portTICK_RATE_MS; - for(int i = 1000; i < 2000; i++) { - PIOS_Servo_Set(0, i); - PIOS_Servo_Set(1, i); - PIOS_Servo_Set(2, i); - PIOS_Servo_Set(3, i); - PIOS_Servo_Set(4, i); - PIOS_Servo_Set(5, i); - PIOS_Servo_Set(6, i); - PIOS_Servo_Set(7, i); - vTaskDelay(xDelay); - } - for(int i = 2000; i > 1000; i--) { - PIOS_Servo_Set(0, i); - PIOS_Servo_Set(1, i); - PIOS_Servo_Set(2, i); - PIOS_Servo_Set(3, i); - PIOS_Servo_Set(4, i); - PIOS_Servo_Set(5, i); - PIOS_Servo_Set(6, i); - PIOS_Servo_Set(7, i); - vTaskDelay(xDelay); - } - } -} -#endif - -#if INCLUDE_TEST_TASKS -static void TaskSDCard(void *pvParameters) -{ - uint16_t second_delay_ctr = 0; - portTickType xLastExecutionTime; - - /* Initialise the xLastExecutionTime variable on task entry */ - xLastExecutionTime = xTaskGetTickCount(); - - for(;;) { - vTaskDelayUntil(&xLastExecutionTime, 1 / portTICK_RATE_MS); - - /* Each second: */ - /* Check if SD card is available */ - /* High-speed access if SD card was previously available */ - if(++second_delay_ctr >= 1000) { - second_delay_ctr = 0; - - uint8_t prev_sdcard_available = sdcard_available; - sdcard_available = PIOS_SDCARD_CheckAvailable(prev_sdcard_available); - - if(sdcard_available && !prev_sdcard_available) { - /* SD Card has been connected! */ - /* Switch to mass storage device */ - MSD_Init(0); - } else if(!sdcard_available && prev_sdcard_available) { - /* Re-init USB for HID */ - PIOS_USB_Init(1); - /* SD Card disconnected! */ - } - } - - /* Each millisecond: */ - /* Handle USB access if device is available */ - if(sdcard_available) { - MSD_Periodic_mS(); - } - } -} -#endif -/** - * @} - * @} - */ - diff --git a/flight/OpenPilot/System/pios_board.c b/flight/OpenPilot/System/pios_board.c deleted file mode 100644 index ad9c13083..000000000 --- a/flight/OpenPilot/System/pios_board.c +++ /dev/null @@ -1,440 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * - * @file pios_board.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board specific static initializers for hardware for the OpenPilot board. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Pull in the board-specific static HW definitions. - * Including .c files is a bit ugly but this allows all of - * the HW definitions to be const and static to limit their - * scope. - * - * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE - */ -#include "board_hw_defs.c" - -#include -#include -#include -#include -#include - -//#define I2C_DEBUG_PIN 0 -//#define USART_GPS_DEBUG_PIN 1 - -/* One slot per selectable receiver group. - * eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS - * NOTE: No slot in this map for NONE. - */ -uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; - -#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192 -#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192 - -#define PIOS_COM_GPS_RX_BUF_LEN 96 - -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192 - -#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 -#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 - -uint32_t pios_com_telem_rf_id; -uint32_t pios_com_telem_usb_id; -uint32_t pios_com_vcp_id; -uint32_t pios_com_gps_id; -uint32_t pios_com_aux_id; -uint32_t pios_com_dsm_id; - -#include "ahrs_spi_comm.h" - -/** - * PIOS_Board_Init() - * initializes all the core subsystems on this specific hardware - * called from System/openpilot.c - */ -void PIOS_Board_Init(void) { - - /* Remap AFIO pin */ - //GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); - -#ifdef PIOS_DEBUG_ENABLE_DEBUG_PINS - PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); -#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */ - - /* Delay system */ - PIOS_DELAY_Init(); - -#if defined(PIOS_INCLUDE_SPI) - /* Set up the SPI interface to the SD card */ - if (PIOS_SPI_Init(&pios_spi_sdcard_id, &pios_spi_sdcard_cfg)) { - PIOS_Assert(0); - } - - /* Enable and mount the SDCard */ - PIOS_SDCARD_Init(pios_spi_sdcard_id); - PIOS_SDCARD_MountFS(0); -#endif /* PIOS_INCLUDE_SPI */ - - /* Initialize UAVObject libraries */ - EventDispatcherInitialize(); - UAVObjInitialize(); - -#if defined(PIOS_INCLUDE_RTC) - /* Initialize the real-time clock and its associated tick */ - PIOS_RTC_Init(&pios_rtc_main_cfg); -#endif - -#if defined(PIOS_INCLUDE_LED) - PIOS_LED_Init(&pios_led_cfg); -#endif /* PIOS_INCLUDE_LED */ - - HwSettingsInitialize(); - - PIOS_WDG_Init(); - - /* Initialize the alarms library */ - AlarmsInitialize(); - - PIOS_IAP_Init(); - uint16_t boot_count = PIOS_IAP_ReadBootCount(); - if (boot_count < 3) { - PIOS_IAP_WriteBootCount(++boot_count); - AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT); - } else { - /* Too many failed boot attempts, force hwsettings to defaults */ - HwSettingsSetDefaults(HwSettingsHandle(), 0); - AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); - } - - /* Initialize the task monitor library */ - TaskMonitorInitialize(); - - /* Set up pulse timers */ - PIOS_TIM_InitClock(&tim_1_cfg); - PIOS_TIM_InitClock(&tim_3_cfg); - PIOS_TIM_InitClock(&tim_5_cfg); - PIOS_TIM_InitClock(&tim_4_cfg); - PIOS_TIM_InitClock(&tim_8_cfg); - - /* Prepare the AHRS Comms upper layer protocol */ - AhrsInitComms(); - - /* Set up the SPI interface to the AHRS */ - if (PIOS_SPI_Init(&pios_spi_ahrs_id, &pios_spi_ahrs_cfg)) { - PIOS_Assert(0); - } - - /* Bind the AHRS comms layer to the AHRS SPI link */ - AhrsConnect(pios_spi_ahrs_id); - -#if defined(PIOS_INCLUDE_USB) - /* Initialize board specific USB data */ - PIOS_USB_BOARD_DATA_Init(); - - /* Flags to determine if various USB interfaces are advertised */ - bool usb_hid_present = false; - bool usb_cdc_present = false; - - uint8_t hwsettings_usb_devicetype; - HwSettingsUSB_DeviceTypeGet(&hwsettings_usb_devicetype); - - switch (hwsettings_usb_devicetype) { - case HWSETTINGS_USB_DEVICETYPE_HIDONLY: - if (PIOS_USB_DESC_HID_ONLY_Init()) { - PIOS_Assert(0); - } - usb_hid_present = true; - break; - case HWSETTINGS_USB_DEVICETYPE_HIDVCP: - if (PIOS_USB_DESC_HID_CDC_Init()) { - PIOS_Assert(0); - } - usb_hid_present = true; - usb_cdc_present = true; - break; - case HWSETTINGS_USB_DEVICETYPE_VCPONLY: - break; - default: - PIOS_Assert(0); - } - - uint32_t pios_usb_id; - PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); - -#if defined(PIOS_INCLUDE_USB_CDC) - /* Configure the USB VCP port */ - uint8_t hwsettings_usb_vcpport; - HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport); - - if (!usb_cdc_present) { - /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ - hwsettings_usb_vcpport = HWSETTINGS_USB_VCPPORT_DISABLED; - } - - switch (hwsettings_usb_vcpport) { - case HWSETTINGS_USB_VCPPORT_DISABLED: - break; - case HWSETTINGS_USB_VCPPORT_USBTELEMETRY: -#if defined(PIOS_INCLUDE_COM) - { - uint32_t pios_usb_cdc_id; - if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - case HWSETTINGS_USB_VCPPORT_COMBRIDGE: -#if defined(PIOS_INCLUDE_COM) - { - uint32_t pios_usb_cdc_id; - if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, - tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - - } -#endif /* PIOS_INCLUDE_COM */ - break; - } -#endif /* PIOS_INCLUDE_USB_CDC */ - -#if defined(PIOS_INCLUDE_USB_HID) - /* Configure the usb HID port */ - uint8_t hwsettings_usb_hidport; - HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport); - - if (!usb_hid_present) { - /* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */ - hwsettings_usb_hidport = HWSETTINGS_USB_HIDPORT_DISABLED; - } - - switch (hwsettings_usb_hidport) { - case HWSETTINGS_USB_HIDPORT_DISABLED: - break; - case HWSETTINGS_USB_HIDPORT_USBTELEMETRY: -#if defined(PIOS_INCLUDE_COM) - { - uint32_t pios_usb_hid_id; - if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - } - -#endif /* PIOS_INCLUDE_USB_HID */ - -#endif /* PIOS_INCLUDE_USB */ - - /* Configure the main IO port */ - uint8_t hwsettings_op_mainport; - HwSettingsOP_MainPortGet(&hwsettings_op_mainport); - - switch (hwsettings_op_mainport) { - case HWSETTINGS_OP_MAINPORT_DISABLED: - break; - case HWSETTINGS_OP_MAINPORT_TELEMETRY: -#if defined(PIOS_INCLUDE_TELEMETRY_RF) - { - uint32_t pios_usart_telem_rf_id; - if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) { - PIOS_Assert(0); - } - - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id, - rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_TELEMETRY_RF */ - break; - } - - /* Configure the flexi port */ - uint8_t hwsettings_op_flexiport; - HwSettingsOP_FlexiPortGet(&hwsettings_op_flexiport); - - switch (hwsettings_op_flexiport) { - case HWSETTINGS_OP_FLEXIPORT_DISABLED: - break; - case HWSETTINGS_OP_FLEXIPORT_GPS: -#if defined(PIOS_INCLUDE_GPS) - { - uint32_t pios_usart_gps_id; - if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) { - PIOS_Assert(0); - } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); - PIOS_Assert(rx_buffer); - if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, - rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, - NULL, 0)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_GPS */ - break; - } - -#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS - PIOS_Servo_Init(&pios_servo_cfg); -#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */ - - PIOS_ADC_Init(); - PIOS_GPIO_Init(); - - /* Configure the rcvr port */ - uint8_t hwsettings_rcvrport; - HwSettingsOP_RcvrPortGet(&hwsettings_rcvrport); - - - switch (hwsettings_rcvrport) { - case HWSETTINGS_OP_RCVRPORT_DISABLED: - break; - case HWSETTINGS_OP_RCVRPORT_DEBUG: - /* Not supported yet */ - break; - case HWSETTINGS_OP_RCVRPORT_DSM2: - case HWSETTINGS_OP_RCVRPORT_DSMX10BIT: - case HWSETTINGS_OP_RCVRPORT_DSMX11BIT: -#if defined(PIOS_INCLUDE_DSM) - { - enum pios_dsm_proto proto; - switch (hwsettings_rcvrport) { - case HWSETTINGS_OP_RCVRPORT_DSM2: - proto = PIOS_DSM_PROTO_DSM2; - break; - case HWSETTINGS_OP_RCVRPORT_DSMX10BIT: - proto = PIOS_DSM_PROTO_DSMX10BIT; - break; - case HWSETTINGS_OP_RCVRPORT_DSMX11BIT: - proto = PIOS_DSM_PROTO_DSMX11BIT; - break; - default: - PIOS_Assert(0); - break; - } - - uint32_t pios_usart_dsm_id; - if (PIOS_USART_Init(&pios_usart_dsm_id, &pios_usart_dsm_cfg)) { - PIOS_Assert(0); - } - - uint32_t pios_dsm_id; - if (PIOS_DSM_Init(&pios_dsm_id, - &pios_dsm_cfg, - &pios_usart_com_driver, - pios_usart_dsm_id, - proto, 0)) { - PIOS_Assert(0); - } - - uint32_t pios_dsm_rcvr_id; - if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT] = pios_dsm_rcvr_id; - } -#endif - break; - case HWSETTINGS_OP_RCVRPORT_PWM: -#if defined(PIOS_INCLUDE_PWM) - { - uint32_t pios_pwm_id; - PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); - - uint32_t pios_pwm_rcvr_id; - if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; - } -#endif /* PIOS_INCLUDE_PWM */ - break; - case HWSETTINGS_OP_RCVRPORT_PPM: -#if defined(PIOS_INCLUDE_PPM) - { - uint32_t pios_ppm_id; - PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); - - uint32_t pios_ppm_rcvr_id; - if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; - } -#endif /* PIOS_INCLUDE_PPM */ - break; - } - -#if defined(PIOS_INCLUDE_I2C) - if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) { - PIOS_Assert(0); - } -#endif /* PIOS_INCLUDE_I2C */ - - /* Make sure we have at least one telemetry link configured or else fail initialization */ - PIOS_Assert(pios_com_telem_rf_id || pios_com_telem_usb_id); -} - -/** - * @} - */ diff --git a/flight/OpenPilot/Tests/test_BMP085.c b/flight/OpenPilot/Tests/test_BMP085.c deleted file mode 100644 index 6bee6a1e6..000000000 --- a/flight/OpenPilot/Tests/test_BMP085.c +++ /dev/null @@ -1,100 +0,0 @@ -/** - ****************************************************************************** - * - * @file openpilot.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sets up and runs main OpenPilot tasks. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* OpenPilot Includes */ -#include "openpilot.h" - -/* Task Priorities */ - -/* Global Variables */ - -/* Local Variables */ - -/* Function Prototypes */ -static void TaskTesting(void *pvParameters); - -/** -* Test Main function -*/ -int main() -{ - // Init - PIOS_SYS_Init(); - PIOS_DELAY_Init(); - PIOS_COM_Init(); - PIOS_ADC_Init(); - PIOS_I2C_Init(); - xTaskCreate(TaskTesting, (signed portCHAR *)"Test", configMINIMAL_STACK_SIZE , NULL, 1, NULL); - - // Start the FreeRTOS scheduler - vTaskStartScheduler(); - - // Should not get here - PIOS_DEBUG_Assert(0); - - return 0; -} - -static void TaskTesting(void *pvParameters) -{ - portTickType xDelay = 500 / portTICK_RATE_MS; - portTickType xTimeout = 10 / portTICK_RATE_MS; - - PIOS_BMP085_Init(); - - for(;;) - { - PIOS_LED_Toggle(LED2); - - int16_t temp; - int32_t pressure; - - PIOS_BMP085_StartADC(TemperatureConv); - xSemaphoreTake(PIOS_BMP085_EOC, xTimeout); - PIOS_BMP085_ReadADC(); - - PIOS_BMP085_StartADC(PressureConv); - xSemaphoreTake(PIOS_BMP085_EOC, xTimeout); - PIOS_BMP085_ReadADC(); - - temp = PIOS_BMP085_GetTemperature(); - pressure = PIOS_BMP085_GetPressure(); - - PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_TELEM_RF, "%3u,%4u\r", temp, pressure); - - vTaskDelay(xDelay); - } -} - -/** -* Idle hook function -*/ -void vApplicationIdleHook(void) -{ - /* Called when the scheduler has no tasks to run */ - - -} diff --git a/flight/OpenPilot/Tests/test_cpuload.c b/flight/OpenPilot/Tests/test_cpuload.c deleted file mode 100644 index a85f5f698..000000000 --- a/flight/OpenPilot/Tests/test_cpuload.c +++ /dev/null @@ -1,89 +0,0 @@ -/** - ****************************************************************************** - * - * @file test_cpuload.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Calibration for the CPU load calculation - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/** - * This file is used to calculate the number of counts we get when - * the CPU is fully idle (no load). This is used by systemmod.c to - * calculate the CPU load. This calibration should be run whenever - * changes are made in the FreeRTOS configuration or on the compiler - * optimisation parameters. - */ - -#include "openpilot.h" - -// Local constants -#define BENCHMARK_DURATION_MS 10000 - -// Local functions -static void testTask(void *pvParameters); - -// Variables -static uint32_t idleCounter = 0; -static uint32_t idleCounterClear = 0; - -int main() -{ - PIOS_SYS_Init(); - - // Create test task - xTaskCreate(testTask, (signed portCHAR *)"Test", 1000 , NULL, 1, NULL); - - // Start the FreeRTOS scheduler - vTaskStartScheduler(); - return 0; -} - -static void testTask(void *pvParameters) -{ - uint32_t countsPerSecond = 0; - - while (1) - { - // Delay until enough required test duration - vTaskDelay( BENCHMARK_DURATION_MS / portTICK_RATE_MS ); - - // Calculate counts per second, set breakpoint here - countsPerSecond = idleCounter / (BENCHMARK_DURATION_MS/1000); - - // Reset and start again - do not clear idleCounter directly! - // SET BREAKPOINT HERE and read the countsPerSecond variable - // this should be used to update IDLE_COUNTS_PER_SEC_AT_NO_LOAD in systemmod.c - idleCounterClear = 1; - } -} - -void vApplicationIdleHook(void) -{ - /* Called when the scheduler has no tasks to run */ - if (idleCounterClear == 0) - { - ++idleCounter; - } - else - { - idleCounter = 0; - idleCounterClear = 0; - } -} diff --git a/flight/OpenPilot/Tests/test_i2c_PCF8570.c b/flight/OpenPilot/Tests/test_i2c_PCF8570.c deleted file mode 100644 index 6a2a17faf..000000000 --- a/flight/OpenPilot/Tests/test_i2c_PCF8570.c +++ /dev/null @@ -1,282 +0,0 @@ -/** - ****************************************************************************** - * - * @file openpilot.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sets up ans runs main OpenPilot tasks. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* - * I2C Test: communicate with external PCF8570 ram chip - * For this test to function, PCF8570 chips need to be attached to the I2C port - * - * Blinking Blue LED: No errors detected, test continues - * Blinking Red LED: Error detected, test stopped - * - */ - -/* OpenPilot Includes */ -#include "openpilot.h" - -//#define USE_DEBUG_PINS - -#define DEVICE_1_ADDRESS 0x50 -#define DEVICE_2_ADDRESS 0x51 - -#ifdef USE_DEBUG_PINS - #define DEBUG_PIN_TASK1_WAIT 0 - #define DEBUG_PIN_TASK1_LOCKED 1 - #define DEBUG_PIN_TASK2_WAIT 2 - #define DEBUG_PIN_TASK2_LOCKED 3 - #define DEBUG_PIN_TRANSFER 4 - #define DEBUG_PIN_IDLE 6 - #define DEBUG_PIN_ERROR 7 - #define DebugPinHigh(x) PIOS_DEBUG_PinHigh(x) - #define DebugPinLow(x) PIOS_DEBUG_PinLow(x) -#else - #define DebugPinHigh(x) - #define DebugPinLow(x) -#endif - - - -#define MAX_LOCK_WAIT 2 // Time in ms that a thread can normally block I2C - -/* Task Priorities */ -#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) - - -/* Global Variables */ - -/* Local Variables */ - -/* Function Prototypes */ -static void Task1(void *pvParameters); -static void Task2(void *pvParameters); - - -/** -* OpenPilot Main function -*/ -int main() -{ - // Init - PIOS_SYS_Init(); - PIOS_DEBUG_Init(); - PIOS_DELAY_Init(); - PIOS_COM_Init(); - PIOS_USB_Init(0); - PIOS_I2C_Init(); - - // Both leds off - PIOS_LED_Off(LED1); - PIOS_LED_Off(LED2); - - // Create task - xTaskCreate(Task1, (signed portCHAR *)"Task1", 1024 , NULL, 1, NULL); - xTaskCreate(Task2, (signed portCHAR *)"Task2", 1024 , NULL, 2, NULL); - - - // Start the FreeRTOS scheduler - vTaskStartScheduler(); - - /* If all is well we will never reach here as the scheduler will now be running. */ - /* If we do get here, it will most likely be because we ran out of heap space. */ - return 0; -} - -static void OnError(void) -{ - PIOS_LED_Off(LED1); - while(1) - { - DebugPinHigh(DEBUG_PIN_ERROR); - PIOS_LED_Toggle(LED2); - vTaskDelay(50 / portTICK_RATE_MS); - DebugPinLow(DEBUG_PIN_ERROR); - } -} -// -// This is a low priority task that will continuously access one I2C device -// Frequently it will release the I2C device so that others can also use I2C -// -static void Task1(void *pvParameters) -{ - int i = 0; - - - if (PIOS_I2C_LockDevice(MAX_LOCK_WAIT / portTICK_RATE_MS)) - { - if (PIOS_I2C_Transfer(I2C_Write, DEVICE_1_ADDRESS<<1, (uint8_t*)"\x20\xB0\xB1\xB2", 4) != 0) - OnError(); - PIOS_I2C_UnlockDevice(); - } - else - { - OnError(); - } - - for(;;) - { - i++; - if (i==100) - { - PIOS_LED_Toggle(LED1); - i = 0; - } - - DebugPinHigh(DEBUG_PIN_TASK1_WAIT); - if (PIOS_I2C_LockDevice(MAX_LOCK_WAIT / portTICK_RATE_MS)) - { - uint8_t buf[20]; - - DebugPinLow(DEBUG_PIN_TASK1_WAIT); - DebugPinHigh(DEBUG_PIN_TASK1_LOCKED); - - // Write A0 A1 A2 at address 0x10 - DebugPinHigh(DEBUG_PIN_TRANSFER); - if (PIOS_I2C_Transfer(I2C_Write, DEVICE_1_ADDRESS<<1, (uint8_t*)"\x10\xA0\xA1\xA2", 4) != 0) - OnError(); - DebugPinLow(DEBUG_PIN_TRANSFER); - - - // Read 3 bytes at address 0x20 and check - DebugPinHigh(DEBUG_PIN_TRANSFER); - if (PIOS_I2C_Transfer(I2C_Write_WithoutStop, DEVICE_1_ADDRESS<<1, (uint8_t*)"\x20", 1) != 0) - OnError(); - DebugPinLow(DEBUG_PIN_TRANSFER); - - DebugPinHigh(DEBUG_PIN_TRANSFER); - if (PIOS_I2C_Transfer(I2C_Read, DEVICE_1_ADDRESS<<1, buf, 3) != 0) - OnError(); - DebugPinLow(DEBUG_PIN_TRANSFER); - - if (memcmp(buf, "\xB0\xB1\xB2",3) != 0) - OnError(); - - // Read 3 bytes at address 0x10 and check - DebugPinHigh(DEBUG_PIN_TRANSFER); - if (PIOS_I2C_Transfer(I2C_Write_WithoutStop, DEVICE_1_ADDRESS<<1, (uint8_t*)"\x10", 1) != 0) - OnError(); - DebugPinLow(DEBUG_PIN_TRANSFER); - - DebugPinHigh(DEBUG_PIN_TRANSFER); - if (PIOS_I2C_Transfer(I2C_Read, DEVICE_1_ADDRESS<<1, buf, 3) != 0) - OnError(); - DebugPinLow(DEBUG_PIN_TRANSFER); - - if (memcmp(buf, "\xA0\xA1\xA2",3) != 0) - OnError(); - - DebugPinLow(DEBUG_PIN_TASK1_LOCKED); - PIOS_I2C_UnlockDevice(); - } - else - { - OnError(); - } - } -} - -// This is a high priority task that will periodically perform some actions on the second I2C device -// Most of the time it will have to wait for the other task task to release I2C -static void Task2(void *pvParameters) -{ - portTickType xLastExecutionTime; - - xLastExecutionTime = xTaskGetTickCount(); - uint32_t count = 0; - - for(;;) - { - uint8_t buf[20]; - - DebugPinHigh(DEBUG_PIN_TASK2_WAIT); - if (PIOS_I2C_LockDevice(MAX_LOCK_WAIT / portTICK_RATE_MS)) - { - DebugPinLow(DEBUG_PIN_TASK2_WAIT); - DebugPinHigh(DEBUG_PIN_TASK2_LOCKED); - - // Write value of count to address 0x10 - buf[0] = 0x10; // The address - memcpy(&buf[1], &count, 4); // The data to write - DebugPinHigh(DEBUG_PIN_TRANSFER); - if (PIOS_I2C_Transfer(I2C_Write, DEVICE_2_ADDRESS<<1, buf, 5) != 0) - OnError(); - DebugPinLow(DEBUG_PIN_TRANSFER); - - DebugPinLow(DEBUG_PIN_TASK2_LOCKED); - PIOS_I2C_UnlockDevice(); - } - else - { - OnError(); - } - - vTaskDelay(2 / portTICK_RATE_MS); - - DebugPinHigh(DEBUG_PIN_TASK2_WAIT); - if (PIOS_I2C_LockDevice(1 / portTICK_RATE_MS)) - { - DebugPinLow(DEBUG_PIN_TASK2_WAIT); - DebugPinHigh(DEBUG_PIN_TASK2_LOCKED); - - // Read at address 0x10 and check - DebugPinHigh(DEBUG_PIN_TRANSFER); - if (PIOS_I2C_Transfer(I2C_Write_WithoutStop, DEVICE_2_ADDRESS<<1, (uint8_t*)"\x10", 1) != 0) - OnError(); - DebugPinLow(DEBUG_PIN_TRANSFER); - - DebugPinHigh(DEBUG_PIN_TRANSFER); - if (PIOS_I2C_Transfer(I2C_Read, DEVICE_2_ADDRESS<<1, buf, 4) != 0) - OnError(); - DebugPinLow(DEBUG_PIN_TRANSFER); - - DebugPinHigh(DEBUG_PIN_TRANSFER); - if (memcmp(buf, &count, 4) != 0) - OnError(); - DebugPinLow(DEBUG_PIN_TRANSFER); - - - DebugPinLow(DEBUG_PIN_TASK2_LOCKED); - PIOS_I2C_UnlockDevice(); - } - else - { - OnError(); - } - - vTaskDelay(5 / portTICK_RATE_MS); - - count++; - } -} - - -/** -* Idle hook function -*/ -void vApplicationIdleHook(void) -{ - /* Called when the scheduler has no tasks to run */ - DebugPinHigh(DEBUG_PIN_IDLE); - DebugPinLow(DEBUG_PIN_IDLE); -} diff --git a/flight/OpenPilot/Tests/test_uavobjects.c b/flight/OpenPilot/Tests/test_uavobjects.c deleted file mode 100644 index fffbc3f25..000000000 --- a/flight/OpenPilot/Tests/test_uavobjects.c +++ /dev/null @@ -1,174 +0,0 @@ -/** - ****************************************************************************** - * - * @file test_uavobjects.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Tests for the UAVObject libraries - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "exampleobject1.h" -#include "uavobjectsinit.h" - -// Local functions -static void testTask(void *pvParameters); -static void eventCallback(UAVObjEvent* ev); -static void eventCallbackPeriodic(UAVObjEvent* ev); - -// Variables -int testDelay = 0; - -int main() -{ - /* Brings up System using CMSIS functions, enables the LEDs. */ - PIOS_SYS_Init(); - - /* Delay system */ - PIOS_DELAY_Init(); - - /* SPI Init */ - PIOS_SPI_Init(); - - /* Enables the SDCard */ - PIOS_SDCARD_Init(); - PIOS_SDCARD_MountFS(0); - - // Turn on both LEDs - PIOS_LED_On(LED1); - PIOS_LED_On(LED2); - - // Create test task - xTaskCreate(testTask, (signed portCHAR *)"ObjTest", 1000 , NULL, 1, NULL); - - // Start the FreeRTOS scheduler - vTaskStartScheduler(); - return 0; -} - -static void testTask(void *pvParameters) -{ - ExampleObject1Data data; - - // Initialize object and manager - EventDispatcherInitialize(); - UAVObjInitialize(); - UAVObjectsInitializeAll(); - - // Set data - ExampleObject1Get(&data); - data.Field1 = 1; - data.Field2 = 2; - ExampleObject1Set(&data); - - // Get data - memset(&data, 0, sizeof(data)); - ExampleObject1Get(&data); - - // Benchmark time is takes to get and set data (both operations) - int tickStart = xTaskGetTickCount(); - for (int n = 0; n < 10000; ++n) - { - ExampleObject1Set(&data); - ExampleObject1Get(&data); - } - int delay = xTaskGetTickCount() - tickStart; - - // Create a new instance and get/set its data - uint16_t instId = ExampleObject1CreateInstance(); - ExampleObject1InstSet(instId, &data); - memset(&data, 0, sizeof(data)); - ExampleObject1InstGet(instId, &data); - - // Test pack/unpack - uint8_t buffer[EXAMPLEOBJECT1_NUMBYTES]; - memset(buffer, 0, EXAMPLEOBJECT1_NUMBYTES); - UAVObjPack(ExampleObject1Handle(), 0, buffer); - memset(&data, 0, sizeof(data)); - ExampleObject1Set(&data); - UAVObjUnpack(ExampleObject1Handle(), 0, buffer); - ExampleObject1Get(&data); - - // Test object saving/loading to SD card - UAVObjSave(ExampleObject1Handle(), 0); - memset(&data, 0, sizeof(data)); - ExampleObject1Set(&data); - UAVObjLoad(ExampleObject1Handle(), 0); - ExampleObject1Get(&data); - - // Retrieve object handle by ID - UAVObjHandle handle = UAVObjGetByID(EXAMPLEOBJECT1_OBJID); - const char* name = UAVObjGetName(handle); - - // Get/Set the metadata - UAVObjMetadata mdata; - ExampleObject1GetMetadata(&mdata); - mdata.gcsTelemetryAcked = 0; - ExampleObject1SetMetadata(&mdata); - memset(&mdata, 0, sizeof(mdata)); - ExampleObject1GetMetadata(&mdata); - - // Test callbacks - ExampleObject1ConnectCallback(eventCallback); - ExampleObject1Set(&data); - - // Test queue events - xQueueHandle queue; - queue = xQueueCreate(10, sizeof(UAVObjEvent)); - ExampleObject1ConnectQueue(queue); - - // Test periodic events - UAVObjEvent ev; - ev.event = 0; - ev.instId = 0; - ev.obj = ExampleObject1Handle(); - EventPeriodicCallbackCreate(&ev, eventCallbackPeriodic, 500); - EventPeriodicQueueCreate(&ev, queue, 250); - - // Done testing - while (1) - { - if(xQueueReceive(queue, &ev, portMAX_DELAY) == pdTRUE) - { - name = UAVObjGetName(ev.obj); - PIOS_LED_Toggle(LED2); - } - } - -} - -static void eventCallback(UAVObjEvent* ev) -{ - const char* name = UAVObjGetName(ev->obj); -} - -static void eventCallbackPeriodic(UAVObjEvent* ev) -{ - static int lastUpdate; - testDelay = xTaskGetTickCount() - lastUpdate; - lastUpdate = xTaskGetTickCount(); - const char* name = UAVObjGetName(ev->obj); - PIOS_LED_Toggle(LED1); - //ExampleObject1Updated(); -} - -void vApplicationIdleHook(void) -{ - /* Called when the scheduler has no tasks to run */ -} diff --git a/flight/PiOS.posix/Boards/pios_board.h b/flight/PiOS.posix/Boards/pios_board.h new file mode 100644 index 000000000..9917a1d23 --- /dev/null +++ b/flight/PiOS.posix/Boards/pios_board.h @@ -0,0 +1,10 @@ +#ifndef PIOS_BOARD_H_ +#define PIOS_BOARD_H_ + +#ifdef USE_SIM_POSIX +#include "sim_posix.h" +#else +#error Board definition has not been provided. +#endif + +#endif /* PIOS_BOARD_H_ */ diff --git a/flight/PiOS.posix/Boards/sim_posix.h b/flight/PiOS.posix/Boards/sim_posix.h new file mode 100644 index 000000000..6fbe14551 --- /dev/null +++ b/flight/PiOS.posix/Boards/sim_posix.h @@ -0,0 +1,263 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef SIM_POSIX_H_ +#define SIM_POSIX_H_ + + +/** + * glue macros for file IO + **/ +#define FILEINFO FILE* +#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL +#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL +#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length +#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file) +#define PIOS_FCLOSE(file) fclose(file) +#define PIOS_FUNLINK(file) unlink((char*)filename) + +//------------------------ +// Timers and Channels Used +//------------------------ +/* +Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 +------+-----------+-----------+-----------+---------- +TIM1 | | | | +TIM2 | --------------- PIOS_DELAY ----------------- +TIM3 | | | | +TIM4 | | | | +TIM5 | | | | +TIM6 | | | | +TIM7 | | | | +TIM8 | | | | +------+-----------+-----------+-----------+---------- +*/ + +//------------------------ +// DMA Channels Used +//------------------------ +/* Channel 1 - */ +/* Channel 2 - SPI1 RX */ +/* Channel 3 - SPI1 TX */ +/* Channel 4 - SPI2 RX */ +/* Channel 5 - SPI2 TX */ +/* Channel 6 - */ +/* Channel 7 - */ +/* Channel 8 - */ +/* Channel 9 - */ +/* Channel 10 - */ +/* Channel 11 - */ +/* Channel 12 - */ + +//------------------------ +// BOOTLOADER_SETTINGS +//------------------------ +//#define BOARD_READABLE true +//#define BOARD_WRITABLE true +//#define MAX_DEL_RETRYS 3 + + +//------------------------ +// PIOS_LED +//------------------------ +#define PIOS_LED_NUM 3 +#define PIOS_LED_HEARTBEAT 0 +#define PIOS_LED_ALARM 1 + +//------------------------ +// PIOS_SPI +// See also pios_board.c +//------------------------ +//#define PIOS_SPI_MAX_DEVS 3 + +//------------------------ +// PIOS_WDG +//------------------------ +#define PIOS_WATCHDOG_TIMEOUT 250 +//#define PIOS_WDG_REGISTER RTC_BKP_DR4 +#define PIOS_WDG_ACTUATOR 0x0001 +#define PIOS_WDG_STABILIZATION 0x0002 +#define PIOS_WDG_ATTITUDE 0x0004 +#define PIOS_WDG_MANUAL 0x0008 +#define PIOS_WDG_SENSORS 0x0010 + +//------------------------ +// PIOS_I2C +// See also pios_board.c +//------------------------ +//#define PIOS_I2C_MAX_DEVS 3 +//extern uint32_t pios_i2c_mag_adapter_id; +//#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_adapter_id) + +//------------------------- +// PIOS_USART +// +// See also pios_board.c +//------------------------- +//#define PIOS_USART_MAX_DEVS 5 + +//------------------------- +// PIOS_COM +// +// See also pios_board.c +//------------------------- +#define PIOS_COM_MAX_DEVS 25 +extern uint32_t pios_com_telem_rf_id; +extern uint32_t pios_com_gps_id; +extern uint32_t pios_com_aux_id; +extern uint32_t pios_com_telem_usb_id; +extern uint32_t pios_com_bridge_id; +extern uint32_t pios_com_vcp_id; +#define PIOS_COM_AUX (pios_com_aux_id) +#define PIOS_COM_GPS (pios_com_gps_id) +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) +#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) +#define PIOS_COM_BRIDGE (pios_com_bridge_id) +#define PIOS_COM_VCP (pios_com_vcp_id) +#define PIOS_COM_DEBUG PIOS_COM_AUX + +//------------------------ +// TELEMETRY +//------------------------ +#define TELEM_QUEUE_SIZE 20 +#define PIOS_TELEM_STACK_SIZE 624 + +#define PIOS_COM_BUFFER_SIZE 1024 +#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE +#define PIOS_UDP_TX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE + +//------------------------- +// System Settings +// +// See also System_stm32f4xx.c +//------------------------- +//These macros are deprecated +//please use PIOS_PERIPHERAL_APBx_CLOCK According to the table below +//#define PIOS_MASTER_CLOCK +//#define PIOS_PERIPHERAL_CLOCK +//#define PIOS_PERIPHERAL_CLOCK + +#define PIOS_SYSCLK 168000000 +// Peripherals that belongs to APB1 are: +// DAC |PWR |CAN1,2 +// I2C1,2,3 |UART4,5 |USART3,2 +// I2S3Ext |SPI3/I2S3 |SPI2/I2S2 +// I2S2Ext |IWDG |WWDG +// RTC/BKP reg +// TIM2,3,4,5,6,7,12,13,14 + +// Calculated as SYSCLK / APBPresc * (APBPre == 1 ? 1 : 2) +// Default APB1 Prescaler = 4 +//#define PIOS_PERIPHERAL_APB1_CLOCK (PIOS_SYSCLK / 2) + +// Peripherals belonging to APB2 +// SDIO |EXTI |SYSCFG |SPI1 +// ADC1,2,3 +// USART1,6 +// TIM1,8,9,10,11 +// +// Default APB2 Prescaler = 2 +// +//#define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK + + +//------------------------- +// Interrupt Priorities +//------------------------- +//#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS +//#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS +//#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... +//#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... + +//------------------------ +// PIOS_RCVR +// See also pios_board.c +//------------------------ +#define PIOS_RCVR_MAX_DEVS 3 +#define PIOS_RCVR_MAX_CHANNELS 12 + +//------------------------- +// Receiver PPM input +//------------------------- +//#define PIOS_PPM_MAX_DEVS 1 +//#define PIOS_PPM_NUM_INPUTS 12 + +//------------------------- +// Receiver PWM input +//------------------------- +//#define PIOS_PWM_MAX_DEVS 1 +//#define PIOS_PWM_NUM_INPUTS 8 + +//------------------------- +// Receiver SPEKTRUM input +//------------------------- +//#define PIOS_SPEKTRUM_MAX_DEVS 2 +//#define PIOS_SPEKTRUM_NUM_INPUTS 12 + +//------------------------- +// Receiver S.Bus input +//------------------------- +//#define PIOS_SBUS_MAX_DEVS 1 +//#define PIOS_SBUS_NUM_INPUTS (16+2) + +//------------------------- +// Receiver DSM input +//------------------------- +//#define PIOS_DSM_MAX_DEVS 2 +//#define PIOS_DSM_NUM_INPUTS 12 + +//------------------------- +// Servo outputs +//------------------------- +//#define PIOS_SERVO_UPDATE_HZ 50 +//#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ +#define PIOS_SERVO_NUM_OUTPUTS 8 +#define PIOS_SERVO_NUM_TIMERS PIOS_SERVO_NUM_OUTPUTS +//-------------------------- +// Timer controller settings +//-------------------------- +//#define PIOS_TIM_MAX_DEVS 6 + +//------------------------- +// ADC +// None. +//------------------------- + +//------------------------- +// USB +//------------------------- +//#define PIOS_USB_MAX_DEVS 1 +//#define PIOS_USB_ENABLED 1 /* Should remove all references to this */ +//#define PIOS_USB_HID_MAX_DEVS 1 + +#endif /* SIM_POSIX_H_ */ +/** + * @} + * @} + */ diff --git a/flight/PiOS.posix/inc/pios_delay.h b/flight/PiOS.posix/inc/pios_delay.h index dcd9bb68d..4b79e3ef1 100644 --- a/flight/PiOS.posix/inc/pios_delay.h +++ b/flight/PiOS.posix/inc/pios_delay.h @@ -1,37 +1,48 @@ -/** - ****************************************************************************** - * - * @file pios_settings.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief Settings functions header - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_DELAY_H -#define PIOS_DELAY_H - - -/* Public Functions */ -extern int32_t PIOS_DELAY_Init(void); -extern int32_t PIOS_DELAY_WaituS(uint16_t uS); -extern int32_t PIOS_DELAY_WaitmS(uint16_t mS); - - -#endif /* PIOS_DELAY_H */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_DELAY Delay Functions + * @brief PiOS Delay functionality + * @{ + * + * @file pios_settings.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Settings functions header + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_DELAY_H +#define PIOS_DELAY_H + +/* Public Functions */ +extern int32_t PIOS_DELAY_Init(void); +extern int32_t PIOS_DELAY_WaituS(uint32_t uS); +extern int32_t PIOS_DELAY_WaitmS(uint32_t mS); +extern uint32_t PIOS_DELAY_GetuS(); +extern uint32_t PIOS_DELAY_GetuSSince(uint32_t t); +extern uint32_t PIOS_DELAY_GetRaw(); +extern uint32_t PIOS_DELAY_DiffuS(uint32_t raw); + +#endif /* PIOS_DELAY_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS.posix/inc/pios_led.h b/flight/PiOS.posix/inc/pios_led.h index 42b0d2443..6ce08b0a0 100644 --- a/flight/PiOS.posix/inc/pios_led.h +++ b/flight/PiOS.posix/inc/pios_led.h @@ -1,43 +1,39 @@ -/** - ****************************************************************************** - * - * @file pios_led.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief LED functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_LED_H -#define PIOS_LED_H - -/* Type Definitions */ - -#if (PIOS_LED_NUM == 1) -typedef enum {LED1 = 0} LedTypeDef; -#elif (PIOS_LED_NUM == 2) -typedef enum {LED1 = 0, LED2 = 1} LedTypeDef; -#endif - -/* Public Functions */ -extern void PIOS_LED_Init(void); -extern void PIOS_LED_On(LedTypeDef LED); -extern void PIOS_LED_Off(LedTypeDef LED); -extern void PIOS_LED_Toggle(LedTypeDef LED); - -#endif /* PIOS_LED_H */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_LED LED Functions + * @{ + * + * @file pios_led.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief LED functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_LED_H +#define PIOS_LED_H + +/* Public Functions */ +extern void PIOS_LED_On(uint32_t led_id); +extern void PIOS_LED_Off(uint32_t led_id); +extern void PIOS_LED_Toggle(uint32_t led_id); +extern void PIOS_LED_Init(); + +#endif /* PIOS_LED_H */ diff --git a/flight/PiOS.posix/inc/pios_posix.h b/flight/PiOS.posix/inc/pios_posix.h index b458f77b6..2b411d270 100644 --- a/flight/PiOS.posix/inc/pios_posix.h +++ b/flight/PiOS.posix/inc/pios_posix.h @@ -35,10 +35,10 @@ typedef enum {FALSE = 0, TRUE = !FALSE} bool; #define true TRUE #endif -#define FILEINFO FILE* +//#define FILEINFO FILE* -#define PIOS_SERVO_NUM_OUTPUTS 8 -#define PIOS_SERVO_NUM_TIMERS PIOS_SERVO_NUM_OUTPUTS +//#define PIOS_SERVO_NUM_OUTPUTS 8 +//#define PIOS_SERVO_NUM_TIMERS PIOS_SERVO_NUM_OUTPUTS #endif diff --git a/flight/PiOS.posix/inc/pios_udp_priv.h b/flight/PiOS.posix/inc/pios_udp_priv.h index 999e192e9..5ce32a01a 100644 --- a/flight/PiOS.posix/inc/pios_udp_priv.h +++ b/flight/PiOS.posix/inc/pios_udp_priv.h @@ -45,7 +45,11 @@ struct pios_udp_cfg { typedef struct { const struct pios_udp_cfg * cfg; +#if defined(PIOS_INCLUDE_FREERTOS) + xTaskHandle rxThread; +#else pthread_t rxThread; +#endif int socket; struct sockaddr_in server; @@ -66,6 +70,6 @@ typedef struct { extern int32_t PIOS_UDP_Init(uint32_t * udp_id, const struct pios_udp_cfg * cfg); - +extern const struct pios_com_driver pios_udp_com_driver; #endif /* PIOS_UDP_PRIV_H */ diff --git a/flight/PiOS.posix/pios.h b/flight/PiOS.posix/pios.h index 9256891b1..8e96fa092 100644 --- a/flight/PiOS.posix/pios.h +++ b/flight/PiOS.posix/pios.h @@ -29,7 +29,7 @@ #define PIOS_H /* PIOS Feature Selection */ -#include "pios_config_posix.h" +#include "pios_config.h" #include #if defined(PIOS_INCLUDE_FREERTOS) @@ -52,7 +52,7 @@ #include "pios_initcall.h" /* PIOS Board Specific Device Configuration */ -#include "pios_board_posix.h" +#include "pios_board.h" /* PIOS Hardware Includes (posix) */ #include diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_linux.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_linux.c deleted file mode 100644 index 20fa0cb9e..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_linux.c +++ /dev/null @@ -1,1024 +0,0 @@ -/* - Copyright (C) 2009 William Davy - william.davy@wittenstein.co.uk - Contributed to FreeRTOS.org V5.3.0. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org 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 FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the Posix port. - *----------------------------------------------------------*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" -/*-----------------------------------------------------------*/ - -#define MAX_NUMBER_OF_TASKS ( _POSIX_THREAD_THREADS_MAX ) -/*-----------------------------------------------------------*/ - -/* Parameters to pass to the newly created pthread. */ -typedef struct XPARAMS -{ - pdTASK_CODE pxCode; - void *pvParams; -} xParams; - -/* Each task maintains its own interrupt status in the critical nesting variable. */ -typedef struct THREAD_SUSPENSIONS -{ - pthread_t hThread; - xTaskHandle hTask; - unsigned portBASE_TYPE uxCriticalNesting; -} xThreadState; -/*-----------------------------------------------------------*/ - -static xThreadState *pxThreads; -static pthread_once_t hSigSetupThread = PTHREAD_ONCE_INIT; -static pthread_attr_t xThreadAttributes; -static pthread_mutex_t xSuspendResumeThreadMutex = PTHREAD_MUTEX_INITIALIZER; -//static pthread_mutex_t xSingleThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xRunningThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_t hMainThread = ( pthread_t )NULL; -static pthread_t hActiveThread = ( pthread_t )NULL; -static pthread_t hRequestedThread = ( pthread_t )NULL; -/*-----------------------------------------------------------*/ - -static volatile portBASE_TYPE xSentinel = 0; -static volatile portBASE_TYPE xGeneralFuckedUpIndicator = 0; -static volatile portBASE_TYPE xVeryFirstTask = 1; -static volatile portBASE_TYPE xSchedulerEnd = pdFALSE; -static volatile portBASE_TYPE xInterruptsEnabled = pdTRUE; -static volatile portBASE_TYPE xServicingTick = pdFALSE; -static volatile portBASE_TYPE xPendYield = pdFALSE; -static volatile portLONG lIndexOfLastAddedTask = 0; -static volatile unsigned portBASE_TYPE uxCriticalNesting; -/*-----------------------------------------------------------*/ - -/* - * Setup the timer to generate the tick interrupts. - */ -static void prvSetupTimerInterrupt( void ); -static void *prvWaitForStart( void * pvParams ); -static void prvSuspendSignalHandler(int sig); -//static void prvResumeSignalHandler(int sig); -static void prvSetupSignalsAndSchedulerPolicy( void ); -static void prvSuspendThread( pthread_t xThreadId ); -static void prvResumeThread( pthread_t xThreadId ); -static pthread_t prvGetThreadHandle( xTaskHandle hTask ); -static portLONG prvGetFreeThreadState( void ); -static void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ); -static unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ); -static void prvDeleteThread( void *xThreadId ); -/*-----------------------------------------------------------*/ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ -#endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - -#if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ -#endif - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; -#endif - -#if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ -#endif - -#if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ -#endif - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ -#endif - -} tskTCB; - -tskTCB* debug_task_handle; -tskTCB* prvGetTaskHandle( pthread_t hThread ) -{ -portLONG lIndex; - - if (pxThreads==NULL) return NULL; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == hThread ) - { - return pxThreads[ lIndex ].hTask; - } - } - return NULL; -} - -#ifdef DEBUG_OUTPUT - static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; - #define debug_printf(...) ( (real_pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%s(%li)\t%s\t%i:",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "__unknown__(%li)\t%s\t%i:",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?real_pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - - //int xbla; - //#define debug_printf(...) xbla=0 - int real_pthread_mutex_lock(pthread_mutex_t* mutex) { - return pthread_mutex_lock(mutex); - } - int real_pthread_mutex_unlock(pthread_mutex_t* mutex) { - return pthread_mutex_unlock(mutex); - } - #define pthread_mutex_lock(...) ( (debug_printf(" -!- pthread_mutex_lock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_lock(__VA_ARGS__):0 ) - #define pthread_mutex_unlock(...) ( (debug_printf(" -=- pthread_mutex_unlock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_unlock(__VA_ARGS__):0 ) - #define pthread_kill(thread,signal) ( (debug_printf(" sending signal %i to thread %li!\n",(int)signal,(long)thread)|1)?pthread_kill(thread,signal):0 ) - #define vTaskSwitchContext() ( (debug_printf("SWITCHCONTEXT!\n")|1)?vTaskSwitchContext():vTaskSwitchContext() ) -#else - #define debug_printf(...) -#endif - -/*-----------------------------------------------------------*/ - -void prvSuspendThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult; -// xResult = pthread_mutex_lock( &xSuspendResumeThreadMutex ); -// if ( 0 == xResult ) -// { - /* Set-up for the Suspend Signal handler? */ - //xSentinel = 0; -//portBASE_TYPE aSentinel=xSentinel; - xResult = pthread_kill( xThreadId, SIG_SUSPEND ); -// xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); -// while ( ( aSentinel == xSentinel ) && ( pdTRUE != xServicingTick ) ) -// { -// sched_yield(); -// } -// } -} -/*-----------------------------------------------------------*/ - -void prvResumeThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult; -// if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) -// { - if ( pthread_self() != xThreadId ) - { - xResult = pthread_kill( xThreadId, SIG_RESUME ); - } -// xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); -// } -} -#define prvSuspendThread(thread) debug_printf("calling SuspendThread(%li)\n",(long)thread); prvSuspendThread(thread) -#define prvResumeThread(thread) debug_printf("calling ResumeThread(%li)\n",(long)thread); prvResumeThread(thread) - -/* - * Exception handlers. - */ -void vPortYield( void ); -void vPortSystemTickHandler( int sig ); - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -void vPortStartFirstTask( void ); -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ -/* Should actually keep this struct on the stack. */ -xParams *pxThisThreadParams = pvPortMalloc( sizeof( xParams ) ); - - (void)pthread_once( &hSigSetupThread, prvSetupSignalsAndSchedulerPolicy ); - - if ( (pthread_t)NULL == hMainThread ) - { - hMainThread = pthread_self(); - } - - /* No need to join the threads. */ - pthread_attr_init( &xThreadAttributes ); - pthread_attr_setdetachstate( &xThreadAttributes, PTHREAD_CREATE_DETACHED ); - - /* Add the task parameters. */ - pxThisThreadParams->pxCode = pxCode; - pxThisThreadParams->pvParams = pvParameters; - - vPortEnterCritical(); - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) { - while (hActiveThread!=hRequestedThread && !xVeryFirstTask) { - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - sched_yield(); - (void)pthread_mutex_lock( &xSuspendResumeThreadMutex ); - } - - - lIndexOfLastAddedTask = prvGetFreeThreadState(); - - /* Create the new pThread. */ - /* On creation of the very first thread, RunningThreadMutex is not claimed yet - * by the master thread - do that! */ - if (xVeryFirstTask==1) { - debug_printf("Seting up very first task (main) - MAIN is ACTIVE TASK\n"); - if (0 == pthread_mutex_lock( &xRunningThreadMutex)) { - xVeryFirstTask=0; - hActiveThread=pthread_self(); - hRequestedThread=hActiveThread; - } else { - printf("Failed to acquire lock for first task"); - exit(1); - } - - } - - if ( 0 != pthread_create( &( pxThreads[ lIndexOfLastAddedTask ].hThread ), &xThreadAttributes, prvWaitForStart, (void *)pxThisThreadParams ) ) - { - /* Thread create failed, signal the failure */ - pxTopOfStack = 0; - } - - /* Wait until the task suspends. */ - xSentinel=0; - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - while ( xSentinel == 0 ) { - sched_yield(); - } - (void)pthread_mutex_lock( &xRunningThreadMutex ); - hActiveThread=pthread_self(); - debug_printf("ACTIVE THREAD RECLAIMED!\n"); - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } else { - debug_printf("mutex locking failed\n"); - exit(1); - } - vPortExitCritical(); - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortStartFirstTask( void ) -{ - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - /* Start the first task. */ - vPortEnableInterrupts(); - - /* Start the first task. */ - hRequestedThread=prvGetThreadHandle( xTaskGetCurrentTaskHandle()); - prvResumeThread( hRequestedThread ); - - sched_yield(); -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ -portBASE_TYPE xResult; -int iSignal; -sigset_t xSignals; -sigset_t xSignalToBlock; -sigset_t xSignalsBlocked; -portLONG lIndex; - - /* Establish the signals to block before they are needed. */ - sigfillset( &xSignalToBlock ); - - /* Block until the end */ - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, &xSignalsBlocked ); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - /* Start the timer that generates the tick ISR. Interrupts are disabled - here already. */ - prvSetupTimerInterrupt(); - - /* Start the first task. Will not return unless all threads are killed. */ - vPortStartFirstTask(); - - /* This is the end signal we are looking for. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - sigaddset( &xSignals, SIG_TICK ); - - /* Allow other threads to run */ - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - debug_printf( "MAIN thread is entering main signal wait loop!\n"); - - while ( pdTRUE != xSchedulerEnd ) - { - if ( 0 != sigwait( &xSignals, &iSignal ) ) - { - printf( "Main thread spurious signal: %d\n", iSignal ); - } - /** - * Tick handler is called from here - AND ONLY FROM HERE - * (needed for cygwin - but should work on all) - */ - if (iSignal==SIG_TICK) { - vPortSystemTickHandler(iSignal); - } - if (iSignal==SIG_RESUME && pdTRUE != xSchedulerEnd) { - debug_printf("main: forwarding signal to %li\n",(long)hRequestedThread); - (void)pthread_kill( hRequestedThread, SIG_RESUME ); - } - } - - printf( "Cleaning Up, Exiting.\n" ); - /* Cleanup the mutexes */ - //xResult = pthread_mutex_destroy( &xSuspendResumeThreadMutex ); - //xResult = pthread_mutex_destroy( &xSingleThreadMutex ); - xResult = pthread_mutex_destroy( &xRunningThreadMutex ); - vPortFree( (void *)pxThreads ); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ -portBASE_TYPE xNumberOfThreads; -portBASE_TYPE xResult; - for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ ) - { - if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread ) - { - /* Kill all of the threads, they are in the detached state. */ - xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread ); - } - } - - /* Signal the scheduler to exit its loop. */ - xSchedulerEnd = pdTRUE; - (void)pthread_kill( hMainThread, SIG_RESUME ); -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Calling Yield from a Interrupt/Signal handler often doesn't work because the - * xSingleThreadMutex is already owned by an original call to Yield. Therefore, - * simply indicate that a yield is required soon. - */ - xPendYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - vPortDisableInterrupts(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - /* Check for unmatched exits. */ - if ( uxCriticalNesting > 0 ) - { - uxCriticalNesting--; - } - - /* If we have reached 0 then re-enable the interrupts. */ - if( uxCriticalNesting == 0 ) - { - /* Have we missed ticks? This is the equivalent of pending an interrupt. */ - if ( pdTRUE == xPendYield ) - { - xPendYield = pdFALSE; - vPortYield(); - } - vPortEnableInterrupts(); - } -} -/*-----------------------------------------------------------*/ - -void vPortYield( void ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; - - /** - * Sentinel - do not change context while the running task is not equal the task supposed to run - */ - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) - { - /** - * Make sure we don't create outdated resume signals - */ - while (hActiveThread!=hRequestedThread) { - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - sched_yield(); - (void)pthread_mutex_lock( &xSuspendResumeThreadMutex ); - } - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - vTaskSwitchContext(); - - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - if ( xTaskToSuspend != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - /* Switch tasks. */ - hRequestedThread = xTaskToResume; - prvResumeThread( xTaskToResume ); - //prvSuspendThread( xTaskToSuspend ); -if (prvGetThreadHandle(xTaskGetCurrentTaskHandle())!=xTaskToResume) { - debug_printf("\n what the fuck???? someone else did a switchcontext?!?\n"); -} - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - prvSuspendSignalHandler(SIG_SUSPEND); - return; - } - else - { - /* Yielding to self */ - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } - } -} -/*-----------------------------------------------------------*/ - -void vPortDisableInterrupts( void ) -{ - xInterruptsEnabled = pdFALSE; -} -/*-----------------------------------------------------------*/ - -void vPortEnableInterrupts( void ) -{ - xInterruptsEnabled = pdTRUE; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xPortSetInterruptMask( void ) -{ -portBASE_TYPE xReturn = xInterruptsEnabled; - xInterruptsEnabled = pdFALSE; - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vPortClearInterruptMask( portBASE_TYPE xMask ) -{ - xInterruptsEnabled = xMask; -} -/*-----------------------------------------------------------*/ - -/* - * Setup the systick timer to generate the tick interrupts at the required - * frequency. - */ -void prvSetupTimerInterrupt( void ) -{ -struct itimerval itimer, oitimer; -portTickType xMicroSeconds = portTICK_RATE_MICROSECONDS; - - debug_printf("init %li microseconds\n",(long)xMicroSeconds); - /* Initialise the structure with the current timer information. */ - if ( 0 == getitimer( TIMER_TYPE, &itimer ) ) - { - /* Set the interval between timer events. */ - itimer.it_interval.tv_sec = 0; - itimer.it_interval.tv_usec = xMicroSeconds; - - /* Set the current count-down. */ - itimer.it_value.tv_sec = 0; - itimer.it_value.tv_usec = xMicroSeconds; - - /* Set-up the timer interrupt. */ - if ( 0 != setitimer( TIMER_TYPE, &itimer, &oitimer ) ) - { - printf( "Set Timer problem.\n" ); - } - } - else - { - printf( "Get Timer problem.\n" ); - } -} -/*-----------------------------------------------------------*/ - -void vPortSystemTickHandler( int sig ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -struct timespec timeout; - - //debug_printf("received %i\n",sig); - /** - * do not call tick handler if - * - interrupts are disabled - * - tick handler is still running - * - old task switch not yet completed (wrong task running) - */ - if ( ( pdTRUE == xInterruptsEnabled ) && ( pdTRUE != xServicingTick ) && ( hRequestedThread == hActiveThread ) ) - { - xServicingTick = pdTRUE; - if ( 0 == pthread_mutex_trylock( &xSuspendResumeThreadMutex ) ) - { - debug_printf("does handle tick\n"); - - /** - * this shouldn't ever happen - but WELL... - * Make sure we don't create outdated resume signals - */ - if (hActiveThread!=hRequestedThread) { - xServicingTick = pdFALSE; - xPendYield = pdTRUE; - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - return; - } - - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - /* Tick Increment. */ - vTaskIncrementTick(); - - /* Select Next Task. */ -#if ( configUSE_PREEMPTION == 1 ) - vTaskSwitchContext(); -#endif - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - //hRequestedThread = xTaskToResume; - - /* The only thread that can process this tick is the running thread. */ - if ( xTaskToSuspend != xTaskToResume ) - { - /* Suspend the current task. */ - hRequestedThread = 0; - prvSuspendThread( xTaskToSuspend ); - timeout.tv_sec=0; - timeout.tv_nsec=10000; - while ( 0 != pthread_mutex_timedlock( &xRunningThreadMutex,&timeout ) ) { - prvSuspendThread( xTaskToSuspend ); - timeout.tv_sec=0; - timeout.tv_nsec=10000; - } - /* - if ( 0 != pthread_mutex_lock( &xRunningThreadMutex)) { - debug_printf("mutex lock failed!\n"); - exit(1); - } - */ - //if ( 0 == pthread_mutex_lock( &xRunningThreadMutex) ) { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - /* Resume next task. */ - hRequestedThread = xTaskToResume; - prvResumeThread( xTaskToResume ); -if (prvGetThreadHandle(xTaskGetCurrentTaskHandle())!=xTaskToResume) { -debug_printf("\n what the fuck???? someone else did a switchcontext?!?\n"); -} - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - } - else - { - /* Release the lock as we are Resuming. */ - // (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - } - else - { - xPendYield = pdTRUE; - } - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - xServicingTick = pdFALSE; - } - else - { - debug_printf("will NOT handle tick\n"); - xPendYield = pdTRUE; - } -} -/*-----------------------------------------------------------*/ - -void vPortForciblyEndThread( void *pxTaskToDelete ) -{ -xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete; -pthread_t xTaskToDelete; -pthread_t xTaskToResume; -portBASE_TYPE xResult; - -// if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) -// { - xTaskToDelete = prvGetThreadHandle( hTaskToDelete ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( xTaskToResume == xTaskToDelete ) - { - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) { - /** - * Make sure we don't create outdated resume signals - */ - while (hActiveThread!=hRequestedThread) { - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - sched_yield(); - (void)pthread_mutex_lock( &xSuspendResumeThreadMutex ); - } - /* This is a suicidal thread, need to select a different task to run. */ - vTaskSwitchContext(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - hRequestedThread = xTaskToResume; - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } else { - debug_printf("mutex lock failed!\n"); - exit(1); - } - } - - if ( pthread_self() != xTaskToDelete ) - { - /* Cancelling a thread that is not me. */ - if ( xTaskToDelete != ( pthread_t )NULL ) - { - /* Send a signal to wake the task so that it definitely cancels. */ - pthread_testcancel(); - xResult = pthread_cancel( xTaskToDelete ); - /* Pthread Clean-up function will note the cancellation. */ - } -// (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - else - { - /* Resume the other thread. */ - prvResumeThread( xTaskToResume ); - /* Pthread Clean-up function will note the cancellation. */ - /* Release the execution. */ - uxCriticalNesting = 0; - vPortEnableInterrupts(); -// (void)pthread_mutex_unlock( &xSingleThreadMutex ); - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - /* Commit suicide */ - pthread_exit( (void *)1 ); - } -// } -} -/*-----------------------------------------------------------*/ - -void *prvWaitForStart( void * pvParams ) -{ -xParams * pxParams = ( xParams * )pvParams; -pdTASK_CODE pvCode = pxParams->pxCode; -void * pParams = pxParams->pvParams; -sigset_t xSignals; - vPortFree( pvParams ); - - pthread_cleanup_push( prvDeleteThread, (void *)pthread_self() ); - - if ( 0 == pthread_mutex_lock( &xRunningThreadMutex ) ) - { - xSentinel=1; - hActiveThread=pthread_self(); - debug_printf("temporarily made ACTIVE THREAD!\n"); - - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - /* set up proc mask */ - pthread_sigmask(SIG_SETMASK,&xSignals,NULL); - - prvSuspendSignalHandler(SIG_SUSPEND); - //prvSuspendThread( pthread_self() ); - } else { - debug_printf("now this is just WRONG!\n"); - exit(1); - } - - pvCode( pParams ); - - pthread_cleanup_pop( 1 ); - return (void *)NULL; -} -/*-----------------------------------------------------------*/ - -void prvSuspendSignalHandler(int sig) -{ -sigset_t xSignals; -//sigset_t xPendingSignals; - - /* Only interested in the resume signal. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - sigaddset( &xSignals, SIG_SUSPEND ); - - /* Unlock the Running thread mutex to allow the resumed task to continue. */ - if ( 0 != pthread_mutex_unlock( &xRunningThreadMutex ) ) - { - printf( "Releasing someone else's lock.\n" ); - } - - debug_printf("SUSPENDING until SIG_RESUME received\n"); - /* Wait on the resume signal. */ - while (hRequestedThread != pthread_self()) { - if ( 0 != sigwait( &xSignals, &sig ) ) - { - printf( "SSH: Sw %d\n", sig ); - /* tricky one - shouldn't ever happen - trying to resolve situation as graceful as possible */ - debug_printf("ALERT AAAAH PANIC! - sigwait failed.....\n\n\n"); - /* Signal main thread something just went HORRIBLY wrong */ - xGeneralFuckedUpIndicator = 2; - //(void)pthread_mutex_lock( &xRunningThreadMutex ); - //(void)pthread_kill( pthread_self(), SIG_SUSPEND ); - //return; - } - } - /* Yield the Scheduler to ensure that the yielding thread completes. */ - if ( 0 != pthread_mutex_lock( &xRunningThreadMutex ) ) - { - //(void)pthread_mutex_unlock( &xSingleThreadMutex ); - debug_printf("critical - mutex acquiring of active thread failed!\n"); - exit(1); - } - hActiveThread = pthread_self(); - - /* Will resume here when the SIG_RESUME signal is received. */ - /* Need to set the interrupts based on the task's critical nesting. */ - if ( uxCriticalNesting == 0 ) - { - vPortEnableInterrupts(); - } - else - { - vPortDisableInterrupts(); - } - if (hRequestedThread==pthread_self()) { - /* doesn't look too bad, does it? */ - xGeneralFuckedUpIndicator = 0; - } - debug_printf("ACTIVE THREAD!\n"); -} -/*-----------------------------------------------------------*/ - -void prvSetupSignalsAndSchedulerPolicy( void ) -{ -/* The following code would allow for configuring the scheduling of this task as a Real-time task. - * The process would then need to be run with higher privileges for it to take affect. -int iPolicy; -int iResult; -int iSchedulerPriority; - iResult = pthread_getschedparam( pthread_self(), &iPolicy, &iSchedulerPriority ); - iResult = pthread_attr_setschedpolicy( &xThreadAttributes, SCHED_FIFO ); - iPolicy = SCHED_FIFO; - iResult = pthread_setschedparam( pthread_self(), iPolicy, &iSchedulerPriority ); */ - -struct sigaction sigsuspendself, sigresume, sigtick; -portLONG lIndex; - - pxThreads = ( xThreadState *)pvPortMalloc( sizeof( xThreadState ) * MAX_NUMBER_OF_TASKS ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = ( xTaskHandle )NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - sigsuspendself.sa_flags = 0; - sigsuspendself.sa_handler = prvSuspendSignalHandler; - sigfillset( &sigsuspendself.sa_mask ); - - sigresume.sa_flags = 0; - //sigresume.sa_handler = prvResumeSignalHandler; - sigresume.sa_handler = SIG_IGN; - sigfillset( &sigresume.sa_mask ); - - sigtick.sa_flags = 0; - //sigtick.sa_handler = vPortSystemTickHandler; - sigtick.sa_handler = SIG_IGN; - sigfillset( &sigtick.sa_mask ); - - if ( 0 != sigaction( SIG_SUSPEND, &sigsuspendself, NULL ) ) - { - printf( "Problem installing SIG_SUSPEND_SELF\n" ); - } - //if ( 0 != sigaction( SIG_RESUME, &sigresume, NULL ) ) - //{ - // printf( "Problem installing SIG_RESUME\n" ); - //} - if ( 0 != sigaction( SIG_TICK, &sigtick, NULL ) ) - { - printf( "Problem installing SIG_TICK\n" ); - } - printf( "Running as PID: %d\n", getpid() ); -} -/*-----------------------------------------------------------*/ - -pthread_t prvGetThreadHandle( xTaskHandle hTask ) -{ -pthread_t hThread = ( pthread_t )NULL; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hThread = pxThreads[ lIndex ].hThread; - break; - } - } - return hThread; -} -/*-----------------------------------------------------------*/ - -portLONG prvGetFreeThreadState( void ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )NULL ) - { - break; - } - } - - if ( MAX_NUMBER_OF_TASKS == lIndex ) - { - printf( "No more free threads, please increase the maximum.\n" ); - lIndex = 0; - vPortEndScheduler(); - } - - return lIndex; -} -/*-----------------------------------------------------------*/ - -void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - pxThreads[ lIndex ].uxCriticalNesting = uxNesting; - break; - } - } -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ) -{ -unsigned portBASE_TYPE uxNesting = 0; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - uxNesting = pxThreads[ lIndex ].uxCriticalNesting; - break; - } - } - return uxNesting; -} -/*-----------------------------------------------------------*/ - -void prvDeleteThread( void *xThreadId ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )xThreadId ) - { - pxThreads[ lIndex ].hThread = (pthread_t)NULL; - pxThreads[ lIndex ].hTask = (xTaskHandle)NULL; - if ( pxThreads[ lIndex ].uxCriticalNesting > 0 ) - { - uxCriticalNesting = 0; - vPortEnableInterrupts(); - } - pxThreads[ lIndex ].uxCriticalNesting = 0; - break; - } - } -} -/*-----------------------------------------------------------*/ - -void vPortAddTaskHandle( void *pxTaskHandle ) -{ -portLONG lIndex; - - pxThreads[ lIndexOfLastAddedTask ].hTask = ( xTaskHandle )pxTaskHandle; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == pxThreads[ lIndexOfLastAddedTask ].hThread ) - { - if ( pxThreads[ lIndex ].hTask != pxThreads[ lIndexOfLastAddedTask ].hTask ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - } - } -} -/*-----------------------------------------------------------*/ - -void vPortFindTicksPerSecond( void ) -{ - /* Needs to be reasonably high for accuracy. */ - unsigned long ulTicksPerSecond = sysconf(_SC_CLK_TCK); - printf( "Timer Resolution for Run TimeStats is %ld ticks per second.\n", ulTicksPerSecond ); -} -/*-----------------------------------------------------------*/ - -unsigned long ulPortGetTimerValue( void ) -{ -struct tms xTimes; - unsigned long ulTotalTime = times( &xTimes ); - /* Return the application code times. - * The timer only increases when the application code is actually running - * which means that the total execution times should add up to 100%. - */ - return ( unsigned long ) xTimes.tms_utime; - - /* Should check ulTotalTime for being clock_t max minus 1. */ - (void)ulTotalTime; -} -/*-----------------------------------------------------------*/ diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_new-thread-implementation_works-on-linux.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_new-thread-implementation_works-on-linux.c deleted file mode 100755 index 7f38e2a2d..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_new-thread-implementation_works-on-linux.c +++ /dev/null @@ -1,1042 +0,0 @@ -/* - Copyright (C) 2009 William Davy - william.davy@wittenstein.co.uk - Contributed to FreeRTOS.org V5.3.0. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org 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 FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the Posix port. - *----------------------------------------------------------*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" -/*-----------------------------------------------------------*/ - -#define MAX_NUMBER_OF_TASKS ( _POSIX_THREAD_THREADS_MAX ) -/*-----------------------------------------------------------*/ - -/* Parameters to pass to the newly created pthread. */ -typedef struct XPARAMS -{ - pdTASK_CODE pxCode; - void *pvParams; -} xParams; - -/* Each task maintains its own interrupt status in the critical nesting variable. */ -typedef struct THREAD_SUSPENSIONS -{ - pthread_t hThread; - xTaskHandle hTask; - unsigned portBASE_TYPE uxCriticalNesting; -} xThreadState; -/*-----------------------------------------------------------*/ - -static xThreadState *pxThreads; -static pthread_once_t hSigSetupThread = PTHREAD_ONCE_INIT; -static pthread_attr_t xThreadAttributes; -static pthread_mutex_t xSuspendResumeThreadMutex = PTHREAD_MUTEX_INITIALIZER; -//static pthread_mutex_t xSingleThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xRunningThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_t hMainThread = ( pthread_t )NULL; -static pthread_t hActiveThread = ( pthread_t )NULL; -static pthread_t hRequestedThread = ( pthread_t )NULL; -/*-----------------------------------------------------------*/ - -static volatile portBASE_TYPE xSentinel = 0; -static volatile portBASE_TYPE xGeneralFuckedUpIndicator = 0; -static volatile portBASE_TYPE xVeryFirstTask = 1; -static volatile portBASE_TYPE xSchedulerEnd = pdFALSE; -static volatile portBASE_TYPE xInterruptsEnabled = pdTRUE; -static volatile portBASE_TYPE xServicingTick = pdFALSE; -static volatile portBASE_TYPE xPendYield = pdFALSE; -static volatile portLONG lIndexOfLastAddedTask = 0; -static volatile unsigned portBASE_TYPE uxCriticalNesting; -/*-----------------------------------------------------------*/ - -/* - * Setup the timer to generate the tick interrupts. - */ -static void prvSetupTimerInterrupt( void ); -static void *prvWaitForStart( void * pvParams ); -static void prvSuspendSignalHandler(int sig); -//static void prvResumeSignalHandler(int sig); -static void prvSetupSignalsAndSchedulerPolicy( void ); -static void prvSuspendThread( pthread_t xThreadId ); -static void prvResumeThread( pthread_t xThreadId ); -static pthread_t prvGetThreadHandle( xTaskHandle hTask ); -static portLONG prvGetFreeThreadState( void ); -static void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ); -static unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ); -static void prvDeleteThread( void *xThreadId ); -static void prvResolveFuckup( void ); -/*-----------------------------------------------------------*/ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ -#endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - -#if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ -#endif - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; -#endif - -#if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ -#endif - -#if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ -#endif - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ -#endif - -} tskTCB; - -tskTCB* debug_task_handle; -tskTCB* prvGetTaskHandle( pthread_t hThread ) -{ -portLONG lIndex; - - if (pxThreads==NULL) return NULL; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == hThread ) - { - return pxThreads[ lIndex ].hTask; - } - } - return NULL; -} - - -#define debug_printf(...) ( (real_pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%s(%li)\t%s\t%i:",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "__unknown__(%li)\t%s\t%i:",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?real_pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - -//int xbla; -//#define debug_printf(...) xbla=0 -int real_pthread_mutex_lock(pthread_mutex_t* mutex) { - return pthread_mutex_lock(mutex); -} -int real_pthread_mutex_unlock(pthread_mutex_t* mutex) { - return pthread_mutex_unlock(mutex); -} -/* -#define pthread_mutex_lock(...) ( (debug_printf(" -!- pthread_mutex_lock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_lock(__VA_ARGS__):0 ) -#define pthread_mutex_unlock(...) ( (debug_printf(" -=- pthread_mutex_unlock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_unlock(__VA_ARGS__):0 ) -#define pthread_kill(thread,signal) ( (debug_printf(" sending signal %i to thread %li!\n",(int)signal,(long)thread)|1)?pthread_kill(thread,signal):0 ) -#define vTaskSwitchContext() ( (debug_printf("SWITCHCONTEXT!\n")|1)?vTaskSwitchContext():vTaskSwitchContext() ) -*/ -/*-----------------------------------------------------------*/ - -void prvSuspendThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult; -// xResult = pthread_mutex_lock( &xSuspendResumeThreadMutex ); -// if ( 0 == xResult ) -// { - /* Set-up for the Suspend Signal handler? */ - //xSentinel = 0; -//portBASE_TYPE aSentinel=xSentinel; - xResult = pthread_kill( xThreadId, SIG_SUSPEND ); -// xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); -// while ( ( aSentinel == xSentinel ) && ( pdTRUE != xServicingTick ) ) -// { -// sched_yield(); -// } -// } -} -/*-----------------------------------------------------------*/ - -void prvResumeThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult; -// if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) -// { - if ( pthread_self() != xThreadId ) - { - xResult = pthread_kill( xThreadId, SIG_RESUME ); - } -// xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); -// } -} -#define prvSuspendThread(thread) debug_printf("calling SuspendThread(%li)\n",(long)thread); prvSuspendThread(thread) -#define prvResumeThread(thread) debug_printf("calling ResumeThread(%li)\n",(long)thread); prvResumeThread(thread) - -/* - * Exception handlers. - */ -void vPortYield( void ); -void vPortSystemTickHandler( int sig ); - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -void vPortStartFirstTask( void ); -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ -/* Should actually keep this struct on the stack. */ -xParams *pxThisThreadParams = pvPortMalloc( sizeof( xParams ) ); - - (void)pthread_once( &hSigSetupThread, prvSetupSignalsAndSchedulerPolicy ); - - if ( (pthread_t)NULL == hMainThread ) - { - hMainThread = pthread_self(); - } - - /* No need to join the threads. */ - pthread_attr_init( &xThreadAttributes ); - pthread_attr_setdetachstate( &xThreadAttributes, PTHREAD_CREATE_DETACHED ); - - /* Add the task parameters. */ - pxThisThreadParams->pxCode = pxCode; - pxThisThreadParams->pvParams = pvParameters; - - vPortEnterCritical(); - - lIndexOfLastAddedTask = prvGetFreeThreadState(); - - /* Create the new pThread. */ - /* On creation of the very first thread, RunningThreadMutex is not claimed yet - * by the master thread - do that! */ - if (xVeryFirstTask==1) { - if (0 == pthread_mutex_lock( &xRunningThreadMutex)) { - xVeryFirstTask=0; - } else { - printf("Failed to acquire lock for first task"); - exit(1); - } - - } - - if ( 0 != pthread_create( &( pxThreads[ lIndexOfLastAddedTask ].hThread ), &xThreadAttributes, prvWaitForStart, (void *)pxThisThreadParams ) ) - { - /* Thread create failed, signal the failure */ - pxTopOfStack = 0; - } - - /* Wait until the task suspends. */ - xSentinel=0; - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - while ( xSentinel == 0 ) { - sched_yield(); - } - (void)pthread_mutex_lock( &xRunningThreadMutex ); - vPortExitCritical(); - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortStartFirstTask( void ) -{ - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - /* Start the first task. */ - vPortEnableInterrupts(); - - /* Start the first task. */ - hRequestedThread=prvGetThreadHandle( xTaskGetCurrentTaskHandle()); - prvResumeThread( hRequestedThread ); - - sched_yield(); -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ -portBASE_TYPE xResult; -int iSignal; -int fuckedUpCount=0; -sigset_t xSignals; -sigset_t xSignalToBlock; -sigset_t xSignalsBlocked; -portLONG lIndex; - - /* Establish the signals to block before they are needed. */ - sigfillset( &xSignalToBlock ); - - /* Block until the end */ - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, &xSignalsBlocked ); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - /* Start the timer that generates the tick ISR. Interrupts are disabled - here already. */ - prvSetupTimerInterrupt(); - - /* Start the first task. Will not return unless all threads are killed. */ - vPortStartFirstTask(); - - /* This is the end signal we are looking for. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - sigaddset( &xSignals, SIG_TICK ); - - /* Allow other threads to run */ - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - debug_printf( "MAIN thread is entering main signal wait loop!\n"); - - while ( pdTRUE != xSchedulerEnd ) - { - if ( 0 != sigwait( &xSignals, &iSignal ) ) - { - printf( "Main thread spurious signal: %d\n", iSignal ); - } - /** - * Tick handler is called from here - AND ONLY FROM HERE - * (needed for cygwin - but should work on all) - */ - if (iSignal==SIG_TICK) { - if (xGeneralFuckedUpIndicator!=0) { - fuckedUpCount++; - if (fuckedUpCount>10) { - fuckedUpCount=0; - prvResolveFuckup(); - } - } else { - fuckedUpCount=0; - } - vPortSystemTickHandler(iSignal); - } - if (iSignal==SIG_RESUME && pdTRUE != xSchedulerEnd) { - debug_printf( "ALERT! Main received SIG_RESUME that was supposed to go elsewhere!"); - } - } - - printf( "Cleaning Up, Exiting.\n" ); - /* Cleanup the mutexes */ - //xResult = pthread_mutex_destroy( &xSuspendResumeThreadMutex ); - //xResult = pthread_mutex_destroy( &xSingleThreadMutex ); - xResult = pthread_mutex_destroy( &xRunningThreadMutex ); - vPortFree( (void *)pxThreads ); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ -portBASE_TYPE xNumberOfThreads; -portBASE_TYPE xResult; - for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ ) - { - if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread ) - { - /* Kill all of the threads, they are in the detached state. */ - xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread ); - } - } - - /* Signal the scheduler to exit its loop. */ - xSchedulerEnd = pdTRUE; - (void)pthread_kill( hMainThread, SIG_RESUME ); -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Calling Yield from a Interrupt/Signal handler often doesn't work because the - * xSingleThreadMutex is already owned by an original call to Yield. Therefore, - * simply indicate that a yield is required soon. - */ - xPendYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - vPortDisableInterrupts(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - /* Check for unmatched exits. */ - if ( uxCriticalNesting > 0 ) - { - uxCriticalNesting--; - } - - /* If we have reached 0 then re-enable the interrupts. */ - if( uxCriticalNesting == 0 ) - { - /* Have we missed ticks? This is the equivalent of pending an interrupt. */ - if ( pdTRUE == xPendYield ) - { - xPendYield = pdFALSE; - vPortYield(); - } - vPortEnableInterrupts(); - } -} -/*-----------------------------------------------------------*/ - -void vPortYield( void ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; - - /** - * Sentinel - do not change context while the running task is not equal the task supposed to run - */ - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) - { - /** - * Make sure we don't create outdated resume signals - */ - while (hActiveThread!=hRequestedThread) { - sched_yield(); - } - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - vTaskSwitchContext(); - - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - hRequestedThread = xTaskToResume; - if ( xTaskToSuspend != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - /* Switch tasks. */ - prvResumeThread( xTaskToResume ); - //prvSuspendThread( xTaskToSuspend ); -if (prvGetThreadHandle(xTaskGetCurrentTaskHandle())!=xTaskToResume) { - debug_printf("\n what the fuck???? someone else did a switchcontext?!?\n"); -} - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - prvSuspendSignalHandler(SIG_SUSPEND); - return; - } - else - { - /* Yielding to self */ - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } - } -} -/*-----------------------------------------------------------*/ - -void vPortDisableInterrupts( void ) -{ - xInterruptsEnabled = pdFALSE; -} -/*-----------------------------------------------------------*/ - -void vPortEnableInterrupts( void ) -{ - xInterruptsEnabled = pdTRUE; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xPortSetInterruptMask( void ) -{ -portBASE_TYPE xReturn = xInterruptsEnabled; - xInterruptsEnabled = pdFALSE; - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vPortClearInterruptMask( portBASE_TYPE xMask ) -{ - xInterruptsEnabled = xMask; -} -/*-----------------------------------------------------------*/ - -/* - * Setup the systick timer to generate the tick interrupts at the required - * frequency. - */ -void prvSetupTimerInterrupt( void ) -{ -struct itimerval itimer, oitimer; -portTickType xMicroSeconds = portTICK_RATE_MICROSECONDS; - - debug_printf("init %li microseconds\n",(long)xMicroSeconds); - /* Initialise the structure with the current timer information. */ - if ( 0 == getitimer( TIMER_TYPE, &itimer ) ) - { - /* Set the interval between timer events. */ - itimer.it_interval.tv_sec = 0; - itimer.it_interval.tv_usec = xMicroSeconds; - - /* Set the current count-down. */ - itimer.it_value.tv_sec = 0; - itimer.it_value.tv_usec = xMicroSeconds; - - /* Set-up the timer interrupt. */ - if ( 0 != setitimer( TIMER_TYPE, &itimer, &oitimer ) ) - { - printf( "Set Timer problem.\n" ); - } - } - else - { - printf( "Get Timer problem.\n" ); - } -} -/*-----------------------------------------------------------*/ - -void vPortSystemTickHandler( int sig ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -struct timespec timeout; - - //debug_printf("received %i\n",sig); - /** - * do not call tick handler if - * - interrupts are disabled - * - tick handler is still running - * - old task switch not yet completed (wrong task running) - */ - if ( ( pdTRUE == xInterruptsEnabled ) && ( pdTRUE != xServicingTick ) && ( hRequestedThread == hActiveThread ) ) - { - if ( 0 == pthread_mutex_trylock( &xSuspendResumeThreadMutex ) ) - { - //debug_printf("will handle tick\n"); - xServicingTick = pdTRUE; - - /** - * this shouldn't ever happen - but WELL... - * Make sure we don't create outdated resume signals - */ - while (hActiveThread!=hRequestedThread) { - sched_yield(); - } - - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - /* Tick Increment. */ - vTaskIncrementTick(); - - /* Select Next Task. */ -#if ( configUSE_PREEMPTION == 1 ) - vTaskSwitchContext(); -#endif - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - hRequestedThread = xTaskToResume; - - /* The only thread that can process this tick is the running thread. */ - if ( xTaskToSuspend != xTaskToResume ) - { - /* Suspend the current task. */ - prvSuspendThread( xTaskToSuspend ); - timeout.tv_sec=0; - timeout.tv_nsec=10000; - //if ( 0 == pthread_mutex_timedlock( &xRunningThreadMutex,&timeout ) ) { - if ( 0 == pthread_mutex_lock( &xRunningThreadMutex) ) { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - /* Resume next task. */ - prvResumeThread( xTaskToResume ); -if (prvGetThreadHandle(xTaskGetCurrentTaskHandle())!=xTaskToResume) { - debug_printf("\n what the fuck???? someone else did a switchcontext?!?\n"); -} - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - } else { - debug_printf("Oh dear - tick handler could not acquire lock!\n\n"); - //prvResumeThread( xTaskToSuspend ); - xGeneralFuckedUpIndicator=3; - } - } - else - { - /* Release the lock as we are Resuming. */ - // (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - xServicingTick = pdFALSE; - } - else - { - xPendYield = pdTRUE; - } - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } - else - { - debug_printf("will NOT handle tick\n"); - xPendYield = pdTRUE; - } -} -/*-----------------------------------------------------------*/ - -void vPortForciblyEndThread( void *pxTaskToDelete ) -{ -xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete; -pthread_t xTaskToDelete; -pthread_t xTaskToResume; -portBASE_TYPE xResult; - -// if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) -// { - xTaskToDelete = prvGetThreadHandle( hTaskToDelete ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( xTaskToResume == xTaskToDelete ) - { - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) { - /** - * Make sure we don't create outdated resume signals - */ - while (hActiveThread!=hRequestedThread) { - sched_yield(); - } - /* This is a suicidal thread, need to select a different task to run. */ - vTaskSwitchContext(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - hRequestedThread = xTaskToResume; - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } else { - debug_printf("THIS was never meant to happen\n"); - exit(1); - } - } - - if ( pthread_self() != xTaskToDelete ) - { - /* Cancelling a thread that is not me. */ - if ( xTaskToDelete != ( pthread_t )NULL ) - { - /* Send a signal to wake the task so that it definitely cancels. */ - pthread_testcancel(); - xResult = pthread_cancel( xTaskToDelete ); - /* Pthread Clean-up function will note the cancellation. */ - } -// (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - else - { - /* Resume the other thread. */ - prvResumeThread( xTaskToResume ); - /* Pthread Clean-up function will note the cancellation. */ - /* Release the execution. */ - uxCriticalNesting = 0; - vPortEnableInterrupts(); -// (void)pthread_mutex_unlock( &xSingleThreadMutex ); - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - /* Commit suicide */ - pthread_exit( (void *)1 ); - } -// } -} -/*-----------------------------------------------------------*/ - -void *prvWaitForStart( void * pvParams ) -{ -xParams * pxParams = ( xParams * )pvParams; -pdTASK_CODE pvCode = pxParams->pxCode; -void * pParams = pxParams->pvParams; -sigset_t xSignals; - vPortFree( pvParams ); - - pthread_cleanup_push( prvDeleteThread, (void *)pthread_self() ); - - if ( 0 == pthread_mutex_lock( &xRunningThreadMutex ) ) - { - xSentinel=1; - - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - /* set up proc mask */ - pthread_sigmask(SIG_SETMASK,&xSignals,NULL); - - prvSuspendSignalHandler(SIG_SUSPEND); - //prvSuspendThread( pthread_self() ); - } else { - debug_printf("now this is just WRONG!\n"); - exit(1); - } - - pvCode( pParams ); - - pthread_cleanup_pop( 1 ); - return (void *)NULL; -} -/*-----------------------------------------------------------*/ - -void prvSuspendSignalHandler(int sig) -{ -sigset_t xSignals; -//sigset_t xPendingSignals; - - /* Only interested in the resume signal. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - sigaddset( &xSignals, SIG_SUSPEND ); - - /* Unlock the Running thread mutex to allow the resumed task to continue. */ - if ( 0 != pthread_mutex_unlock( &xRunningThreadMutex ) ) - { - printf( "Releasing someone else's lock.\n" ); - } - - //debug_printf("SUSPENDING until SIG_RESUME received\n"); - /* Wait on the resume signal. */ - while (hRequestedThread != pthread_self()) { - if ( 0 != sigwait( &xSignals, &sig ) ) - { - printf( "SSH: Sw %d\n", sig ); - /* tricky one - shouldn't ever happen - trying to resolve situation as graceful as possible */ - debug_printf("ALERT AAAAH PANIC! - sigwait failed.....\n\n\n"); - /* Signal main thread something just went HORRIBLY wrong */ - xGeneralFuckedUpIndicator = 2; - //(void)pthread_mutex_lock( &xRunningThreadMutex ); - //(void)pthread_kill( pthread_self(), SIG_SUSPEND ); - //return; - } else if (sig == SIG_RESUME) { - //debug_printf("received signal %i\n",sig); - /* Make sure the right thread received the signal */ - if (hRequestedThread != pthread_self() ) { - debug_printf( "ALERT! Received SIG_RESUME which is already outdated!\n active thread is %li\n",(long)hRequestedThread); - /* Signal main thread something just went wrong */ - xGeneralFuckedUpIndicator = 1; - /* - if (0 == sigpending(&xPendingSignals)) { - if (sigismember(&xPendingSignals,SIG_SUSPEND)) { - debug_printf( "reason: we slept too long...\n"); - //(void)sigwait(&xPendingSignals,&sig); - // we can safely return - signal is already pending - return; - } - } - debug_printf( "reason: unknown! - whatever ...\n\n"); - */ - //exit(1); - //(void)pthread_kill( xTaskToResume, SIG_RESUME ); - //(void)pthread_mutex_lock( &xRunningThreadMutex ); - //(void)pthread_kill( pthread_self(), SIG_SUSPEND ); - //return; - } - } - } - /* Yield the Scheduler to ensure that the yielding thread completes. */ - if ( 0 != pthread_mutex_lock( &xRunningThreadMutex ) ) - { - //(void)pthread_mutex_unlock( &xSingleThreadMutex ); - debug_printf("critical - mutex acquiring of active thread failed!\n"); - exit(1); - } - hActiveThread = pthread_self(); - - /* Will resume here when the SIG_RESUME signal is received. */ - /* Need to set the interrupts based on the task's critical nesting. */ - if ( uxCriticalNesting == 0 ) - { - vPortEnableInterrupts(); - } - else - { - vPortDisableInterrupts(); - } - if (hRequestedThread==pthread_self()) { - /* doesn't look too bad, does it? */ - xGeneralFuckedUpIndicator = 0; - } - //debug_printf("ACTIVE THREAD!\n"); -} -/*-----------------------------------------------------------*/ - -void prvSetupSignalsAndSchedulerPolicy( void ) -{ -/* The following code would allow for configuring the scheduling of this task as a Real-time task. - * The process would then need to be run with higher privileges for it to take affect. -int iPolicy; -int iResult; -int iSchedulerPriority; - iResult = pthread_getschedparam( pthread_self(), &iPolicy, &iSchedulerPriority ); - iResult = pthread_attr_setschedpolicy( &xThreadAttributes, SCHED_FIFO ); - iPolicy = SCHED_FIFO; - iResult = pthread_setschedparam( pthread_self(), iPolicy, &iSchedulerPriority ); */ - -struct sigaction sigsuspendself, sigresume, sigtick; -portLONG lIndex; - - pxThreads = ( xThreadState *)pvPortMalloc( sizeof( xThreadState ) * MAX_NUMBER_OF_TASKS ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = ( xTaskHandle )NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - sigsuspendself.sa_flags = 0; - sigsuspendself.sa_handler = prvSuspendSignalHandler; - sigfillset( &sigsuspendself.sa_mask ); - - sigresume.sa_flags = 0; - //sigresume.sa_handler = prvResumeSignalHandler; - sigresume.sa_handler = SIG_IGN; - sigfillset( &sigresume.sa_mask ); - - sigtick.sa_flags = 0; - //sigtick.sa_handler = vPortSystemTickHandler; - sigtick.sa_handler = SIG_IGN; - sigfillset( &sigtick.sa_mask ); - - if ( 0 != sigaction( SIG_SUSPEND, &sigsuspendself, NULL ) ) - { - printf( "Problem installing SIG_SUSPEND_SELF\n" ); - } - //if ( 0 != sigaction( SIG_RESUME, &sigresume, NULL ) ) - //{ - // printf( "Problem installing SIG_RESUME\n" ); - //} - if ( 0 != sigaction( SIG_TICK, &sigtick, NULL ) ) - { - printf( "Problem installing SIG_TICK\n" ); - } - printf( "Running as PID: %d\n", getpid() ); -} -/*-----------------------------------------------------------*/ - -pthread_t prvGetThreadHandle( xTaskHandle hTask ) -{ -pthread_t hThread = ( pthread_t )NULL; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hThread = pxThreads[ lIndex ].hThread; - break; - } - } - return hThread; -} -/*-----------------------------------------------------------*/ - -portLONG prvGetFreeThreadState( void ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )NULL ) - { - break; - } - } - - if ( MAX_NUMBER_OF_TASKS == lIndex ) - { - printf( "No more free threads, please increase the maximum.\n" ); - lIndex = 0; - vPortEndScheduler(); - } - - return lIndex; -} -/*-----------------------------------------------------------*/ - -void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - pxThreads[ lIndex ].uxCriticalNesting = uxNesting; - break; - } - } -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ) -{ -unsigned portBASE_TYPE uxNesting = 0; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - uxNesting = pxThreads[ lIndex ].uxCriticalNesting; - break; - } - } - return uxNesting; -} -/*-----------------------------------------------------------*/ - -void prvDeleteThread( void *xThreadId ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )xThreadId ) - { - pxThreads[ lIndex ].hThread = (pthread_t)NULL; - pxThreads[ lIndex ].hTask = (xTaskHandle)NULL; - if ( pxThreads[ lIndex ].uxCriticalNesting > 0 ) - { - uxCriticalNesting = 0; - vPortEnableInterrupts(); - } - pxThreads[ lIndex ].uxCriticalNesting = 0; - break; - } - } -} -/*-----------------------------------------------------------*/ - -void vPortAddTaskHandle( void *pxTaskHandle ) -{ -portLONG lIndex; - - pxThreads[ lIndexOfLastAddedTask ].hTask = ( xTaskHandle )pxTaskHandle; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == pxThreads[ lIndexOfLastAddedTask ].hThread ) - { - if ( pxThreads[ lIndex ].hTask != pxThreads[ lIndexOfLastAddedTask ].hTask ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - } - } -} -/*-----------------------------------------------------------*/ - -void vPortFindTicksPerSecond( void ) -{ - /* Needs to be reasonably high for accuracy. */ - unsigned long ulTicksPerSecond = sysconf(_SC_CLK_TCK); - printf( "Timer Resolution for Run TimeStats is %ld ticks per second.\n", ulTicksPerSecond ); -} -/*-----------------------------------------------------------*/ - -unsigned long ulPortGetTimerValue( void ) -{ -struct tms xTimes; - unsigned long ulTotalTime = times( &xTimes ); - /* Return the application code times. - * The timer only increases when the application code is actually running - * which means that the total execution times should add up to 100%. - */ - return ( unsigned long ) xTimes.tms_utime; - - /* Should check ulTotalTime for being clock_t max minus 1. */ - (void)ulTotalTime; -} -/*-----------------------------------------------------------*/ -/** - * Scheduler f***d up - we got to fix that - */ -void prvResolveFuckup( void ) -{ - - printf("Scheduler fucked up again - lets try to fix it...\n"); - printf("sending sig_suspend to thread that is supposed to be dead...\n"); - prvSuspendThread(hActiveThread); - printf("acquire running lock..."); - if ( 0 == pthread_mutex_lock( &xRunningThreadMutex) ) { - printf("sending sig_resume to thread that is supposed to be running...\n"); - prvResumeThread(hRequestedThread); - printf("giving up mutex...\n"); - (void)pthread_mutex_unlock(&xRunningThreadMutex); - } - -} -/*-----------------------------------------------------------*/ diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_test-for-macos.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_test-for-macos.c deleted file mode 100644 index 81af9bcec..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_test-for-macos.c +++ /dev/null @@ -1,1026 +0,0 @@ -/* - Copyright (C) 2009 William Davy - william.davy@wittenstein.co.uk - Contributed to FreeRTOS.org V5.3.0. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org 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 FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the Posix port. - *----------------------------------------------------------*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" -/*-----------------------------------------------------------*/ - -#define MAX_NUMBER_OF_TASKS ( _POSIX_THREAD_THREADS_MAX ) -/*-----------------------------------------------------------*/ - -/* Parameters to pass to the newly created pthread. */ -typedef struct XPARAMS -{ - pdTASK_CODE pxCode; - void *pvParams; -} xParams; - -/* Each task maintains its own interrupt status in the critical nesting variable. */ -typedef struct THREAD_SUSPENSIONS -{ - pthread_t hThread; - xTaskHandle hTask; - unsigned portBASE_TYPE uxCriticalNesting; -} xThreadState; -/*-----------------------------------------------------------*/ - -static xThreadState *pxThreads; -static pthread_once_t hSigSetupThread = PTHREAD_ONCE_INIT; -static pthread_attr_t xThreadAttributes; -static pthread_mutex_t xSuspendResumeThreadMutex = PTHREAD_MUTEX_INITIALIZER; -//static pthread_mutex_t xSingleThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xRunningThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_t hMainThread = ( pthread_t )NULL; -static pthread_t hActiveThread = ( pthread_t )NULL; -static pthread_t hRequestedThread = ( pthread_t )NULL; -/*-----------------------------------------------------------*/ - -static volatile portBASE_TYPE xSentinel = 0; -static volatile portBASE_TYPE xGeneralFuckedUpIndicator = 0; -static volatile portBASE_TYPE xVeryFirstTask = 1; -static volatile portBASE_TYPE xSchedulerEnd = pdFALSE; -static volatile portBASE_TYPE xInterruptsEnabled = pdTRUE; -static volatile portBASE_TYPE xServicingTick = pdFALSE; -static volatile portBASE_TYPE xPendYield = pdFALSE; -static volatile portLONG lIndexOfLastAddedTask = 0; -static volatile unsigned portBASE_TYPE uxCriticalNesting; -/*-----------------------------------------------------------*/ - -/* - * Setup the timer to generate the tick interrupts. - */ -static void prvSetupTimerInterrupt( void ); -static void *prvWaitForStart( void * pvParams ); -static void prvSuspendSignalHandler(int sig); -//static void prvResumeSignalHandler(int sig); -static void prvSetupSignalsAndSchedulerPolicy( void ); -static void prvSuspendThread( pthread_t xThreadId ); -static void prvResumeThread( pthread_t xThreadId ); -static pthread_t prvGetThreadHandle( xTaskHandle hTask ); -static portLONG prvGetFreeThreadState( void ); -static void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ); -static unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ); -static void prvDeleteThread( void *xThreadId ); -/*-----------------------------------------------------------*/ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ -#endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - -#if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ -#endif - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; -#endif - -#if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ -#endif - -#if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ -#endif - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ -#endif - -} tskTCB; - -tskTCB* debug_task_handle; -tskTCB* prvGetTaskHandle( pthread_t hThread ) -{ -portLONG lIndex; - - if (pxThreads==NULL) return NULL; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == hThread ) - { - return pxThreads[ lIndex ].hTask; - } - } - return NULL; -} - - -#define debug_printf(...) ( (real_pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%s(%li)\t%s\t%i:",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "__unknown__(%li)\t%s\t%i:",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?real_pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - -//int xbla; -//#define debug_printf(...) xbla=0 -int real_pthread_mutex_lock(pthread_mutex_t* mutex) { - return pthread_mutex_lock(mutex); -} -int real_pthread_mutex_unlock(pthread_mutex_t* mutex) { - return pthread_mutex_unlock(mutex); -} -#define pthread_mutex_lock(...) ( (debug_printf(" -!- pthread_mutex_lock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_lock(__VA_ARGS__):0 ) -#define pthread_mutex_unlock(...) ( (debug_printf(" -=- pthread_mutex_unlock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_unlock(__VA_ARGS__):0 ) -#define pthread_kill(thread,signal) ( (debug_printf(" sending signal %i to thread %li!\n",(int)signal,(long)thread)|1)?pthread_kill(thread,signal):0 ) -#define vTaskSwitchContext() ( (debug_printf("SWITCHCONTEXT!\n")|1)?vTaskSwitchContext():vTaskSwitchContext() ) -/*-----------------------------------------------------------*/ - -void prvSuspendThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult; -// xResult = pthread_mutex_lock( &xSuspendResumeThreadMutex ); -// if ( 0 == xResult ) -// { - /* Set-up for the Suspend Signal handler? */ - //xSentinel = 0; -//portBASE_TYPE aSentinel=xSentinel; - xResult = pthread_kill( xThreadId, SIG_SUSPEND ); -// xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); -// while ( ( aSentinel == xSentinel ) && ( pdTRUE != xServicingTick ) ) -// { -// sched_yield(); -// } -// } -} -/*-----------------------------------------------------------*/ - -void prvResumeThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult; -// if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) -// { - if ( pthread_self() != xThreadId ) - { - xResult = pthread_kill( xThreadId, SIG_RESUME ); - } -// xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); -// } -} -#define prvSuspendThread(thread) debug_printf("calling SuspendThread(%li)\n",(long)thread); prvSuspendThread(thread) -#define prvResumeThread(thread) debug_printf("calling ResumeThread(%li)\n",(long)thread); prvResumeThread(thread) - -/* - * Exception handlers. - */ -void vPortYield( void ); -void vPortSystemTickHandler( int sig ); - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -void vPortStartFirstTask( void ); -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ -/* Should actually keep this struct on the stack. */ -xParams *pxThisThreadParams = pvPortMalloc( sizeof( xParams ) ); - - (void)pthread_once( &hSigSetupThread, prvSetupSignalsAndSchedulerPolicy ); - - if ( (pthread_t)NULL == hMainThread ) - { - hMainThread = pthread_self(); - } - - /* No need to join the threads. */ - pthread_attr_init( &xThreadAttributes ); - pthread_attr_setdetachstate( &xThreadAttributes, PTHREAD_CREATE_DETACHED ); - - /* Add the task parameters. */ - pxThisThreadParams->pxCode = pxCode; - pxThisThreadParams->pvParams = pvParameters; - - vPortEnterCritical(); - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) { - while (hActiveThread!=hRequestedThread && !xVeryFirstTask) { - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - sched_yield(); - (void)pthread_mutex_lock( &xSuspendResumeThreadMutex ); - } - - - lIndexOfLastAddedTask = prvGetFreeThreadState(); - - /* Create the new pThread. */ - /* On creation of the very first thread, RunningThreadMutex is not claimed yet - * by the master thread - do that! */ - if (xVeryFirstTask==1) { - debug_printf("Seting up very first task (main) - MAIN is ACTIVE TASK\n"); - if (0 == pthread_mutex_lock( &xRunningThreadMutex)) { - xVeryFirstTask=0; - hActiveThread=pthread_self(); - hRequestedThread=hActiveThread; - } else { - printf("Failed to acquire lock for first task"); - exit(1); - } - - } - - if ( 0 != pthread_create( &( pxThreads[ lIndexOfLastAddedTask ].hThread ), &xThreadAttributes, prvWaitForStart, (void *)pxThisThreadParams ) ) - { - /* Thread create failed, signal the failure */ - pxTopOfStack = 0; - } - - /* Wait until the task suspends. */ - xSentinel=0; - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - while ( xSentinel == 0 ) { - sched_yield(); - } - (void)pthread_mutex_lock( &xRunningThreadMutex ); - hActiveThread=pthread_self(); - debug_printf("ACTIVE THREAD RECLAIMED!\n"); - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } else { - debug_printf("mutex locking failed\n"); - exit(1); - } - vPortExitCritical(); - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortStartFirstTask( void ) -{ - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - /* Start the first task. */ - vPortEnableInterrupts(); - - /* Start the first task. */ - hRequestedThread=prvGetThreadHandle( xTaskGetCurrentTaskHandle()); - prvResumeThread( hRequestedThread ); - - sched_yield(); -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ -portBASE_TYPE xResult; -int iSignal; -sigset_t xSignals; -sigset_t xSignalToBlock; -sigset_t xSignalsBlocked; -portLONG lIndex; - - /* Establish the signals to block before they are needed. */ - sigfillset( &xSignalToBlock ); - - /* Block until the end */ - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, &xSignalsBlocked ); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - /* Start the timer that generates the tick ISR. Interrupts are disabled - here already. */ - prvSetupTimerInterrupt(); - - /* Start the first task. Will not return unless all threads are killed. */ - vPortStartFirstTask(); - - /* This is the end signal we are looking for. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - sigaddset( &xSignals, SIG_TICK ); - - /* Allow other threads to run */ - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - debug_printf( "MAIN thread is entering main signal wait loop!\n"); - - while ( pdTRUE != xSchedulerEnd ) - { - if ( 0 != sigwait( &xSignals, &iSignal ) ) - { - printf( "Main thread spurious signal: %d\n", iSignal ); - } - /** - * Tick handler is called from here - AND ONLY FROM HERE - * (needed for cygwin - but should work on all) - */ - if (iSignal==SIG_TICK) { - vPortSystemTickHandler(iSignal); - } - if (iSignal==SIG_RESUME && pdTRUE != xSchedulerEnd) { - debug_printf("main: forwarding signal to %li\n",(long)hRequestedThread); - (void)pthread_kill( hRequestedThread, SIG_RESUME ); - } - } - - printf( "Cleaning Up, Exiting.\n" ); - /* Cleanup the mutexes */ - //xResult = pthread_mutex_destroy( &xSuspendResumeThreadMutex ); - //xResult = pthread_mutex_destroy( &xSingleThreadMutex ); - xResult = pthread_mutex_destroy( &xRunningThreadMutex ); - vPortFree( (void *)pxThreads ); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ -portBASE_TYPE xNumberOfThreads; -portBASE_TYPE xResult; - for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ ) - { - if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread ) - { - /* Kill all of the threads, they are in the detached state. */ - xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread ); - } - } - - /* Signal the scheduler to exit its loop. */ - xSchedulerEnd = pdTRUE; - (void)pthread_kill( hMainThread, SIG_RESUME ); -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Calling Yield from a Interrupt/Signal handler often doesn't work because the - * xSingleThreadMutex is already owned by an original call to Yield. Therefore, - * simply indicate that a yield is required soon. - */ - xPendYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - vPortDisableInterrupts(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - /* Check for unmatched exits. */ - if ( uxCriticalNesting > 0 ) - { - uxCriticalNesting--; - } - - /* If we have reached 0 then re-enable the interrupts. */ - if( uxCriticalNesting == 0 ) - { - /* Have we missed ticks? This is the equivalent of pending an interrupt. */ - if ( pdTRUE == xPendYield ) - { - xPendYield = pdFALSE; - vPortYield(); - } - vPortEnableInterrupts(); - } -} -/*-----------------------------------------------------------*/ - -void vPortYield( void ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; - - /** - * Sentinel - do not change context while the running task is not equal the task supposed to run - */ - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) - { - /** - * Make sure we don't create outdated resume signals - */ - while (hActiveThread!=hRequestedThread) { - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - sched_yield(); - (void)pthread_mutex_lock( &xSuspendResumeThreadMutex ); - } - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - vTaskSwitchContext(); - - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - if ( xTaskToSuspend != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - /* Switch tasks. */ - hRequestedThread = xTaskToResume; - prvResumeThread( xTaskToResume ); - //prvSuspendThread( xTaskToSuspend ); -if (prvGetThreadHandle(xTaskGetCurrentTaskHandle())!=xTaskToResume) { - debug_printf("\n what the fuck???? someone else did a switchcontext?!?\n"); -} - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - prvSuspendSignalHandler(SIG_SUSPEND); - return; - } - else - { - /* Yielding to self */ - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } - } -} -/*-----------------------------------------------------------*/ - -void vPortDisableInterrupts( void ) -{ - xInterruptsEnabled = pdFALSE; -} -/*-----------------------------------------------------------*/ - -void vPortEnableInterrupts( void ) -{ - xInterruptsEnabled = pdTRUE; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xPortSetInterruptMask( void ) -{ -portBASE_TYPE xReturn = xInterruptsEnabled; - xInterruptsEnabled = pdFALSE; - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vPortClearInterruptMask( portBASE_TYPE xMask ) -{ - xInterruptsEnabled = xMask; -} -/*-----------------------------------------------------------*/ - -/* - * Setup the systick timer to generate the tick interrupts at the required - * frequency. - */ -void prvSetupTimerInterrupt( void ) -{ -struct itimerval itimer, oitimer; -portTickType xMicroSeconds = portTICK_RATE_MICROSECONDS; - - debug_printf("init %li microseconds\n",(long)xMicroSeconds); - /* Initialise the structure with the current timer information. */ - if ( 0 == getitimer( TIMER_TYPE, &itimer ) ) - { - /* Set the interval between timer events. */ - itimer.it_interval.tv_sec = 0; - itimer.it_interval.tv_usec = xMicroSeconds; - - /* Set the current count-down. */ - itimer.it_value.tv_sec = 0; - itimer.it_value.tv_usec = xMicroSeconds; - - /* Set-up the timer interrupt. */ - if ( 0 != setitimer( TIMER_TYPE, &itimer, &oitimer ) ) - { - printf( "Set Timer problem.\n" ); - } - } - else - { - printf( "Get Timer problem.\n" ); - } -} -/*-----------------------------------------------------------*/ - -void vPortSystemTickHandler( int sig ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -struct timespec timeout; - - //debug_printf("received %i\n",sig); - /** - * do not call tick handler if - * - interrupts are disabled - * - tick handler is still running - * - old task switch not yet completed (wrong task running) - */ - if ( ( pdTRUE == xInterruptsEnabled ) && ( pdTRUE != xServicingTick ) && ( hRequestedThread == hActiveThread ) ) - { - xServicingTick = pdTRUE; - if ( 0 == pthread_mutex_trylock( &xSuspendResumeThreadMutex ) ) - { - debug_printf("does handle tick\n"); - - /** - * this shouldn't ever happen - but WELL... - * Make sure we don't create outdated resume signals - */ - if (hActiveThread!=hRequestedThread) { - xServicingTick = pdFALSE; - xPendYield = pdTRUE; - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - return; - } - - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - /* Tick Increment. */ - vTaskIncrementTick(); - - /* Select Next Task. */ -#if ( configUSE_PREEMPTION == 1 ) - vTaskSwitchContext(); -#endif - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - //hRequestedThread = xTaskToResume; - - /* The only thread that can process this tick is the running thread. */ - if ( xTaskToSuspend != xTaskToResume ) - { - /* Suspend the current task. */ - hRequestedThread = 0; - prvSuspendThread( xTaskToSuspend ); - timeout.tv_sec=0; - timeout.tv_nsec=10000; - /*while ( 0 != pthread_mutex_timedlock( &xRunningThreadMutex,&timeout ) ) { - prvSuspendThread( xTaskToSuspend ); - timeout.tv_sec=0; - timeout.tv_nsec=10000; - } - */ - if ( 0 != pthread_mutex_lock( &xRunningThreadMutex)) { - debug_printf("mutex lock failed!\n"); - exit(1); - } - //if ( 0 == pthread_mutex_lock( &xRunningThreadMutex) ) { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - /* Resume next task. */ - hRequestedThread = xTaskToResume; - prvResumeThread( xTaskToResume ); -if (prvGetThreadHandle(xTaskGetCurrentTaskHandle())!=xTaskToResume) { -debug_printf("\n what the fuck???? someone else did a switchcontext?!?\n"); -} - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - } - else - { - /* Release the lock as we are Resuming. */ - // (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - } - else - { - xPendYield = pdTRUE; - } - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - xServicingTick = pdFALSE; - } - else - { - debug_printf("will NOT handle tick\n"); - xPendYield = pdTRUE; - } -} -/*-----------------------------------------------------------*/ - -void vPortForciblyEndThread( void *pxTaskToDelete ) -{ -xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete; -pthread_t xTaskToDelete; -pthread_t xTaskToResume; -portBASE_TYPE xResult; - -// if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) -// { - xTaskToDelete = prvGetThreadHandle( hTaskToDelete ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( xTaskToResume == xTaskToDelete ) - { - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) { - /** - * Make sure we don't create outdated resume signals - */ - while (hActiveThread!=hRequestedThread) { - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - sched_yield(); - (void)pthread_mutex_lock( &xSuspendResumeThreadMutex ); - } - /* This is a suicidal thread, need to select a different task to run. */ - vTaskSwitchContext(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - hRequestedThread = xTaskToResume; - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } else { - debug_printf("mutex lock failed!\n"); - exit(1); - } - } - - if ( pthread_self() != xTaskToDelete ) - { - /* Cancelling a thread that is not me. */ - if ( xTaskToDelete != ( pthread_t )NULL ) - { - /* Send a signal to wake the task so that it definitely cancels. */ - pthread_testcancel(); - xResult = pthread_cancel( xTaskToDelete ); - /* Pthread Clean-up function will note the cancellation. */ - } -// (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - else - { - /* Resume the other thread. */ - prvResumeThread( xTaskToResume ); - /* Pthread Clean-up function will note the cancellation. */ - /* Release the execution. */ - uxCriticalNesting = 0; - vPortEnableInterrupts(); -// (void)pthread_mutex_unlock( &xSingleThreadMutex ); - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - /* Commit suicide */ - pthread_exit( (void *)1 ); - } -// } -} -/*-----------------------------------------------------------*/ - -void *prvWaitForStart( void * pvParams ) -{ -xParams * pxParams = ( xParams * )pvParams; -pdTASK_CODE pvCode = pxParams->pxCode; -void * pParams = pxParams->pvParams; -sigset_t xSignals; - vPortFree( pvParams ); - - pthread_cleanup_push( prvDeleteThread, (void *)pthread_self() ); - - if ( 0 == pthread_mutex_lock( &xRunningThreadMutex ) ) - { - xSentinel=1; - hActiveThread=pthread_self(); - debug_printf("temporarily made ACTIVE THREAD!\n"); - - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - /* set up proc mask */ - pthread_sigmask(SIG_SETMASK,&xSignals,NULL); - - prvSuspendSignalHandler(SIG_SUSPEND); - //prvSuspendThread( pthread_self() ); - } else { - debug_printf("now this is just WRONG!\n"); - exit(1); - } - - pvCode( pParams ); - - pthread_cleanup_pop( 1 ); - return (void *)NULL; -} -/*-----------------------------------------------------------*/ - -void prvSuspendSignalHandler(int sig) -{ -sigset_t xSignals; -//sigset_t xPendingSignals; - - /* Only interested in the resume signal. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - sigaddset( &xSignals, SIG_SUSPEND ); - - /* Unlock the Running thread mutex to allow the resumed task to continue. */ - if ( 0 != pthread_mutex_unlock( &xRunningThreadMutex ) ) - { - printf( "Releasing someone else's lock.\n" ); - } - - debug_printf("SUSPENDING until SIG_RESUME received\n"); - /* Wait on the resume signal. */ - while (hRequestedThread != pthread_self()) { - if ( 0 != sigwait( &xSignals, &sig ) ) - { - printf( "SSH: Sw %d\n", sig ); - /* tricky one - shouldn't ever happen - trying to resolve situation as graceful as possible */ - debug_printf("ALERT AAAAH PANIC! - sigwait failed.....\n\n\n"); - /* Signal main thread something just went HORRIBLY wrong */ - xGeneralFuckedUpIndicator = 2; - //(void)pthread_mutex_lock( &xRunningThreadMutex ); - //(void)pthread_kill( pthread_self(), SIG_SUSPEND ); - //return; - } else if (sig == SIG_RESUME) { - //debug_printf("received signal %i\n",sig); - /* Make sure the right thread received the signal */ - if (hRequestedThread != pthread_self() ) { - debug_printf( "resume_signalhandler: forwarding to %li\n",(long)hRequestedThread); - (void)pthread_kill( hRequestedThread, SIG_RESUME ); - } - } - } - /* Yield the Scheduler to ensure that the yielding thread completes. */ - if ( 0 != pthread_mutex_lock( &xRunningThreadMutex ) ) - { - //(void)pthread_mutex_unlock( &xSingleThreadMutex ); - debug_printf("critical - mutex acquiring of active thread failed!\n"); - exit(1); - } - hActiveThread = pthread_self(); - - /* Will resume here when the SIG_RESUME signal is received. */ - /* Need to set the interrupts based on the task's critical nesting. */ - if ( uxCriticalNesting == 0 ) - { - vPortEnableInterrupts(); - } - else - { - vPortDisableInterrupts(); - } - if (hRequestedThread==pthread_self()) { - /* doesn't look too bad, does it? */ - xGeneralFuckedUpIndicator = 0; - } - debug_printf("ACTIVE THREAD!\n"); -} -/*-----------------------------------------------------------*/ - -void prvSetupSignalsAndSchedulerPolicy( void ) -{ -/* The following code would allow for configuring the scheduling of this task as a Real-time task. - * The process would then need to be run with higher privileges for it to take affect. -int iPolicy; -int iResult; -int iSchedulerPriority; - iResult = pthread_getschedparam( pthread_self(), &iPolicy, &iSchedulerPriority ); - iResult = pthread_attr_setschedpolicy( &xThreadAttributes, SCHED_FIFO ); - iPolicy = SCHED_FIFO; - iResult = pthread_setschedparam( pthread_self(), iPolicy, &iSchedulerPriority ); */ - -struct sigaction sigsuspendself, sigresume, sigtick; -portLONG lIndex; - - pxThreads = ( xThreadState *)pvPortMalloc( sizeof( xThreadState ) * MAX_NUMBER_OF_TASKS ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = ( xTaskHandle )NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - sigsuspendself.sa_flags = 0; - sigsuspendself.sa_handler = prvSuspendSignalHandler; - sigfillset( &sigsuspendself.sa_mask ); - - sigresume.sa_flags = 0; - //sigresume.sa_handler = prvResumeSignalHandler; - sigresume.sa_handler = SIG_IGN; - sigfillset( &sigresume.sa_mask ); - - sigtick.sa_flags = 0; - //sigtick.sa_handler = vPortSystemTickHandler; - sigtick.sa_handler = SIG_IGN; - sigfillset( &sigtick.sa_mask ); - - if ( 0 != sigaction( SIG_SUSPEND, &sigsuspendself, NULL ) ) - { - printf( "Problem installing SIG_SUSPEND_SELF\n" ); - } - //if ( 0 != sigaction( SIG_RESUME, &sigresume, NULL ) ) - //{ - // printf( "Problem installing SIG_RESUME\n" ); - //} - if ( 0 != sigaction( SIG_TICK, &sigtick, NULL ) ) - { - printf( "Problem installing SIG_TICK\n" ); - } - printf( "Running as PID: %d\n", getpid() ); -} -/*-----------------------------------------------------------*/ - -pthread_t prvGetThreadHandle( xTaskHandle hTask ) -{ -pthread_t hThread = ( pthread_t )NULL; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hThread = pxThreads[ lIndex ].hThread; - break; - } - } - return hThread; -} -/*-----------------------------------------------------------*/ - -portLONG prvGetFreeThreadState( void ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )NULL ) - { - break; - } - } - - if ( MAX_NUMBER_OF_TASKS == lIndex ) - { - printf( "No more free threads, please increase the maximum.\n" ); - lIndex = 0; - vPortEndScheduler(); - } - - return lIndex; -} -/*-----------------------------------------------------------*/ - -void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - pxThreads[ lIndex ].uxCriticalNesting = uxNesting; - break; - } - } -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ) -{ -unsigned portBASE_TYPE uxNesting = 0; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - uxNesting = pxThreads[ lIndex ].uxCriticalNesting; - break; - } - } - return uxNesting; -} -/*-----------------------------------------------------------*/ - -void prvDeleteThread( void *xThreadId ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )xThreadId ) - { - pxThreads[ lIndex ].hThread = (pthread_t)NULL; - pxThreads[ lIndex ].hTask = (xTaskHandle)NULL; - if ( pxThreads[ lIndex ].uxCriticalNesting > 0 ) - { - uxCriticalNesting = 0; - vPortEnableInterrupts(); - } - pxThreads[ lIndex ].uxCriticalNesting = 0; - break; - } - } -} -/*-----------------------------------------------------------*/ - -void vPortAddTaskHandle( void *pxTaskHandle ) -{ -portLONG lIndex; - - pxThreads[ lIndexOfLastAddedTask ].hTask = ( xTaskHandle )pxTaskHandle; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == pxThreads[ lIndexOfLastAddedTask ].hThread ) - { - if ( pxThreads[ lIndex ].hTask != pxThreads[ lIndexOfLastAddedTask ].hTask ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - } - } -} -/*-----------------------------------------------------------*/ - -void vPortFindTicksPerSecond( void ) -{ - /* Needs to be reasonably high for accuracy. */ - unsigned long ulTicksPerSecond = sysconf(_SC_CLK_TCK); - printf( "Timer Resolution for Run TimeStats is %ld ticks per second.\n", ulTicksPerSecond ); -} -/*-----------------------------------------------------------*/ - -unsigned long ulPortGetTimerValue( void ) -{ -struct tms xTimes; - unsigned long ulTotalTime = times( &xTimes ); - /* Return the application code times. - * The timer only increases when the application code is actually running - * which means that the total execution times should add up to 100%. - */ - return ( unsigned long ) xTimes.tms_utime; - - /* Should check ulTotalTime for being clock_t max minus 1. */ - (void)ulTotalTime; -} -/*-----------------------------------------------------------*/ diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_with-debugging-output.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_with-debugging-output.c deleted file mode 100755 index a9679b712..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/port_with-debugging-output.c +++ /dev/null @@ -1,1097 +0,0 @@ -/* - Copyright (C) 2009 William Davy - william.davy@wittenstein.co.uk - Contributed to FreeRTOS.org V5.3.0. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org 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 FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the Posix port. - *----------------------------------------------------------*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" -/*-----------------------------------------------------------*/ - -#define MAX_NUMBER_OF_TASKS ( _POSIX_THREAD_THREADS_MAX ) -/*-----------------------------------------------------------*/ - -/* Parameters to pass to the newly created pthread. */ -typedef struct XPARAMS -{ - pdTASK_CODE pxCode; - void *pvParams; -} xParams; - -/* Each task maintains its own interrupt status in the critical nesting variable. */ -typedef struct THREAD_SUSPENSIONS -{ - pthread_t hThread; - xTaskHandle hTask; - unsigned portBASE_TYPE uxCriticalNesting; -} xThreadState; -/*-----------------------------------------------------------*/ - -static xThreadState *pxThreads; -static pthread_once_t hSigSetupThread = PTHREAD_ONCE_INIT; -static pthread_attr_t xThreadAttributes; -static pthread_mutex_t xSuspendResumeThreadMutex = PTHREAD_MUTEX_INITIALIZER; -//static pthread_mutex_t xSingleThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xRunningThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_t hMainThread = ( pthread_t )NULL; -static pthread_t hActiveThread = ( pthread_t )NULL; -static pthread_t hRequestedThread = ( pthread_t )NULL; -/*-----------------------------------------------------------*/ - -static volatile portBASE_TYPE xSentinel = 0; -static volatile portBASE_TYPE xGeneralFuckedUpIndicator = 0; -static volatile portBASE_TYPE xVeryFirstTask = 1; -static volatile portBASE_TYPE xSchedulerEnd = pdFALSE; -static volatile portBASE_TYPE xInterruptsEnabled = pdTRUE; -static volatile portBASE_TYPE xServicingTick = pdFALSE; -static volatile portBASE_TYPE xPendYield = pdFALSE; -static volatile portLONG lIndexOfLastAddedTask = 0; -static volatile unsigned portBASE_TYPE uxCriticalNesting; -/*-----------------------------------------------------------*/ - -/* - * Setup the timer to generate the tick interrupts. - */ -static void prvSetupTimerInterrupt( void ); -static void *prvWaitForStart( void * pvParams ); -static void prvSuspendSignalHandler(int sig); -//static void prvResumeSignalHandler(int sig); -static void prvSetupSignalsAndSchedulerPolicy( void ); -static void prvSuspendThread( pthread_t xThreadId ); -static void prvResumeThread( pthread_t xThreadId ); -static pthread_t prvGetThreadHandle( xTaskHandle hTask ); -static portLONG prvGetFreeThreadState( void ); -static void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ); -static unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ); -static void prvDeleteThread( void *xThreadId ); -static void prvResolveFuckup( void ); -/*-----------------------------------------------------------*/ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ -#endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - -#if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ -#endif - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; -#endif - -#if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ -#endif - -#if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ -#endif - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ -#endif - -} tskTCB; - -tskTCB* debug_task_handle; -tskTCB* prvGetTaskHandle( pthread_t hThread ) -{ -portLONG lIndex; - - if (pxThreads==NULL) return NULL; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == hThread ) - { - return pxThreads[ lIndex ].hTask; - } - } - return NULL; -} - - -#define debug_printf(...) ( (real_pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%s(%li)\t%s\t%i:",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "__unknown__(%li)\t%s\t%i:",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?real_pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - -//int xbla; -//#define debug_printf(...) xbla=0 -int real_pthread_mutex_lock(pthread_mutex_t* mutex) { - return pthread_mutex_lock(mutex); -} -int real_pthread_mutex_unlock(pthread_mutex_t* mutex) { - return pthread_mutex_unlock(mutex); -} -#define pthread_mutex_lock(...) ( (debug_printf(" -!- pthread_mutex_lock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_lock(__VA_ARGS__):0 ) -#define pthread_mutex_unlock(...) ( (debug_printf(" -=- pthread_mutex_unlock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_unlock(__VA_ARGS__):0 ) -#define pthread_mutex_trylock(...) ( pthread_mutex_trylock(__VA_ARGS__)==0?((debug_printf(" -:)- pthread_mutex_trylock(%s) success\n",#__VA_ARGS__)|1)?0:0):-1) -#define pthread_kill(thread,signal) ( (debug_printf(" sending signal %i to thread %li!\n",(int)signal,(long)thread)|1)?pthread_kill(thread,signal):0 ) -#define vTaskSwitchContext() ( (debug_printf("SWITCHCONTEXT!\n")|1)?vTaskSwitchContext():vTaskSwitchContext() ) -/*-----------------------------------------------------------*/ - -void prvSuspendThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult; -// xResult = pthread_mutex_lock( &xSuspendResumeThreadMutex ); -// if ( 0 == xResult ) -// { - /* Set-up for the Suspend Signal handler? */ - //xSentinel = 0; -//portBASE_TYPE aSentinel=xSentinel; - xResult = pthread_kill( xThreadId, SIG_SUSPEND ); -// xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); -// while ( ( aSentinel == xSentinel ) && ( pdTRUE != xServicingTick ) ) -// { -// sched_yield(); -// } -// } -} -/*-----------------------------------------------------------*/ - -void prvResumeThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult; -// if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) -// { - if ( pthread_self() != xThreadId ) - { - xResult = pthread_kill( xThreadId, SIG_RESUME ); - } -// xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); -// } -} -#define prvSuspendThread(thread) debug_printf("calling SuspendThread(%li)\n",(long)thread); prvSuspendThread(thread) -#define prvResumeThread(thread) debug_printf("calling ResumeThread(%li)\n",(long)thread); prvResumeThread(thread) - -/* - * Exception handlers. - */ -void vPortYield( void ); -void vPortSystemTickHandler( int sig ); - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -void vPortStartFirstTask( void ); -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ -/* Should actually keep this struct on the stack. */ -xParams *pxThisThreadParams = pvPortMalloc( sizeof( xParams ) ); - - (void)pthread_once( &hSigSetupThread, prvSetupSignalsAndSchedulerPolicy ); - - if ( (pthread_t)NULL == hMainThread ) - { - hMainThread = pthread_self(); - } - - /* No need to join the threads. */ - pthread_attr_init( &xThreadAttributes ); - pthread_attr_setdetachstate( &xThreadAttributes, PTHREAD_CREATE_DETACHED ); - - /* Add the task parameters. */ - pxThisThreadParams->pxCode = pxCode; - pxThisThreadParams->pvParams = pvParameters; - - vPortEnterCritical(); - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) { - while (hActiveThread!=hRequestedThread && !xVeryFirstTask) { - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - sched_yield(); - (void)pthread_mutex_lock( &xSuspendResumeThreadMutex ); - } - - - lIndexOfLastAddedTask = prvGetFreeThreadState(); - - /* Create the new pThread. */ - /* On creation of the very first thread, RunningThreadMutex is not claimed yet - * by the master thread - do that! */ - if (xVeryFirstTask==1) { - debug_printf("Seting up very first task (main) - MAIN is ACTIVE TASK\n"); - if (0 == pthread_mutex_lock( &xRunningThreadMutex)) { - xVeryFirstTask=0; - hActiveThread=pthread_self(); - hRequestedThread=hActiveThread; - } else { - printf("Failed to acquire lock for first task"); - exit(1); - } - - } - - if ( 0 != pthread_create( &( pxThreads[ lIndexOfLastAddedTask ].hThread ), &xThreadAttributes, prvWaitForStart, (void *)pxThisThreadParams ) ) - { - /* Thread create failed, signal the failure */ - pxTopOfStack = 0; - } - - /* Wait until the task suspends. */ - xSentinel=0; - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - while ( xSentinel == 0 ) { - sched_yield(); - } - (void)pthread_mutex_lock( &xRunningThreadMutex ); - hActiveThread=pthread_self(); - debug_printf("ACTIVE THREAD RECLAIMED!\n"); - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } else { - debug_printf("mutex locking failed\n"); - exit(1); - } - vPortExitCritical(); - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortStartFirstTask( void ) -{ - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - /* Start the first task. */ - vPortEnableInterrupts(); - - /* Start the first task. */ - hRequestedThread=prvGetThreadHandle( xTaskGetCurrentTaskHandle()); - prvResumeThread( hRequestedThread ); - - sched_yield(); -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ -portBASE_TYPE xResult; -int iSignal; -int fuckedUpCount=0; -sigset_t xSignals; -sigset_t xSignalToBlock; -sigset_t xSignalsBlocked; -portLONG lIndex; - - /* Establish the signals to block before they are needed. */ - sigfillset( &xSignalToBlock ); - - /* Block until the end */ - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, &xSignalsBlocked ); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - /* Start the timer that generates the tick ISR. Interrupts are disabled - here already. */ - prvSetupTimerInterrupt(); - - /* Start the first task. Will not return unless all threads are killed. */ - vPortStartFirstTask(); - - /* This is the end signal we are looking for. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - sigaddset( &xSignals, SIG_TICK ); - - /* Allow other threads to run */ - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - debug_printf( "MAIN thread is entering main signal wait loop!\n"); - - while ( pdTRUE != xSchedulerEnd ) - { - if ( 0 != sigwait( &xSignals, &iSignal ) ) - { - printf( "Main thread spurious signal: %d\n", iSignal ); - } - /** - * Tick handler is called from here - AND ONLY FROM HERE - * (needed for cygwin - but should work on all) - */ - if (iSignal==SIG_TICK) { - if (xGeneralFuckedUpIndicator!=0 && hActiveThread!=hRequestedThread) { - fuckedUpCount++; - if (fuckedUpCount>10) { - fuckedUpCount=0; - prvResolveFuckup(); - } - } else { - fuckedUpCount=0; - } - vPortSystemTickHandler(iSignal); - } - if (iSignal==SIG_RESUME && pdTRUE != xSchedulerEnd) { - debug_printf( "ALERT! Main received SIG_RESUME that was supposed to go elsewhere!"); - } - } - - printf( "Cleaning Up, Exiting.\n" ); - /* Cleanup the mutexes */ - //xResult = pthread_mutex_destroy( &xSuspendResumeThreadMutex ); - //xResult = pthread_mutex_destroy( &xSingleThreadMutex ); - xResult = pthread_mutex_destroy( &xRunningThreadMutex ); - vPortFree( (void *)pxThreads ); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ -portBASE_TYPE xNumberOfThreads; -portBASE_TYPE xResult; - for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ ) - { - if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread ) - { - /* Kill all of the threads, they are in the detached state. */ - xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread ); - } - } - - /* Signal the scheduler to exit its loop. */ - xSchedulerEnd = pdTRUE; - (void)pthread_kill( hMainThread, SIG_RESUME ); -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Calling Yield from a Interrupt/Signal handler often doesn't work because the - * xSingleThreadMutex is already owned by an original call to Yield. Therefore, - * simply indicate that a yield is required soon. - */ - xPendYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - vPortDisableInterrupts(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - /* Check for unmatched exits. */ - if ( uxCriticalNesting > 0 ) - { - uxCriticalNesting--; - } - - /* If we have reached 0 then re-enable the interrupts. */ - if( uxCriticalNesting == 0 ) - { - /* Have we missed ticks? This is the equivalent of pending an interrupt. */ - if ( pdTRUE == xPendYield ) - { - xPendYield = pdFALSE; - vPortYield(); - } - vPortEnableInterrupts(); - } -} -/*-----------------------------------------------------------*/ - -void vPortYield( void ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; - - /** - * Sentinel - do not change context while the running task is not equal the task supposed to run - */ -// if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) - while ( 0 != pthread_mutex_trylock ( &xSuspendResumeThreadMutex ) ) { - sched_yield(); - } - - /** - * Make sure we don't create outdated resume signals - */ - while (hActiveThread!=hRequestedThread) { - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - sched_yield(); - while (0 != pthread_mutex_trylock( &xSuspendResumeThreadMutex )) { - sched_yield(); - } - } - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - vTaskSwitchContext(); - - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - if ( xTaskToSuspend != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - /* Switch tasks. */ - hRequestedThread = xTaskToResume; - prvResumeThread( xTaskToResume ); - //prvSuspendThread( xTaskToSuspend ); -if (prvGetThreadHandle(xTaskGetCurrentTaskHandle())!=xTaskToResume) { -debug_printf("\n what the fuck???? someone else did a switchcontext?!?\n"); -} - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - prvSuspendSignalHandler(SIG_SUSPEND); - return; - } - else - { - /* Yielding to self */ - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } -} -/*-----------------------------------------------------------*/ - -void vPortDisableInterrupts( void ) -{ - xInterruptsEnabled = pdFALSE; -} -/*-----------------------------------------------------------*/ - -void vPortEnableInterrupts( void ) -{ - xInterruptsEnabled = pdTRUE; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xPortSetInterruptMask( void ) -{ -portBASE_TYPE xReturn = xInterruptsEnabled; - xInterruptsEnabled = pdFALSE; - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vPortClearInterruptMask( portBASE_TYPE xMask ) -{ - xInterruptsEnabled = xMask; -} -/*-----------------------------------------------------------*/ - -/* - * Setup the systick timer to generate the tick interrupts at the required - * frequency. - */ -void prvSetupTimerInterrupt( void ) -{ -struct itimerval itimer, oitimer; -portTickType xMicroSeconds = portTICK_RATE_MICROSECONDS; - - debug_printf("init %li microseconds\n",(long)xMicroSeconds); - /* Initialise the structure with the current timer information. */ - if ( 0 == getitimer( TIMER_TYPE, &itimer ) ) - { - /* Set the interval between timer events. */ - itimer.it_interval.tv_sec = 0; - itimer.it_interval.tv_usec = xMicroSeconds; - - /* Set the current count-down. */ - itimer.it_value.tv_sec = 0; - itimer.it_value.tv_usec = xMicroSeconds; - - /* Set-up the timer interrupt. */ - if ( 0 != setitimer( TIMER_TYPE, &itimer, &oitimer ) ) - { - printf( "Set Timer problem.\n" ); - } - } - else - { - printf( "Get Timer problem.\n" ); - } -} -/*-----------------------------------------------------------*/ - -void vPortSystemTickHandler( int sig ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -struct timespec timeout; - - //debug_printf("received %i\n",sig); - /** - * do not call tick handler if - * - interrupts are disabled - * - tick handler is still running - * - old task switch not yet completed (wrong task running) - */ - if ( ( pdTRUE == xInterruptsEnabled ) && ( pdTRUE != xServicingTick ) && ( hRequestedThread == hActiveThread ) ) - { - xServicingTick = pdTRUE; - if ( 0 == pthread_mutex_trylock( &xSuspendResumeThreadMutex ) ) - { - debug_printf("does handle tick\n"); - - /** - * this shouldn't ever happen - but WELL... - * Make sure we don't create outdated resume signals - */ - if (hActiveThread!=hRequestedThread) { - xServicingTick = pdFALSE; - xPendYield = pdTRUE; - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - return; - } - - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - /* Tick Increment. */ - vTaskIncrementTick(); - - /* Select Next Task. */ -#if ( configUSE_PREEMPTION == 1 ) - vTaskSwitchContext(); -#endif - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - //hRequestedThread = xTaskToResume; - - /* The only thread that can process this tick is the running thread. */ - if ( xTaskToSuspend != xTaskToResume ) - { - /* Suspend the current task. */ - hRequestedThread = 0; - prvSuspendThread( xTaskToSuspend ); - //timeout.tv_sec=0; - //timeout.tv_nsec=10000; - //sched_yield(); - while ( 0 != pthread_mutex_lock( &xRunningThreadMutex) ) { - prvSuspendThread( xTaskToSuspend ); - timeout.tv_sec=0; - timeout.tv_nsec=1; - nanosleep(&timeout,0); - } - //if ( 0 == pthread_mutex_lock( &xRunningThreadMutex) ) { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - /* Resume next task. */ - hRequestedThread = xTaskToResume; - prvResumeThread( xTaskToResume ); -if (prvGetThreadHandle(xTaskGetCurrentTaskHandle())!=xTaskToResume) { -debug_printf("\n what the fuck???? someone else did a switchcontext?!?\n"); -} - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - } - else - { - /* Release the lock as we are Resuming. */ - // (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - } - else - { - xPendYield = pdTRUE; - } - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - xServicingTick = pdFALSE; - } - else - { - debug_printf("will NOT handle tick\n"); - xPendYield = pdTRUE; - } -} -/*-----------------------------------------------------------*/ - -void vPortForciblyEndThread( void *pxTaskToDelete ) -{ -xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete; -pthread_t xTaskToDelete; -pthread_t xTaskToResume; -portBASE_TYPE xResult; - -// if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) -// { - xTaskToDelete = prvGetThreadHandle( hTaskToDelete ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( xTaskToResume == xTaskToDelete ) - { - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) { - /** - * Make sure we don't create outdated resume signals - */ - while (hActiveThread!=hRequestedThread) { - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - sched_yield(); - (void)pthread_mutex_lock( &xSuspendResumeThreadMutex ); - } - /* This is a suicidal thread, need to select a different task to run. */ - vTaskSwitchContext(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - hRequestedThread = xTaskToResume; - (void)pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } else { - debug_printf("mutex lock failed!\n"); - exit(1); - } - } - - if ( pthread_self() != xTaskToDelete ) - { - /* Cancelling a thread that is not me. */ - if ( xTaskToDelete != ( pthread_t )NULL ) - { - /* Send a signal to wake the task so that it definitely cancels. */ - pthread_testcancel(); - xResult = pthread_cancel( xTaskToDelete ); - /* Pthread Clean-up function will note the cancellation. */ - } -// (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - else - { - /* Resume the other thread. */ - prvResumeThread( xTaskToResume ); - /* Pthread Clean-up function will note the cancellation. */ - /* Release the execution. */ - uxCriticalNesting = 0; - vPortEnableInterrupts(); -// (void)pthread_mutex_unlock( &xSingleThreadMutex ); - (void)pthread_mutex_unlock( &xRunningThreadMutex ); - /* Commit suicide */ - pthread_exit( (void *)1 ); - } -// } -} -/*-----------------------------------------------------------*/ - -void *prvWaitForStart( void * pvParams ) -{ -xParams * pxParams = ( xParams * )pvParams; -pdTASK_CODE pvCode = pxParams->pxCode; -void * pParams = pxParams->pvParams; -sigset_t xSignals; - vPortFree( pvParams ); - - pthread_cleanup_push( prvDeleteThread, (void *)pthread_self() ); - - if ( 0 == pthread_mutex_lock( &xRunningThreadMutex ) ) - { - xSentinel=1; - hActiveThread=pthread_self(); - debug_printf("temporarily made ACTIVE THREAD!\n"); - - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - /* set up proc mask */ - pthread_sigmask(SIG_SETMASK,&xSignals,NULL); - - prvSuspendSignalHandler(SIG_SUSPEND); - //prvSuspendThread( pthread_self() ); - } else { - debug_printf("now this is just WRONG!\n"); - exit(1); - } - - pvCode( pParams ); - - pthread_cleanup_pop( 1 ); - return (void *)NULL; -} -/*-----------------------------------------------------------*/ - -void prvSuspendSignalHandler(int sig) -{ -sigset_t xSignals; -//sigset_t xPendingSignals; - - /* Only interested in the resume signal. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - sigaddset( &xSignals, SIG_SUSPEND ); - - /* Unlock the Running thread mutex to allow the resumed task to continue. */ - if ( 0 != pthread_mutex_unlock( &xRunningThreadMutex ) ) - { - printf( "Releasing someone else's lock.\n" ); - } - - debug_printf("SUSPENDING until SIG_RESUME received\n"); - /* Wait on the resume signal. */ - while (hRequestedThread != pthread_self()) { - if ( 0 != sigwait( &xSignals, &sig ) ) - { - //printf( "SSH: Sw %d\n", sig ); - /* tricky one - shouldn't ever happen - trying to resolve situation as graceful as possible */ - debug_printf("ALERT AAAAH PANIC! - sigwait failed.....\n\n\n"); - /* Signal main thread something just went HORRIBLY wrong */ - xGeneralFuckedUpIndicator = 2; - sched_yield(); - //(void)pthread_mutex_lock( &xRunningThreadMutex ); - //(void)pthread_kill( pthread_self(), SIG_SUSPEND ); - //return; - } else if (sig == SIG_RESUME) { - //debug_printf("received signal %i\n",sig); - /* Make sure the right thread received the signal */ - if (hRequestedThread != pthread_self() ) { - debug_printf( "ALERT! Received SIG_RESUME which is already outdated!\n active thread is %li\n",(long)hRequestedThread); - /* Signal main thread something just went wrong */ - xGeneralFuckedUpIndicator = 1; - /* - if (0 == sigpending(&xPendingSignals)) { - if (sigismember(&xPendingSignals,SIG_SUSPEND)) { - debug_printf( "reason: we slept too long...\n"); - //(void)sigwait(&xPendingSignals,&sig); - // we can safely return - signal is already pending - return; - } - } - debug_printf( "reason: unknown! - whatever ...\n\n"); - */ - //exit(1); - //(void)pthread_kill( xTaskToResume, SIG_RESUME ); - //(void)pthread_mutex_lock( &xRunningThreadMutex ); - //(void)pthread_kill( pthread_self(), SIG_SUSPEND ); - //return; - } - } - } - /* Yield the Scheduler to ensure that the yielding thread completes. */ - if ( 0 != pthread_mutex_lock( &xRunningThreadMutex ) ) - { - //(void)pthread_mutex_unlock( &xSingleThreadMutex ); - debug_printf("critical - mutex acquiring of active thread failed!\n"); - exit(1); - } - hActiveThread = pthread_self(); - - /* Will resume here when the SIG_RESUME signal is received. */ - /* Need to set the interrupts based on the task's critical nesting. */ - if ( uxCriticalNesting == 0 ) - { - vPortEnableInterrupts(); - } - else - { - vPortDisableInterrupts(); - } - if (hRequestedThread==pthread_self()) { - /* doesn't look too bad, does it? */ - xGeneralFuckedUpIndicator = 0; - } - debug_printf("ACTIVE THREAD!\n"); -} -/*-----------------------------------------------------------*/ - -void prvSetupSignalsAndSchedulerPolicy( void ) -{ -/* The following code would allow for configuring the scheduling of this task as a Real-time task. - * The process would then need to be run with higher privileges for it to take affect. -int iPolicy; -int iResult; -int iSchedulerPriority; - iResult = pthread_getschedparam( pthread_self(), &iPolicy, &iSchedulerPriority ); - iResult = pthread_attr_setschedpolicy( &xThreadAttributes, SCHED_FIFO ); - iPolicy = SCHED_FIFO; - iResult = pthread_setschedparam( pthread_self(), iPolicy, &iSchedulerPriority ); */ - -struct sigaction sigsuspendself, sigresume, sigtick; -portLONG lIndex; - - pxThreads = ( xThreadState *)pvPortMalloc( sizeof( xThreadState ) * MAX_NUMBER_OF_TASKS ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = ( xTaskHandle )NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - sigsuspendself.sa_flags = 0; - sigsuspendself.sa_handler = prvSuspendSignalHandler; - sigfillset( &sigsuspendself.sa_mask ); - - sigresume.sa_flags = 0; - //sigresume.sa_handler = prvResumeSignalHandler; - sigresume.sa_handler = SIG_IGN; - sigfillset( &sigresume.sa_mask ); - - sigtick.sa_flags = 0; - //sigtick.sa_handler = vPortSystemTickHandler; - sigtick.sa_handler = SIG_IGN; - sigfillset( &sigtick.sa_mask ); - - if ( 0 != sigaction( SIG_SUSPEND, &sigsuspendself, NULL ) ) - { - printf( "Problem installing SIG_SUSPEND_SELF\n" ); - } - //if ( 0 != sigaction( SIG_RESUME, &sigresume, NULL ) ) - //{ - // printf( "Problem installing SIG_RESUME\n" ); - //} - if ( 0 != sigaction( SIG_TICK, &sigtick, NULL ) ) - { - printf( "Problem installing SIG_TICK\n" ); - } - printf( "Running as PID: %d\n", getpid() ); -} -/*-----------------------------------------------------------*/ - -pthread_t prvGetThreadHandle( xTaskHandle hTask ) -{ -pthread_t hThread = ( pthread_t )NULL; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hThread = pxThreads[ lIndex ].hThread; - break; - } - } - return hThread; -} -/*-----------------------------------------------------------*/ - -portLONG prvGetFreeThreadState( void ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )NULL ) - { - break; - } - } - - if ( MAX_NUMBER_OF_TASKS == lIndex ) - { - printf( "No more free threads, please increase the maximum.\n" ); - lIndex = 0; - vPortEndScheduler(); - } - - return lIndex; -} -/*-----------------------------------------------------------*/ - -void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - pxThreads[ lIndex ].uxCriticalNesting = uxNesting; - break; - } - } -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ) -{ -unsigned portBASE_TYPE uxNesting = 0; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - uxNesting = pxThreads[ lIndex ].uxCriticalNesting; - break; - } - } - return uxNesting; -} -/*-----------------------------------------------------------*/ - -void prvDeleteThread( void *xThreadId ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )xThreadId ) - { - pxThreads[ lIndex ].hThread = (pthread_t)NULL; - pxThreads[ lIndex ].hTask = (xTaskHandle)NULL; - if ( pxThreads[ lIndex ].uxCriticalNesting > 0 ) - { - uxCriticalNesting = 0; - vPortEnableInterrupts(); - } - pxThreads[ lIndex ].uxCriticalNesting = 0; - break; - } - } -} -/*-----------------------------------------------------------*/ - -void vPortAddTaskHandle( void *pxTaskHandle ) -{ -portLONG lIndex; - - pxThreads[ lIndexOfLastAddedTask ].hTask = ( xTaskHandle )pxTaskHandle; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == pxThreads[ lIndexOfLastAddedTask ].hThread ) - { - if ( pxThreads[ lIndex ].hTask != pxThreads[ lIndexOfLastAddedTask ].hTask ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - } - } -} -/*-----------------------------------------------------------*/ - -void vPortFindTicksPerSecond( void ) -{ - /* Needs to be reasonably high for accuracy. */ - unsigned long ulTicksPerSecond = sysconf(_SC_CLK_TCK); - printf( "Timer Resolution for Run TimeStats is %ld ticks per second.\n", ulTicksPerSecond ); -} -/*-----------------------------------------------------------*/ - -unsigned long ulPortGetTimerValue( void ) -{ -struct tms xTimes; - unsigned long ulTotalTime = times( &xTimes ); - /* Return the application code times. - * The timer only increases when the application code is actually running - * which means that the total execution times should add up to 100%. - */ - return ( unsigned long ) xTimes.tms_utime; - - /* Should check ulTotalTime for being clock_t max minus 1. */ - (void)ulTotalTime; -} -/*-----------------------------------------------------------*/ -/** - * Scheduler f***d up - we got to fix that - */ -void prvResolveFuckup( void ) -{ -struct timespec timeout; -pthread_t xTaskToResume; - - (void)pthread_mutex_lock ( &xSuspendResumeThreadMutex); - if (hActiveThread == hRequestedThread) { - debug_printf("emergency handler started - but not needed - returning\n"); - return; - } - printf("\nScheduler fucked up again - lets try to fix it...\n"); - if (hRequestedThread==0) { - printf("\nno supposedly active thread - fixing\n"); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - } else { - xTaskToResume = hRequestedThread; - } - printf("\nsending sig_suspend to thread that is supposed to be dead...\n"); - prvSuspendThread(hActiveThread); - printf("\nacquire running lock...\n"); - //timeout.tv_sec=0; - //timeout.tv_nsec=100; - sched_yield(); - while ( 0 != pthread_mutex_trylock( &xRunningThreadMutex) ) { - prvSuspendThread(hActiveThread); - timeout.tv_sec=0; - timeout.tv_nsec=1; - nanosleep(&timeout,NULL); - } - printf("\nsending sig_resume to thread that is supposed to be running...\n"); - prvResumeThread(xTaskToResume); - printf("\ngiving up mutex...\n"); - (void)pthread_mutex_unlock(&xRunningThreadMutex); - (void)pthread_mutex_unlock ( &xSuspendResumeThreadMutex); - -} -/*-----------------------------------------------------------*/ diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/scheduler.txt b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/scheduler.txt deleted file mode 100644 index dc1815cea..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/scheduler.txt +++ /dev/null @@ -1,42 +0,0 @@ -thread initial START: - -master gives up running mutex -master waits for sentinel set -master akquires running mutex - -thread akquires RUNNING_MUTEX -threads sets sentinel -thread suspends itself - - - -thread SUSPEND: - -thread gives up RUNNING_MUTEX -thread waits for sig_resume -thread akquires RUNNING_MUTEX -thread runs - - -thread END: - -if other: -delete the other thread -if self: -thread gives up RUNNING_MUTEX -thread sends sig_resume to new active thread -thread self kills - - -thread YIELD -thread sends sig_resume to new active thread -thread suspends itself - - -time tick yield -tick handler sends SUSPEND to running thread -tick handler akquires RUNNING_MUTEX -tick handler sends sig_resume to new active thread -tock handler gives up RUNNING_MUTEX -tick handler ends - diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_1_sleep.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_1_sleep.c deleted file mode 100644 index b173eb9bc..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_1_sleep.c +++ /dev/null @@ -1,35 +0,0 @@ -/** - * small test program whether signals between threads work as they should - */ - -#include -#include -#include - -void sighandler(int sig) { - write(2,".",1); - return; -} - -void* threadstart(void* arg) { - - while (1) { - sleep(1); - } -} - -int main(char** argc, int argv) { - - pthread_t testthread1; - struct sigaction action; - - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - pthread_create(&testthread1,NULL,threadstart,NULL); - while (1) { - pthread_kill(testthread1,SIGUSR1); - } -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_2_nanosleep.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_2_nanosleep.c deleted file mode 100644 index c01679a18..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_2_nanosleep.c +++ /dev/null @@ -1,38 +0,0 @@ -/** - * small test program whether signals between threads work as they should - */ - -#include -#include -#include - -void sighandler(int sig) { - write(2,".",1); - return; -} - -void* threadstart(void* arg) { -struct timespec sleeptime; - - while (1) { - sleeptime.tv_sec=1; - sleeptime.tv_nsec=0; - nanosleep(&sleeptime,NULL); - } -} - -int main(char** argc, int argv) { - - pthread_t testthread1; - struct sigaction action; - - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - pthread_create(&testthread1,NULL,threadstart,NULL); - while (1) { - pthread_kill(testthread1,SIGUSR1); - } -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_3_select.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_3_select.c deleted file mode 100644 index 9fc852774..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_3_select.c +++ /dev/null @@ -1,40 +0,0 @@ -/** - * small test program whether signals between threads work as they should - */ - -#include -#include -#include -#include -#include - -void sighandler(int sig) { - write(2,".",1); - return; -} - -void* threadstart(void* arg) { -struct timeval sleeptime; - - while (1) { - sleeptime.tv_sec=1; - sleeptime.tv_usec=0; - select(0,NULL,NULL,NULL,&sleeptime); - } -} - -int main(char** argc, int argv) { - - pthread_t testthread1; - struct sigaction action; - - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - pthread_create(&testthread1,NULL,threadstart,NULL); - while (1) { - pthread_kill(testthread1,SIGUSR1); - } -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_4_mutex_lock.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_4_mutex_lock.c deleted file mode 100644 index d5bf3119f..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_4_mutex_lock.c +++ /dev/null @@ -1,41 +0,0 @@ -/** - * small etst program whether signals between threads work as they should - */ - -#include -#include - -static pthread_mutex_t Mutex = PTHREAD_MUTEX_INITIALIZER; - -/** - * actual test program - */ - -void sighandler(int sig) { - write(2,".",1); - return; -} - -void* threadstart(void* arg) { - - while (1) { - pthread_mutex_lock(&Mutex); - } -} - -int main(char** argc, int argv) { - - pthread_t testthread1; - struct sigaction action; - - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - pthread_mutex_lock(&Mutex); - pthread_create(&testthread1,NULL,threadstart,NULL); - while (1) { - pthread_kill(testthread1,SIGUSR1); - } -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_5_pselect.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_5_pselect.c deleted file mode 100644 index a3d98b8bd..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_5_pselect.c +++ /dev/null @@ -1,42 +0,0 @@ -/** - * small test program whether signals between threads work as they should - */ - -#include -#include -#include -#include -#include - -void sighandler(int sig) { - write(2,".",1); - return; -} - -void* threadstart(void* arg) { -sigset_t sigset; -struct timespec sleeptime; - - while (1) { - sleeptime.tv_sec=1; - sleeptime.tv_nsec=0; - sigemptyset(&sigset); - pselect(0,NULL,NULL,NULL,&sleeptime,&sigset); - } -} - -int main(char** argc, int argv) { - - pthread_t testthread1; - struct sigaction action; - - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - pthread_create(&testthread1,NULL,threadstart,NULL); - while (1) { - pthread_kill(testthread1,SIGUSR1); - } -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_6_sched_yield.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_6_sched_yield.c deleted file mode 100644 index 58fc902ea..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_6_sched_yield.c +++ /dev/null @@ -1,35 +0,0 @@ -/** - * small test program whether signals between threads work as they should - */ - -#include -#include -#include - -void sighandler(int sig) { - write(2,".",1); - return; -} - -void* threadstart(void* arg) { - - while (1) { - sched_yield(); - } -} - -int main(char** argc, int argv) { - - pthread_t testthread1; - struct sigaction action; - - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - pthread_create(&testthread1,NULL,threadstart,NULL); - while (1) { - pthread_kill(testthread1,SIGUSR1); - } -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_7_busy_waiting.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_7_busy_waiting.c deleted file mode 100644 index d3a808e61..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_7_busy_waiting.c +++ /dev/null @@ -1,34 +0,0 @@ -/** - * small test program whether signals between threads work as they should - */ - -#include -#include -#include - -void sighandler(int sig) { - write(2,".",1); - return; -} - -void* threadstart(void* arg) { - - while (1) { - } -} - -int main(char** argc, int argv) { - - pthread_t testthread1; - struct sigaction action; - - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - pthread_create(&testthread1,NULL,threadstart,NULL); - while (1) { - pthread_kill(testthread1,SIGUSR1); - } -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_8_io.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_8_io.c deleted file mode 100644 index 3f21c3238..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/test_case_8_io.c +++ /dev/null @@ -1,36 +0,0 @@ -/** - * small test program whether signals between threads work as they should - */ - -#include -#include -#include - -void sighandler(int sig) { - write(2,".",1); - return; -} - -void* threadstart(void* arg) { - char buf[1024]; - - while (1) { - read(1,buf,512); - } -} - -int main(char** argc, int argv) { - - pthread_t testthread1; - struct sigaction action; - - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - pthread_create(&testthread1,NULL,threadstart,NULL); - while (1) { - pthread_kill(testthread1,SIGUSR1); - } -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/thread_signal_test.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/thread_signal_test.c deleted file mode 100644 index 7a230399f..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/thread_signal_test.c +++ /dev/null @@ -1,62 +0,0 @@ -/** - * small etst program whether signals between threads work as they should - */ - -#include -#include -#include -#include - -static pthread_mutex_t Mutex = PTHREAD_MUTEX_INITIALIZER; - -void sighandler(int sig) { - printf("signal handler called in thread %li - signal %i\n",(long)pthread_self(),sig); -} - - -void* threadstart(void* arg) { -struct timespec timeout; -struct sigaction action; - printf("thread %li started\n",(long)pthread_self()); - - printf("installing signal handler\n"); - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - printf("getting mutex\n"); - pthread_mutex_lock(&Mutex); - printf("got mutex\n"); - - - while (1) { - timeout.tv_sec=1; - timeout.tv_nsec=0; - nanosleep(&timeout,0); - printf("thread %li still running...\n",(long)pthread_self()); - } - -} - - -int main(char** argc, int argv) { - -pthread_t testthread1; -pthread_t testthread2; -printf("thread test program\n"); -sleep(5); -printf("starting thread 1\n"); -pthread_create(&testthread1,NULL,threadstart,NULL); -sleep(5); -printf("starting thread 2\n"); -pthread_create(&testthread2,NULL,threadstart,NULL); -while (1) { - sleep(5); - printf("sending SIG_USR1 to thread 1\n"); - pthread_kill(testthread1,SIGUSR1); - sleep(5); - printf("sending SIG_USR1 to thread 2\n"); - pthread_kill(testthread2,SIGUSR1); -} -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/thread_signal_test2.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/thread_signal_test2.c deleted file mode 100644 index d6df0a023..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/thread_signal_test2.c +++ /dev/null @@ -1,128 +0,0 @@ -/** - * small etst program whether signals between threads work as they should - */ - -#include -#include -#include -#include -#include - -static pthread_mutex_t Mutex = PTHREAD_MUTEX_INITIALIZER; - -/** - * printf is not thread safe - this little helper function allow debug output in thread safe context - */ -/* write a string to a filehandle */ -void print_char(int fh, char *c) { - int t=0; - while (c[t]!=0) t++; - write(fh,c,t); -} - -/* create a dezimal string from an integer */ -int int2char(char* x,unsigned long i) { - if (i==0) { - return 0; - } - int k=int2char(&x[0],i/10); - x[k]='0'+(i%10); - x[k+1]=0; - return k+1; -} -/* print a number*/ -void print_number(int fh, long i) { - char buffer[39]; // 39 characters are enough to store a 128 bit integer in dezimal notation (~~3.4* 10^38) - - if (i==0) { - print_char(fh,"0"); - } else { - if (i<0) { - buffer[0]='-'; - int2char(&buffer[1],-i); - } else { - int2char(buffer,i); - } - print_char(fh,buffer); - } -} - -/** - * actual test program - */ - -void sighandler(int sig) { - print_char(2,"signal handler called in thread "); - print_number(2,(long)pthread_self()); - print_char(2," - signal "); - print_number(2,sig); - print_char(2,"\n"); -} - - -void* threadstart(void* arg) { -struct timespec timeout; -int t; - print_char(2,"thread "); - print_number(2,(long)pthread_self()); - print_char(2," started \n"); - - while (1) { - print_char(2,"getting mutex\n"); - pthread_mutex_lock(&Mutex); - print_char(2,"got mutex\n"); - - - for (t=0;t<20;t++) { - timeout.tv_sec=1; - timeout.tv_nsec=0; - nanosleep(&timeout,0); - - print_char(2,"thread "); - print_number(2,(long)pthread_self()); - print_char(2," still running...\n"); - } - pthread_mutex_unlock(&Mutex); - sleep(1); - } -} - - -int main(char** argc, int argv) { - - pthread_t testthread1; - pthread_t testthread2; - struct sigaction action; - print_char(2,"thread test program\n\n"); - - print_char(2,"demonstrate print function\n"); - long t=1; - while (t!=0) { - print_number(2,t); - print_char(2," >> "); - t=(t>0)?t*2:t/2; - } - print_number(2,t); - print_char(2,"\ndone\n\n"); - - print_char(2,"installing signal handler\n"); - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - sleep(5); - print_char(2,"starting thread 1\n"); - pthread_create(&testthread1,NULL,threadstart,NULL); - sleep(5); - print_char(2,"starting thread 2\n"); - pthread_create(&testthread2,NULL,threadstart,NULL); - while (1) { - sleep(5); - print_char(2,"sending SIG_USR1 to thread 1\n"); - pthread_kill(testthread1,SIGUSR1); - sleep(5); - print_char(2,"sending SIG_USR1 to thread 2\n"); - pthread_kill(testthread2,SIGUSR1); - } -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/thread_signal_test3.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/thread_signal_test3.c deleted file mode 100644 index 8e8c9dbf0..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/thread_signal_test3.c +++ /dev/null @@ -1,46 +0,0 @@ -/** - * small etst program whether signals between threads work as they should - */ - -#include -#include -#include - - -/** - * actual test program - */ - -void sighandler(int sig) { - return; -} - - -void* threadstart(void* arg) { -struct timespec timeout; -int t; - - while (1) { - timeout.tv_sec=0; - timeout.tv_nsec=1; - nanosleep(&timeout,0); - } -} - - -int main(char** argc, int argv) { - - pthread_t testthread1; - struct sigaction action; - - - action.sa_handler=sighandler; - action.sa_flags=0; - sigfillset( &action.sa_mask ); - sigaction(SIGUSR1,&action,NULL); - - pthread_create(&testthread1,NULL,threadstart,NULL); - while (1) { - pthread_kill(testthread1,SIGUSR1); - } -} diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/port-pthread_cond.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/port-pthread_cond.c deleted file mode 100644 index 8eab3b367..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/port-pthread_cond.c +++ /dev/null @@ -1,1179 +0,0 @@ -/* - Copyright (C) 2009 William Davy - william.davy@wittenstein.co.uk - Contributed to FreeRTOS.org V5.3.0. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org 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 FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the Posix port. - *----------------------------------------------------------*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" -/*-----------------------------------------------------------*/ - -#define MAX_NUMBER_OF_TASKS ( _POSIX_THREAD_THREADS_MAX ) -/*-----------------------------------------------------------*/ - -#ifdef __APPLE__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES - #define RUNNING_THREAD_MUTEX - #define TICK_SIGNAL -#endif -#ifdef __CYGWIN__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES -#endif -#ifdef __linux__ - #define COND_SIGNALING -// #define CHECK_TASK_RESUMES - #define RUNNING_THREAD_MUTEX - #define TICK_SIGNAL -#endif - - -/* Parameters to pass to the newly created pthread. */ -typedef struct XPARAMS -{ - pdTASK_CODE pxCode; - void *pvParams; -} xParams; - -/* Each task maintains its own interrupt status in the critical nesting variable. */ -typedef struct THREAD_SUSPENSIONS -{ - pthread_t hThread; - pthread_cond_t * hCond; - pthread_mutex_t * hMutex; - xTaskHandle hTask; - portBASE_TYPE xThreadState; - unsigned portBASE_TYPE uxCriticalNesting; -} xThreadState; -/*-----------------------------------------------------------*/ - -static xThreadState *pxThreads; -static pthread_once_t hSigSetupThread = PTHREAD_ONCE_INIT; -static pthread_attr_t xThreadAttributes; -#ifdef RUNNING_THREAD_MUTEX -static pthread_mutex_t xRunningThread = PTHREAD_MUTEX_INITIALIZER; -#endif -static pthread_mutex_t xSuspendResumeThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xSwappingThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_t hMainThread = ( pthread_t )NULL; -/*-----------------------------------------------------------*/ - -static volatile portBASE_TYPE xSentinel = 0; -static volatile portBASE_TYPE xRunning = pdFALSE; -static volatile portBASE_TYPE xSuspended = pdFALSE; -static volatile portBASE_TYPE xStarted = pdFALSE; -static volatile portBASE_TYPE xHandover = 0; -static volatile portBASE_TYPE xSchedulerEnd = pdFALSE; -static volatile portBASE_TYPE xInterruptsEnabled = pdTRUE; -static volatile portBASE_TYPE xServicingTick = pdFALSE; -static volatile portBASE_TYPE xPendYield = pdFALSE; -static volatile portLONG lIndexOfLastAddedTask = 0; -static volatile unsigned portBASE_TYPE uxCriticalNesting; -/*-----------------------------------------------------------*/ - -/* - * Setup the timer to generate the tick interrupts. - */ -static void *prvWaitForStart( void * pvParams ); -static void prvSuspendSignalHandler(int sig); -static void prvSetupSignalsAndSchedulerPolicy( void ); -static void pauseThread( portBASE_TYPE pauseMode ); -static pthread_t prvGetThreadHandle( xTaskHandle hTask ); -#ifdef COND_SIGNALING -static pthread_cond_t * prvGetConditionHandle( xTaskHandle hTask ); -static pthread_mutex_t * prvGetMutexHandle( xTaskHandle hTask ); -#endif -static xTaskHandle prvGetTaskHandle( pthread_t hThread ); -static portLONG prvGetFreeThreadState( void ); -static void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ); -static unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ); -static void prvDeleteThread( void *xThreadId ); -/*-----------------------------------------------------------*/ - -/* - * Exception handlers. - */ -void vPortYield( void ); -void vPortSystemTickHandler( int sig ); - -#define THREAD_PAUSE_CREATED 0 -#define THREAD_PAUSE_YIELD 1 -#define THREAD_PAUSE_INTERRUPT 2 - -//#define DEBUG_OUTPUT -//#define ERROR_OUTPUT -#ifdef DEBUG_OUTPUT - - static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; - - #define debug_printf(...) ( (real_pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ","__unknown__",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?real_pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - - #define debug_error debug_printf - - int real_pthread_mutex_lock(pthread_mutex_t* mutex) { - return pthread_mutex_lock(mutex); - } - int real_pthread_mutex_unlock(pthread_mutex_t* mutex) { - return pthread_mutex_unlock(mutex); - } - #define pthread_mutex_trylock(...) ( (debug_printf(" -!- pthread_mutex_trylock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_trylock(__VA_ARGS__):0 ) - #define pthread_mutex_lock(...) ( (debug_printf(" -!- pthread_mutex_lock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_lock(__VA_ARGS__):0 ) - #define pthread_mutex_unlock(...) ( (debug_printf(" -=- pthread_mutex_unlock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_unlock(__VA_ARGS__):0 ) - #define pthread_kill(thread,signal) ( (debug_printf("Sending signal %i to thread %li!\n",(int)signal,(long)thread)|1)?pthread_kill(thread,signal):0 ) - #define pthread_cond_signal( hCond ) (debug_printf( "pthread_cond_signals(%li)\r\n", *((long int *) hCond) ) ? 1 : pthread_cond_signal( hCond ) ) - #define pthread_cond_timedwait( hCond, hMutex, it ) (debug_printf( "pthread_cond_timedwait(%li,%li)\r\n", *((long int *) hCond), *((long int *) hMutex )) ? 1 : pthread_cond_timedwait( hCond, hMutex, it ) ) - #define pthread_sigmask( how, set, out ) (debug_printf( "pthread_sigmask( %i, %li )\r\n", how, *((long int*) set) ) ? 1 : pthread_sigmask( how, set, out ) ) - -#else - #ifdef ERROR_OUTPUT - static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; - #define debug_error(...) ( (pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ","__unknown__",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - - #define debug_printf(...) - #else - #define debug_printf(...) - #define debug_error(...) - #endif -#endif - - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -void vPortStartFirstTask( void ); -/*-----------------------------------------------------------*/ - - -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ -#endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - -#if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ -#endif - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; -#endif - -#if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ -#endif - -#if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ -#endif - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ -#endif - -} tskTCB; - -tskTCB *debug_task_handle; - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ -/* Should actually keep this struct on the stack. */ -xParams *pxThisThreadParams = pvPortMalloc( sizeof( xParams ) ); - - debug_printf("pxPortInitialiseStack\r\n"); - - (void)pthread_once( &hSigSetupThread, prvSetupSignalsAndSchedulerPolicy ); - - if ( (pthread_t)NULL == hMainThread ) - { - hMainThread = pthread_self(); - } - - /* No need to join the threads. */ - pthread_attr_init( &xThreadAttributes ); - pthread_attr_setdetachstate( &xThreadAttributes, PTHREAD_CREATE_DETACHED ); - - /* Add the task parameters. */ - pxThisThreadParams->pxCode = pxCode; - pxThisThreadParams->pvParams = pvParameters; - - vPortEnterCritical(); - - lIndexOfLastAddedTask = prvGetFreeThreadState(); - - debug_printf( "Got index for new task %i\r\n", lIndexOfLastAddedTask ); - -#ifdef COND_SIGNALING - /* Create a condition signal for this thread */ -// pthread_condattr_t condAttr; -// assert( 0 == pthread_condattr_init( &condAttr ) ); - pxThreads[ lIndexOfLastAddedTask ].hCond = ( pthread_cond_t *) malloc( sizeof( pthread_cond_t ) ); - assert( 0 == pthread_cond_init( pxThreads[ lIndexOfLastAddedTask ].hCond , NULL ) ); //&condAttr ) ); - debug_printf("Cond: %li\r\n", *( (long int *) &pxThreads[ lIndexOfLastAddedTask ].hCond) ); - - /* Create a condition mutex for this thread */ -// pthread_mutexattr_t mutexAttr; -// assert( 0 == pthread_mutexattr_init( &mutexAttr ) ); -// assert( 0 == pthread_mutexattr_settype( &mutexAttr, PTHREAD_MUTEX_ERRORCHECK ) ); - pxThreads[ lIndexOfLastAddedTask ].hMutex = ( pthread_mutex_t *) malloc( sizeof( pthread_mutex_t ) ); - assert( 0 == pthread_mutex_init( pxThreads[ lIndexOfLastAddedTask ].hMutex, NULL ) ); //&mutexAttr ) ); - debug_printf("Mutex: %li\r\n", *( (long int *) &pxThreads[ lIndexOfLastAddedTask ].hMutex) ); -#endif - - /* Create a thread and store it's handle number */ - xSentinel = 0; - assert( 0 == pthread_create( &( pxThreads[ lIndexOfLastAddedTask ].hThread ), &xThreadAttributes, prvWaitForStart, (void *)pxThisThreadParams ) ); - - /* Wait until the task suspends. */ - while ( xSentinel == 0 ); - vPortExitCritical(); - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortStartFirstTask( void ) -{ - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - debug_printf("vPortStartFirstTask\r\n"); - - /* Start the first task. */ - vPortEnableInterrupts(); - xRunning = 1; - - /* Start the first task. */ -#ifdef COND_SIGNALING - pthread_cond_t * hCond = prvGetConditionHandle( xTaskGetCurrentTaskHandle() ); - assert( pthread_cond_signal( hCond ) == 0 ); -#endif -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ -portBASE_TYPE xResult; -sigset_t xSignalToBlock; -portLONG lIndex; - - debug_printf( "xPortStartScheduler\r\n" ); - - /* Establish the signals to block before they are needed. */ - sigemptyset( &xSignalToBlock ); - sigaddset( &xSignalToBlock, SIG_SUSPEND ); - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, NULL ); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - /* Start the first task. Will not return unless all threads are killed. */ - vPortStartFirstTask(); - - /* Unfortunately things are stable if we start ticking during setup. This need to be */ - /* checked careful in startup on hardware */ - usleep(1000000); - -#ifdef TICK_SIGNAL - struct itimerval itimer; - portTickType xMicroSeconds = portTICK_RATE_MICROSECONDS; - - debug_printf("init %li microseconds\n",(long)xMicroSeconds); - /* Initialise the structure with the current timer information. */ - assert ( 0 == getitimer( TIMER_TYPE, &itimer ) ); - - /* Set the interval between timer events. */ - itimer.it_interval.tv_sec = 0; - itimer.it_interval.tv_usec = xMicroSeconds; - - /* Set the current count-down. */ - itimer.it_value.tv_sec = 0; - itimer.it_value.tv_usec = xMicroSeconds; - - struct sigaction sigtick; - sigtick.sa_flags = 0; - sigtick.sa_handler = vPortSystemTickHandler; - sigfillset( &sigtick.sa_mask ); - assert ( 0 == sigaction( SIG_TICK, &sigtick, NULL ) ); - - /* Set-up the timer interrupt. */ - assert ( 0 == setitimer( TIMER_TYPE, &itimer, NULL ) ); - - sigemptyset( &xSignalToBlock ); - sigaddset( &xSignalToBlock, SIG_SUSPEND ); - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, NULL ); - - while(1) - { - usleep(1000); - sched_yield(); - } -#else - - struct timespec x; - while( pdTRUE != xSchedulerEnd ) { - x.tv_sec=0; - x.tv_nsec=portTICK_RATE_MICROSECONDS * 1000; - nanosleep(&x,NULL); -// printf("."); fflush(stdout); - vPortSystemTickHandler(SIG_TICK); -// printf("*"); fflush(stdout); - } - -#endif - debug_printf( "Cleaning Up, Exiting.\n" ); - /* Cleanup the mutexes */ - xResult = pthread_mutex_destroy( &xSuspendResumeThreadMutex ); - xResult = pthread_mutex_destroy( &xSwappingThreadMutex ); - vPortFree( (void *)pxThreads ); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ -portBASE_TYPE xNumberOfThreads; -portBASE_TYPE xResult; - - - for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ ) - { - if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread ) - { - /* Kill all of the threads, they are in the detached state. */ - xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread ); - } - } - - /* Signal the scheduler to exit its loop. */ - xSchedulerEnd = pdTRUE; - (void)pthread_kill( hMainThread, SIG_RESUME ); -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Calling Yield from a Interrupt/Signal handler often doesn't work because the - * xSwappingThreadMutex is already owned by an original call to Yield. Therefore, - * simply indicate that a yield is required soon. - */ - - xPendYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - vPortDisableInterrupts(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - /* Check for unmatched exits. */ - if ( uxCriticalNesting > 0 ) - { - uxCriticalNesting--; - } - - /* If we have reached 0 then re-enable the interrupts. */ - if( uxCriticalNesting == 0 ) - { - /* Have we missed ticks? This is the equivalent of pending an interrupt. */ - if ( pdTRUE == xPendYield ) - { - xPendYield = pdFALSE; - vPortYield(); - } - vPortEnableInterrupts(); - } -} -/*-----------------------------------------------------------*/ - -void vPortYield( void ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -sigset_t xSignals; -int retVal; -tskTCB * oldTask, * newTask; - - /* We must mask the suspend signal here, because otherwise there can be an */ - /* interrupt while in pthread_mutex_lock and that will cause the next thread */ - /* to deadlock when it tries to get this mutex */ - - debug_printf( "Entering\r\n" ); - - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_SUSPEND ); - sigaddset( &xSignals, SIG_TICK ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL ); - - oldTask = xTaskGetCurrentTaskHandle(); - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - retVal = pthread_mutex_trylock( &xSwappingThreadMutex ); - while( retVal != 0 ) { - - assert( retVal == EBUSY ); - - /* If we can't get the mutex, that means an interrupt is running and we */ - /* should keep an eye out if this task should suspend so the interrupt */ - /* routine doesn't stall waiting for this task to pause */ - debug_printf( "Waiting to get swapping mutex from ISR\r\n" ); - - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if( prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) != pthread_self() ) { - debug_printf( "The current task isn't even us. Pausing now, deal with possible interrupt later.\r\n" ); - pauseThread( THREAD_PAUSE_YIELD ); - - /* Now we are resuming, want to be able to catch this interrupt again */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_TICK ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL); - return; - } - sched_yield(); - retVal = pthread_mutex_trylock( &xSwappingThreadMutex ); - } - - /* At this point we have the lock, active task shouldn't change */ - if(xTaskToSuspend != pthread_self() ) { - debug_printf( "The current task isn't even us, letting interrupt happen. Watch for swap.\r\n" ); - - assert( pthread_mutex_unlock( &xSwappingThreadMutex ) == 0); - - pauseThread( THREAD_PAUSE_YIELD ); - - /* Now we are resuming, want to be able to catch this interrupt again */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_TICK ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL); - return; - } - - assert( xTaskToSuspend == pthread_self() ); // race condition I didn't account for - - xStarted = pdFALSE; - - /* Get new task then release the task switching mutex */ - vTaskSwitchContext(); - newTask = xTaskGetCurrentTaskHandle(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( pthread_self() != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - - debug_error( "Swapping From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); - -#ifdef COND_SIGNALING - /* Set resume condition for specific thread */ - pthread_cond_t * hCond = prvGetConditionHandle( xTaskGetCurrentTaskHandle() ); - assert( pthread_cond_signal( hCond ) == 0 ); -#endif -#ifdef CHECK_TASK_RESUMES - while( xStarted == pdFALSE ) - debug_printf( "Waiting for task to resume\r\n" ); -#endif - - debug_printf( "Detected task resuming. Pausing this task\r\n" ); - - /* Release swapping thread mutex and pause self */ - assert( pthread_mutex_unlock( &xSwappingThreadMutex ) == 0); - pauseThread( THREAD_PAUSE_YIELD ); - } - else { - assert( pthread_mutex_unlock( &xSwappingThreadMutex ) == 0); - } - - /* Now we are resuming, want to be able to catch this interrupt again */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_TICK ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL); -} -/*-----------------------------------------------------------*/ - -void vPortDisableInterrupts( void ) -{ - //debug_printf("\r\n"); - xInterruptsEnabled = pdFALSE; -} -/*-----------------------------------------------------------*/ - -void vPortEnableInterrupts( void ) -{ - //debug_printf("\r\n"); - xInterruptsEnabled = pdTRUE; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xPortSetInterruptMask( void ) -{ -portBASE_TYPE xReturn = xInterruptsEnabled; - debug_printf("\r\n"); - xInterruptsEnabled = pdFALSE; - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vPortClearInterruptMask( portBASE_TYPE xMask ) -{ - debug_printf("\r\n"); - xInterruptsEnabled = xMask; -} -/*-----------------------------------------------------------*/ - - -void vPortSystemTickHandler( int sig ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -tskTCB * oldTask, * newTask; - - debug_printf( "\r\n\r\n" ); - debug_printf( "(xInterruptsEnabled = %i, xServicingTick = %i)\r\n", (int) xInterruptsEnabled != 0, (int) xServicingTick != 0); - if ( ( pdTRUE == xInterruptsEnabled ) && ( pdTRUE != xServicingTick ) ) - { -// debug_printf( "Checking for lock ...\r\n" ); - if ( 0 == pthread_mutex_trylock( &xSwappingThreadMutex ) ) - { - debug_printf( "Handling\r\n"); - xServicingTick = pdTRUE; - - oldTask = xTaskGetCurrentTaskHandle(); - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - /* Need to set this before updating the task in case it notices before the */ - /* interrupt is set */ - xSuspended = pdFALSE; - xStarted = pdFALSE; - - /* Tick Increment. */ - vTaskIncrementTick(); - - /* Select Next Task. */ -#if ( configUSE_PREEMPTION == 1 ) - vTaskSwitchContext(); -#endif - - newTask = xTaskGetCurrentTaskHandle(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - debug_printf( "Want %s running\r\n", newTask->pcTaskName ); - /* The only thread that can process this tick is the running thread. */ - if ( xTaskToSuspend != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - - debug_printf( "Swapping From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); - - assert( pthread_kill( xTaskToSuspend, SIG_SUSPEND ) == 0); - -#ifdef CHECK_TASK_RESUMES - /* It shouldn't be possible for a second task swap to happen while waiting for this because */ - /* they can't get the xSwappingThreadMutex */ - while( xSuspended == pdFALSE ) -#endif - { - debug_printf( "Waiting for old task to suspend\r\n" ); - debug_printf( "Sent signal\r\n" ); - sched_yield(); - } - debug_printf( "Suspended\r\n" ); - -#ifdef CHECK_TASK_RESUMES - while( xStarted == pdFALSE) -#endif - { - debug_printf( "Waiting for new task to resume\r\n" ); -#ifdef COND_SIGNALING - // Set resume condition for specific thread - pthread_cond_t * hCond = prvGetConditionHandle( xTaskGetCurrentTaskHandle() ); - assert( pthread_cond_signal( hCond ) == 0 ); -#endif - - sched_yield(); - } - - debug_printf( "Swapped From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); } - else - { - // debug_error ("Want %s running \r\n", newTask->pcTaskName ); - } - xServicingTick = pdFALSE; - (void)pthread_mutex_unlock( &xSwappingThreadMutex ); - } - else - { - debug_error( "Pending yield here (portYield has lock - hopefully)\r\n" ); - xPendYield = pdTRUE; - } - - } - else - { - debug_printf( "Pending yield or here\r\n"); - xPendYield = pdTRUE; - } - debug_printf("Exiting\r\n"); -} -/*-----------------------------------------------------------*/ - -void vPortForciblyEndThread( void *pxTaskToDelete ) -{ -xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete; -pthread_t xTaskToDelete; -pthread_t xTaskToResume; -portBASE_TYPE xResult; - - printf("vPortForciblyEndThread\r\n"); - - if ( 0 == pthread_mutex_lock( &xSwappingThreadMutex ) ) - { - xTaskToDelete = prvGetThreadHandle( hTaskToDelete ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( xTaskToResume == xTaskToDelete ) - { - /* This is a suicidal thread, need to select a different task to run. */ - vTaskSwitchContext(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - } - - if ( pthread_self() != xTaskToDelete ) - { - /* Cancelling a thread that is not me. */ - if ( xTaskToDelete != ( pthread_t )NULL ) - { - /* Send a signal to wake the task so that it definitely cancels. */ - pthread_testcancel(); - xResult = pthread_cancel( xTaskToDelete ); - /* Pthread Clean-up function will note the cancellation. */ - } - (void)pthread_mutex_unlock( &xSwappingThreadMutex ); - } - else - { - /* Resume the other thread. */ - /* Assert zero - I never fixed this functionality */ - assert( 0 ); - - /* Pthread Clean-up function will note the cancellation. */ - /* Release the execution. */ - uxCriticalNesting = 0; - vPortEnableInterrupts(); - (void)pthread_mutex_unlock( &xSwappingThreadMutex ); - /* Commit suicide */ - pthread_exit( (void *)1 ); - } - } -} -/*-----------------------------------------------------------*/ - -void *prvWaitForStart( void * pvParams ) -{ -xParams * pxParams = ( xParams * )pvParams; -pdTASK_CODE pvCode = pxParams->pxCode; -void * pParams = pxParams->pvParams; - vPortFree( pvParams ); - - pthread_cleanup_push( prvDeleteThread, (void *)pthread_self() ); - - /* want to block suspend when not the active thread */ - sigset_t xSignals; - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_SUSPEND ); - sigaddset( &xSignals, SIG_TICK ); - assert( pthread_sigmask( SIG_SETMASK, &xSignals, NULL ) == 0); - - /* Because the FreeRTOS creates the TCB stack, which in this implementation */ - /* creates a thread, we need to wait until the task handle is added before */ - /* trying to pause. Must set xSentinel high so the creating task knows we're */ - /* here */ - - debug_printf("Thread started, waiting till handle is added\r\n"); - - xSentinel = 1; - - while( prvGetTaskHandle( pthread_self() ) == NULL ){ - sched_yield(); - } - - debug_printf("Handle added, pausing\r\n"); - - /* Want to delay briefly until we have explicit resume signal as otherwise the */ - /* current task variable might be in the wrong state */ - pauseThread( THREAD_PAUSE_CREATED ); - debug_printf("Starting first run\r\n"); - - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_TICK ); - assert( pthread_sigmask( SIG_SETMASK, &xSignals, NULL ) == 0); - - pvCode( pParams ); - - pthread_cleanup_pop( 1 ); - return (void *)NULL; -} -/*-----------------------------------------------------------*/ - -void pauseThread( portBASE_TYPE pauseMode ) -{ - debug_printf( "Pausing thread %li. Set xSuspended true\r\n", (long int) pthread_self() ); - xSuspended = pdTRUE; - -#ifdef RUNNING_THREAD_MUTEX - if( pauseMode != THREAD_PAUSE_CREATED ) - assert( 0 == pthread_mutex_unlock( &xRunningThread ) ); -#endif - -#ifdef COND_SIGNALING - int xResult; - xTaskHandle hTask = prvGetTaskHandle( pthread_self() ); - pthread_cond_t * hCond = prvGetConditionHandle( hTask ); - pthread_mutex_t * hMutex = prvGetMutexHandle( hTask ); - debug_printf("Cond: %li\r\n", *( (long int *) hCond) ); - debug_printf("Mutex: %li\r\n", *( (long int *) hMutex) ); - - struct timeval tv; - struct timespec ts; - gettimeofday( &tv, NULL ); - ts.tv_sec = tv.tv_sec + 0; -#endif - - while (1) { - if( pthread_self() == prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) && xRunning ) - { - - xStarted = pdTRUE; - -#ifdef RUNNING_THREAD_MUTEX - assert( 0 == pthread_mutex_lock( &xRunningThread ) ); -#endif - debug_error("Resuming\r\n"); - return; - } - else { -#ifdef COND_SIGNALING - gettimeofday( &tv, NULL ); - ts.tv_sec = ts.tv_sec + 1; - ts.tv_nsec = 0; - xResult = pthread_cond_timedwait( hCond, hMutex, &ts ); - assert( xResult != EINVAL ); -#else - /* For windows where conditional signaling is buggy */ - /* It would be wonderful to put a nanosleep here, but since its not reentrant safe */ - /* and there may be a sleep in the main code (this can be called from an ISR) we must */ - /* check this */ - if( pauseMode != THREAD_PAUSE_INTERRUPT ) - usleep(1000); - sched_yield(); - -#endif -// debug_error( "Checked my status\r\n" ); - } - - } -} - -void prvSuspendSignalHandler(int sig) -{ -sigset_t xBlockSignals; - - /* This signal is set here instead of pauseThread because it is checked by the tick handler */ - /* which means if there were a swap it should result in a suspend interrupt */ - - debug_error( "Caught signal %i\r\n", sig ); - -#ifdef CHECK_TASK_RESUMES - /* This would seem like a major bug, but can happen because now we send extra suspend signals */ - /* if they aren't caught */ - if( pthread_self() == prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ) { - debug_printf( "Marked as current task, resuming\r\n" ); - return; - } -#endif - - /* Check that we aren't suspending when we should be running. This bug would need tracking down */ -// assert( pthread_self() != prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) ); - - /* Block further suspend signals. They need to go to their thread */ - sigemptyset( &xBlockSignals ); - sigaddset( &xBlockSignals, SIG_SUSPEND ); - sigaddset( &xBlockSignals, SIG_TICK ); - assert( pthread_sigmask( SIG_SETMASK, &xBlockSignals, NULL ) == 0); - - while( pthread_self() != prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ) - { - debug_printf( "Incorrectly woke up. Repausing\r\n" ); - pauseThread( THREAD_PAUSE_INTERRUPT ); - } - - assert( pthread_self() == prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ); - - /* Old synchronization code, may still be required - while( !xHandover ); - assert( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ); */ - - /* Respond to signals again */ - sigemptyset( &xBlockSignals ); - sigaddset( &xBlockSignals, SIG_TICK ); - assert( 0 == pthread_sigmask( SIG_SETMASK, &xBlockSignals, NULL ) ); - - debug_printf( "Resuming %li from signal %i\r\n", (long int) pthread_self(), sig ); - - /* Will resume here when the SIG_RESUME signal is received. */ - /* Need to set the interrupts based on the task's critical nesting. */ - if ( uxCriticalNesting == 0 ) - { - vPortEnableInterrupts(); - } - else - { - vPortDisableInterrupts(); - } - debug_printf("Exit\r\n"); -} - -/*-----------------------------------------------------------*/ - -void prvSetupSignalsAndSchedulerPolicy( void ) -{ -/* The following code would allow for configuring the scheduling of this task as a Real-time task. - * The process would then need to be run with higher privileges for it to take affect. -int iPolicy; -int iResult; -int iSchedulerPriority; - iResult = pthread_getschedparam( pthread_self(), &iPolicy, &iSchedulerPriority ); - iResult = pthread_attr_setschedpolicy( &xThreadAttributes, SCHED_FIFO ); - iPolicy = SCHED_FIFO; - iResult = pthread_setschedparam( pthread_self(), iPolicy, &iSchedulerPriority ); */ - -struct sigaction sigsuspendself; -portLONG lIndex; - - debug_printf("prvSetupSignalAndSchedulerPolicy\r\n"); - - pxThreads = ( xThreadState *)pvPortMalloc( sizeof( xThreadState ) * MAX_NUMBER_OF_TASKS ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = ( xTaskHandle )NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - sigsuspendself.sa_flags = 0; - sigsuspendself.sa_handler = prvSuspendSignalHandler; - sigemptyset( &sigsuspendself.sa_mask ); - - assert ( 0 == sigaction( SIG_SUSPEND, &sigsuspendself, NULL ) ); -} - -/*-----------------------------------------------------------*/ -pthread_mutex_t * prvGetMutexHandle( xTaskHandle hTask ) -{ -pthread_mutex_t * hMutex; -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hMutex = pxThreads[ lIndex ].hMutex; - break; - } - } - return hMutex; -} - -/*-----------------------------------------------------------*/ -xTaskHandle prvGetTaskHandle( pthread_t hThread ) -{ -xTaskHandle hTask = NULL; -portLONG lIndex; - - /* If not initialized yet */ - if( pxThreads == NULL ) return NULL; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == hThread ) - { - hTask = pxThreads[ lIndex ].hTask; - break; - } - } - return hTask; -} - -/*-----------------------------------------------------------*/ -pthread_cond_t * prvGetConditionHandle( xTaskHandle hTask ) -{ -pthread_cond_t * hCond; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - debug_printf( "Found condition on %i task\r\n", lIndex ); - return pxThreads[ lIndex ].hCond; - break; - } - } - printf( "Failed to get handle, pausing then recursing\r\n" ); - usleep(1000); - return prvGetConditionHandle( hTask ); - assert(0); - return hCond; -} - -/*-----------------------------------------------------------*/ -pthread_t prvGetThreadHandle( xTaskHandle hTask ) -{ - pthread_t hThread = ( pthread_t )NULL; - portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hThread = pxThreads[ lIndex ].hThread; - break; - } - } - return hThread; -} -/*-----------------------------------------------------------*/ - -portLONG prvGetFreeThreadState( void ) -{ -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )NULL ) - { - break; - } - } - - if ( MAX_NUMBER_OF_TASKS == lIndex ) - { - printf( "No more free threads, please increase the maximum.\n" ); - lIndex = 0; - vPortEndScheduler(); - } - - return lIndex; -} -/*-----------------------------------------------------------*/ - -void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ) -{ -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - pxThreads[ lIndex ].uxCriticalNesting = uxNesting; - break; - } - } -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ) -{ -unsigned portBASE_TYPE uxNesting = 0; -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - uxNesting = pxThreads[ lIndex ].uxCriticalNesting; - break; - } - } - return uxNesting; -} -/*-----------------------------------------------------------*/ - -void prvDeleteThread( void *xThreadId ) -{ -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )xThreadId ) - { - pxThreads[ lIndex ].hThread = (pthread_t)NULL; - pxThreads[ lIndex ].hTask = (xTaskHandle)NULL; - if ( pxThreads[ lIndex ].uxCriticalNesting > 0 ) - { - uxCriticalNesting = 0; - vPortEnableInterrupts(); - } - pxThreads[ lIndex ].uxCriticalNesting = 0; - break; - } - } -} -/*-----------------------------------------------------------*/ - -void vPortAddTaskHandle( void *pxTaskHandle ) -{ -portLONG lIndex; - - debug_printf("vPortAddTaskHandle\r\n"); - - pxThreads[ lIndexOfLastAddedTask ].hTask = ( xTaskHandle )pxTaskHandle; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == pxThreads[ lIndexOfLastAddedTask ].hThread ) - { - if ( pxThreads[ lIndex ].hTask != pxThreads[ lIndexOfLastAddedTask ].hTask ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - } - } - usleep(10000); -} -/*-----------------------------------------------------------*/ - -void vPortFindTicksPerSecond( void ) -{ - - /* Needs to be reasonably high for accuracy. */ - unsigned long ulTicksPerSecond = sysconf(_SC_CLK_TCK); - printf( "Timer Resolution for Run TimeStats is %ld ticks per second.\n", ulTicksPerSecond ); -} -/*-----------------------------------------------------------*/ - -unsigned long ulPortGetTimerValue( void ) -{ -struct tms xTimes; - - unsigned long ulTotalTime = times( &xTimes ); - /* Return the application code times. - * The timer only increases when the application code is actually running - * which means that the total execution times should add up to 100%. - */ - return ( unsigned long ) xTimes.tms_utime; - - /* Should check ulTotalTime for being clock_t max minus 1. */ - (void)ulTotalTime; -} -/*-----------------------------------------------------------*/ diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/port-stupidlysimplerversion.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/port-stupidlysimplerversion.c deleted file mode 100644 index 53d49b094..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/port-stupidlysimplerversion.c +++ /dev/null @@ -1,1109 +0,0 @@ -/* - Copyright (C) 2009 William Davy - william.davy@wittenstein.co.uk - Contributed to FreeRTOS.org V5.3.0. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org 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 FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the Posix port. - *----------------------------------------------------------*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" -/*-----------------------------------------------------------*/ - -#define MAX_NUMBER_OF_TASKS ( _POSIX_THREAD_THREADS_MAX ) -/*-----------------------------------------------------------*/ - -#define DB_P(x) // x - - -/* Parameters to pass to the newly created pthread. */ -typedef struct XPARAMS -{ - pdTASK_CODE pxCode; - void *pvParams; -} xParams; - -/* Each task maintains its own interrupt status in the critical nesting variable. */ -typedef struct THREAD_SUSPENSIONS -{ - pthread_t hThread; - pthread_cond_t hCond; - pthread_mutex_t hMutex; - xTaskHandle hTask; - unsigned portBASE_TYPE uxCriticalNesting; -} xThreadState; -/*-----------------------------------------------------------*/ - -static xThreadState *pxThreads; -static pthread_once_t hSigSetupThread = PTHREAD_ONCE_INIT; -static pthread_attr_t xThreadAttributes; -static pthread_mutex_t xRunningThread = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xSuspendResumeThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xSingleThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_t hMainThread = ( pthread_t )NULL; -/*-----------------------------------------------------------*/ - -static volatile portBASE_TYPE xSentinel = 0; -static volatile portBASE_TYPE xHandover = 0; -static volatile portBASE_TYPE xSchedulerEnd = pdFALSE; -static volatile portBASE_TYPE xInterruptsEnabled = pdTRUE; -static volatile portBASE_TYPE xInterruptsCurrent = pdTRUE; -static volatile portBASE_TYPE xServicingTick = pdFALSE; -static volatile portBASE_TYPE xPendYield = pdFALSE; -static volatile portLONG lIndexOfLastAddedTask = 0; -static volatile unsigned portBASE_TYPE uxCriticalNesting; -/*-----------------------------------------------------------*/ - -/* - * Setup the timer to generate the tick interrupts. - */ -static void *prvWaitForStart( void * pvParams ); -static void prvSuspendSignalHandler(int sig); -//static void prvResumeSignalHandler(int sig); -static void prvSetupSignalsAndSchedulerPolicy( void ); -static void prvSuspendThread( pthread_t xThreadId ); -static void pauseThread(); -//static void prvResumeThread( pthread_t xThreadId ); -static pthread_t prvGetThreadHandle( xTaskHandle hTask ); -static pthread_cond_t prvGetThreadCondition( xTaskHandle hTask ); -static pthread_mutex_t prvGetThreadMutex( xTaskHandle hTask ); -static xTaskHandle prvGetThreadTask( pthread_t hThread ); -static portLONG prvGetFreeThreadState( void ); -static void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ); -static unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ); -static void prvDeleteThread( void *xThreadId ); -/*-----------------------------------------------------------*/ - - -/* - * Exception handlers. - */ -void vPortYield( void ); -void vPortSystemTickHandler( int sig ); - - - -//#define DEBUG_OUTPUT -#ifdef DEBUG_OUTPUT - - static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; - - #define debug_printf(...) ( (real_pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ","__unknown__",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?real_pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - - #define debug_error debug_printf - - int real_pthread_mutex_lock(pthread_mutex_t* mutex) { - return pthread_mutex_lock(mutex); - } - int real_pthread_mutex_unlock(pthread_mutex_t* mutex) { - return pthread_mutex_unlock(mutex); - } - #define pthread_mutex_lock(...) ( (debug_printf(" -!- pthread_mutex_lock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_lock(__VA_ARGS__):0 ) - #define pthread_mutex_unlock(...) ( (debug_printf(" -=- pthread_mutex_unlock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_unlock(__VA_ARGS__):0 ) - #define pthread_kill(thread,signal) ( (debug_printf("Sending signal %i to thread %li!\n",(int)signal,(long)thread)|1)?pthread_kill(thread,signal):0 ) -#else - #define debug_error(...) ( (pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ","__unknown__",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - - #define debug_printf(...) -#endif - - - - - -//#define debug_printf(...) fprintf( stderr, __VA_ARGS__ ); -/* - * Start first task is a separate function so it can be tested in isolation. - */ -void vPortStartFirstTask( void ); -/*-----------------------------------------------------------*/ - - -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ -#endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - -#if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ -#endif - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; -#endif - -#if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ -#endif - -#if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ -#endif - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ -#endif - -} tskTCB; - -tskTCB *debug_task_handle; -tskTCB * prvGetTaskHandle( pthread_t hThread ) -{ - portLONG lIndex; - - if (pxThreads==NULL) return NULL; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == hThread ) - { - return pxThreads[ lIndex ].hTask; - } - } - return NULL; -} - - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ -/* Should actually keep this struct on the stack. */ -xParams *pxThisThreadParams = pvPortMalloc( sizeof( xParams ) ); - - debug_printf("pxPortInitialiseStack\r\n"); - - (void)pthread_once( &hSigSetupThread, prvSetupSignalsAndSchedulerPolicy ); - - if ( (pthread_t)NULL == hMainThread ) - { - hMainThread = pthread_self(); - } /*else { - sigset_t xSignals; - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_TICK ); - pthread_sigmask( SIG_BLOCK, &xSignals, NULL ); - } */ - - - /* No need to join the threads. */ - pthread_attr_init( &xThreadAttributes ); - pthread_attr_setdetachstate( &xThreadAttributes, PTHREAD_CREATE_DETACHED ); - - /* Add the task parameters. */ - pxThisThreadParams->pxCode = pxCode; - pxThisThreadParams->pvParams = pvParameters; - - vPortEnterCritical(); - - lIndexOfLastAddedTask = prvGetFreeThreadState(); - - /* Create a condition signal for this thread */ -/* pthread_condattr_t condAttr; - assert( 0 == pthread_condattr_init(&condAttr) ); - assert( 0 == pthread_cond_init( &( pxThreads[ lIndexOfLastAddedTask ].hCond ), &condAttr ) ); */ - - /* Create a condition mutex for this thread */ -/* pthread_mutexattr_t mutexAttr; - assert( 0 == pthread_mutexattr_init( &mutexAttr ) ); - assert( 0 == pthread_mutexattr_settype( &mutexAttr, PTHREAD_MUTEX_ERRORCHECK ) ); - assert( 0 == pthread_mutex_init( &( pxThreads[ lIndexOfLastAddedTask ].hMutex ), &mutexAttr ) );*/ - - /* Create a thread and store it's handle number */ - xSentinel = 0; - assert( 0 == pthread_create( &( pxThreads[ lIndexOfLastAddedTask ].hThread ), &xThreadAttributes, prvWaitForStart, (void *)pxThisThreadParams ) ); - - - - /* Wait until the task suspends. */ - while ( xSentinel == 0 ); - vPortExitCritical(); - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortStartFirstTask( void ) -{ - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - debug_printf("vPortStartFirstTask\r\n"); - - /* Start the first task. */ - vPortEnableInterrupts(); - - /* Start the first task. */ - //prvResumeThread( prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ); - - debug_printf( "Sending resume signal to %li\r\n", (long int) prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ); -// pthread_kill( prvGetThreadHandle( xTaskGetCurrentTaskHandle() ), SIG_RESUME ); - // Set resume condition for specific thread - //pthread_cond_t hCond = prvGetThreadCondition( xTaskGetCurrentTaskHandle() ); - //assert( pthread_cond_signal( &hCond ) == 0 ); - -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ -portBASE_TYPE xResult; -sigset_t xSignals; -sigset_t xSignalToBlock; -sigset_t xSignalsBlocked; -portLONG lIndex; - - debug_printf( "xPortStartScheduler\r\n" ); - - /* Establish the signals to block before they are needed. */ - sigfillset( &xSignalToBlock ); - sigaddset( &xSignalToBlock, SIG_SUSPEND ); -/* sigaddset( &xSignalToBlock, SIG_RESUME ); - sigaddset( &xSignalToBlock, SIG_TICK ); */ - - - /* Block until the end */ - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, &xSignalsBlocked ); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - /* Start the timer that generates the tick ISR. Interrupts are disabled - here already. */ -// prvSetupTimerInterrupt(); - - /* Start the first task. Will not return unless all threads are killed. */ - vPortStartFirstTask(); - - /* This is the end signal we are looking for. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - - while( pdTRUE != xSchedulerEnd ) { - struct timespec x; - x.tv_sec=0; - x.tv_nsec=1000000; - nanosleep(&x,NULL); - printf("."); fflush(stdout); - vPortSystemTickHandler(SIG_TICK); - } - - debug_printf( "Cleaning Up, Exiting.\n" ); - /* Cleanup the mutexes */ - xResult = pthread_mutex_destroy( &xSuspendResumeThreadMutex ); - xResult = pthread_mutex_destroy( &xSingleThreadMutex ); - vPortFree( (void *)pxThreads ); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ -portBASE_TYPE xNumberOfThreads; -portBASE_TYPE xResult; - - DB_P("vPortEndScheduler\r\n"); - - for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ ) - { - if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread ) - { - /* Kill all of the threads, they are in the detached state. */ - xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread ); - } - } - - /* Signal the scheduler to exit its loop. */ - xSchedulerEnd = pdTRUE; - (void)pthread_kill( hMainThread, SIG_RESUME ); -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Calling Yield from a Interrupt/Signal handler often doesn't work because the - * xSingleThreadMutex is already owned by an original call to Yield. Therefore, - * simply indicate that a yield is required soon. - */ - - DB_P("vPortYieldFromISR\r\n"); - - xPendYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - DB_P("vPortEnterCritical\r\n"); - - vPortDisableInterrupts(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - DB_P("vPortExitCritical\r\n"); - /* Check for unmatched exits. */ - if ( uxCriticalNesting > 0 ) - { - uxCriticalNesting--; - } - - /* If we have reached 0 then re-enable the interrupts. */ - if( uxCriticalNesting == 0 ) - { - /* Have we missed ticks? This is the equivalent of pending an interrupt. */ - if ( pdTRUE == xPendYield ) - { - xPendYield = pdFALSE; - vPortYield(); - } - vPortEnableInterrupts(); - } -} -/*-----------------------------------------------------------*/ - -void vPortYield( void ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -sigset_t xSignals; - - /* We must mask the suspend signal here, because otherwise there can be an */ - /* interrupt while in pthread_mutex_lock and that will cause the next thread */ - /* to deadlock when it tries to get this mutex */ - - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_SUSPEND ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL ); - - assert( pthread_mutex_lock( &xSingleThreadMutex ) == 0); - - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - if(xTaskToSuspend != pthread_self() ) { - /* This means between masking the interrupt and getting the lock, there was an interrupt */ - /* and this task should suspend. Release the lock, then unmask interrupts to go ahead and */ - /* service the signal */ - assert( 0 == pthread_mutex_unlock( &xSingleThreadMutex ) ); - debug_printf( "The current task isn't even us, letting interrupt happen\r\n" ); - /* Now we are resuming, want to be able to catch this interrupt again */ - sigemptyset( &xSignals ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL); - return; - } - - /* Get new task then release the task switching mutex */ - vTaskSwitchContext(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - assert( pthread_mutex_unlock( &xSingleThreadMutex ) == 0); - - if ( pthread_self() != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - - /* pausing self if switching tasks, can now rely on other thread waking itself up */ - pauseThread(); - } - - /* Now we are resuming, want to be able to catch this interrupt again */ - sigemptyset( &xSignals ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL); -} -/*-----------------------------------------------------------*/ - -void vPortDisableInterrupts( void ) -{ - DB_P("vPortDisableInterrupts\r\n"); - xInterruptsEnabled = pdFALSE; -} -/*-----------------------------------------------------------*/ - -void vPortEnableInterrupts( void ) -{ - DB_P("vPortEnableInterrupts\r\n"); - xInterruptsEnabled = pdTRUE; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xPortSetInterruptMask( void ) -{ -portBASE_TYPE xReturn = xInterruptsEnabled; - DB_P("vPortsetInterruptMask\r\n"); - xInterruptsEnabled = pdFALSE; - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vPortClearInterruptMask( portBASE_TYPE xMask ) -{ - DB_P("vPortClearInterruptMask\r\n"); - xInterruptsEnabled = xMask; -} -/*-----------------------------------------------------------*/ - - -void vPortSystemTickHandler( int sig ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -portBASE_TYPE xInterruptValue; -tskTCB * oldTask, * newTask; -int lockResult; - - DB_P("vPortSystemTickHandler"); - xInterruptValue = xInterruptsEnabled; - debug_printf( "\r\n\r\n" ); - debug_printf( "(xInterruptsEnabled = %i, xServicingTick = %i)\r\n", (int) xInterruptValue != 0, (int) xServicingTick != 0); - if ( ( pdTRUE == xInterruptValue ) && ( pdTRUE != xServicingTick ) ) - { - debug_printf( "Checking for lock ...\r\n" ); - lockResult = pthread_mutex_trylock( &xSingleThreadMutex ); -// lockResult = 0; - debug_printf( "Done\r\n" ); - if ( 0 == lockResult) - { - debug_printf( "Handling\r\n"); - xServicingTick = pdTRUE; - oldTask = xTaskGetCurrentTaskHandle(); - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - /* Tick Increment. */ - vTaskIncrementTick(); - - /* Select Next Task. */ -#if ( configUSE_PREEMPTION == 1 ) - vTaskSwitchContext(); -#endif - - newTask = xTaskGetCurrentTaskHandle(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - /* The only thread that can process this tick is the running thread. */ - if ( xTaskToSuspend != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - - debug_printf( "Swapping From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); - prvSuspendThread( xTaskToSuspend ); /* Suspend the current task. */ - debug_printf( "Swapped From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); - } - xServicingTick = pdFALSE; - (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - else - { - debug_printf( "Pending yield here (portYield has lock - hopefully)\r\n" ); - xPendYield = pdTRUE; - } - - } - else - { - debug_printf( "Pending yield or here\r\n"); - xPendYield = pdTRUE; - } -} -/*-----------------------------------------------------------*/ - -void vPortForciblyEndThread( void *pxTaskToDelete ) -{ -xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete; -pthread_t xTaskToDelete; -pthread_t xTaskToResume; -portBASE_TYPE xResult; - - printf("vPortForciblyEndThread\r\n"); - - if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) - { - xTaskToDelete = prvGetThreadHandle( hTaskToDelete ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( xTaskToResume == xTaskToDelete ) - { - /* This is a suicidal thread, need to select a different task to run. */ - vTaskSwitchContext(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - } - - if ( pthread_self() != xTaskToDelete ) - { - /* Cancelling a thread that is not me. */ - if ( xTaskToDelete != ( pthread_t )NULL ) - { - /* Send a signal to wake the task so that it definitely cancels. */ - pthread_testcancel(); - xResult = pthread_cancel( xTaskToDelete ); - /* Pthread Clean-up function will note the cancellation. */ - } - (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - else - { - /* Resume the other thread. */ - //prvResumeThread( xTaskToResume ); - assert( 0 ); - - /* Pthread Clean-up function will note the cancellation. */ - /* Release the execution. */ - uxCriticalNesting = 0; - vPortEnableInterrupts(); - (void)pthread_mutex_unlock( &xSingleThreadMutex ); - /* Commit suicide */ - pthread_exit( (void *)1 ); - } - } -} -/*-----------------------------------------------------------*/ - -void *prvWaitForStart( void * pvParams ) -{ -xParams * pxParams = ( xParams * )pvParams; -pdTASK_CODE pvCode = pxParams->pxCode; -void * pParams = pxParams->pvParams; - vPortFree( pvParams ); - - pthread_cleanup_push( prvDeleteThread, (void *)pthread_self() ); - - xSentinel = 1; // tell creating block to resume - - /* want to block suspend when not the active thread */ - sigset_t xSignals; - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_SUSPEND ); - assert( pthread_sigmask( SIG_BLOCK, &xSignals, NULL ) == 0); - - debug_printf( "Delaying before the pause to make sure system knows about task\r\n" ); - struct timespec x; - x.tv_sec=0; - x.tv_nsec=10000000; - nanosleep(&x,NULL); - - // wait for resume signal - debug_printf("Pausing newly created thread\r\n"); -// pthread_mutex_lock( &xRunningThread ); -// pauseThread(); - - while (1) { - if( pthread_self() == prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) ) - { - // assert( 0 == pthread_mutex_lock( &xRunningThread ) ); - break; - } - else { - struct timespec x; - x.tv_sec=0; - x.tv_nsec=100000; - nanosleep(&x,NULL); - sched_yield(); - } - - } - - // no longer want to block any signals - sigemptyset( &xSignals ); - assert( pthread_sigmask( SIG_SETMASK, &xSignals, NULL ) == 0); - debug_printf("Starting first run\r\n"); - - //xHandover = 1; - //assert ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) - - pvCode( pParams ); - - pthread_cleanup_pop( 1 ); - return (void *)NULL; -} -/*-----------------------------------------------------------*/ - -void pauseThread() -{ - debug_printf("\r\n"); - -// assert( 0 == pthread_mutex_unlock( &xRunningThread ) ); - while (1) { - if( pthread_self() == prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) ) - { -// assert( 0 == pthread_mutex_lock( &xRunningThread ) ); - return; - } - else { - struct timespec x; - x.tv_sec=0; - x.tv_nsec=100000; - nanosleep(&x,NULL); - sched_yield(); - } - - } - xTaskHandle hTask = prvGetThreadTask( pthread_self() ); - pthread_cond_t hCond = prvGetThreadCondition( hTask ); - pthread_mutex_t hMutex = prvGetThreadMutex( hTask ); - // while( !shouldResume ) { - pthread_cond_wait( &hCond, &hMutex ); - assert( 0 == pthread_mutex_lock( &xRunningThread ) ); - // } -} - -void prvSuspendSignalHandler(int sig) -{ -sigset_t xBlockSignals; - - debug_printf( "Caught signal %i\r\n", sig ); - /* Check that we aren't suspending when we should be running. This bug would need tracking down */ - //assert( pthread_self() != prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) ); - if( pthread_self() == prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ) return; - - /* Block further suspend signals. They need to go to their thread */ - sigemptyset( &xBlockSignals ); - sigaddset( &xBlockSignals, SIG_SUSPEND ); - assert( pthread_sigmask( SIG_BLOCK, &xBlockSignals, NULL ) == 0); - - /* Unlock the Single thread mutex to allow the resumed task to continue. */ - //assert ( 0 == pthread_mutex_unlock( &xSingleThreadMutex ) ); - - // Set resume condition for specific thread -/* pthread_cond_t hCond = prvGetThreadCondition( xTaskGetCurrentTaskHandle() ); - assert( pthread_cond_signal( &hCond ) == 0 ); */ - - pauseThread(); - - while( pthread_self() != prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ) - { - debug_printf( "Incorrectly woke up. Repausing\r\n" ); - pauseThread(); - } - - /* Make sure the right thread is resuming */ - assert( pthread_self() == prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) ); - - /* Old synchronization code, may still be required - while( !xHandover ); - assert( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ); */ - - /* Respond to signals again */ - sigemptyset( &xBlockSignals ); - pthread_sigmask( SIG_SETMASK, &xBlockSignals, NULL ); - - debug_printf( "Resuming %li from signal %i\r\n", (long int) pthread_self(), sig ); - - /* Will resume here when the SIG_RESUME signal is received. */ - /* Need to set the interrupts based on the task's critical nesting. */ - if ( uxCriticalNesting == 0 ) - { - vPortEnableInterrupts(); - } - else - { - vPortDisableInterrupts(); - } - debug_printf("Exit\r\n"); -} -/*-----------------------------------------------------------*/ - -void prvSuspendThread( pthread_t xThreadId ) -{ - debug_printf( "Suspending %li\r\n", (long int) xThreadId); - /* Set-up for the Suspend Signal handler? */ - xSentinel = 0; - - if( pthread_self() == xThreadId ) { - debug_printf( "Pausing self, no reason to call signal handler\r\n" ); - pauseThread(); - } - else { - debug_printf( "About to kill %li\r\n", (long int) xThreadId ); - assert( pthread_kill( xThreadId, SIG_SUSPEND ) == 0); - debug_printf( "Killed %li\r\n", (long int) xThreadId ); - } - - -// while ( ( xSentinel == 0 ) && ( pdTRUE != xServicingTick ) ) - { -// debug_printf( "sched_yield()\r\n" ); - sched_yield(); - } -} -/*-----------------------------------------------------------*/ - -/*void prvResumeSignalHandler(int sig) -{ - - DB_P("prvResumeSignalHandler\r\n"); - - debug_printf( "prvResumeSignalHandler getLock"); - while(1); - // Yield the Scheduler to ensure that the yielding thread completes. - if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) - { - debug_printf( "prvResumeSignalHandler: unlocking xSingleThreadMutex (%li)\r\n", (long int) pthread_self()); - (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } -}*/ -/*-----------------------------------------------------------*/ - -/*void prvResumeThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult; - - DB_P("prvResumeThread\r\n"); - debug_printf( "getLock\r\n" ); - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) - { - debug_printf( "Resuming %li\r\n", (long int) xThreadId ); - if ( pthread_self() != xThreadId ) - { - //xResult = pthread_kill( xThreadId, SIG_RESUME ); - debug_printf( "No longer doing anything. Suspend handler for previous thread should start %li\r\n", (long int) xThreadId ); - } - else { - debug_printf( "Thread attempting to resume itself. This is not expected behavior\r\n" ); - kill( getpid(), SIGKILL ); - } - - xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } - else { - debug_printf("Error getting lock to resume thread\r\n"); - kill( getpid(), SIGKILL ); - } - -} */ -/*-----------------------------------------------------------*/ - -void prvSetupSignalsAndSchedulerPolicy( void ) -{ -/* The following code would allow for configuring the scheduling of this task as a Real-time task. - * The process would then need to be run with higher privileges for it to take affect. -int iPolicy; -int iResult; -int iSchedulerPriority; - iResult = pthread_getschedparam( pthread_self(), &iPolicy, &iSchedulerPriority ); - iResult = pthread_attr_setschedpolicy( &xThreadAttributes, SCHED_FIFO ); - iPolicy = SCHED_FIFO; - iResult = pthread_setschedparam( pthread_self(), iPolicy, &iSchedulerPriority ); */ - -struct sigaction sigsuspendself; -portLONG lIndex; - - debug_printf("prvSetupSignalAndSchedulerPolicy\r\n"); - - pxThreads = ( xThreadState *)pvPortMalloc( sizeof( xThreadState ) * MAX_NUMBER_OF_TASKS ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = ( xTaskHandle )NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - sigsuspendself.sa_flags = 0; - sigsuspendself.sa_handler = prvSuspendSignalHandler; - sigfillset( &sigsuspendself.sa_mask ); - - assert ( 0 == sigaction( SIG_SUSPEND, &sigsuspendself, NULL ) ); -} - -/*-----------------------------------------------------------*/ -pthread_mutex_t prvGetThreadMutex( xTaskHandle hTask ) -{ -pthread_mutex_t hMutex; -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hMutex = pxThreads[ lIndex ].hMutex; - break; - } - } - return hMutex; -} - -/*-----------------------------------------------------------*/ -xTaskHandle prvGetThreadTask( pthread_t hThread ) -{ -xTaskHandle hTask; -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == hThread ) - { - hTask = pxThreads[ lIndex ].hTask; - break; - } - } - return hTask; -} - -/*-----------------------------------------------------------*/ -pthread_cond_t prvGetThreadCondition( xTaskHandle hTask ) -{ -pthread_cond_t hCond; -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hCond = pxThreads[ lIndex ].hCond; - break; - } - } - return hCond; -} - -/*-----------------------------------------------------------*/ -pthread_t prvGetThreadHandle( xTaskHandle hTask ) -{ - pthread_t hThread = ( pthread_t )NULL; - portLONG lIndex; - - DB_P("prvGetThreadHandle\r\n"); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hThread = pxThreads[ lIndex ].hThread; - break; - } - } - return hThread; -} -/*-----------------------------------------------------------*/ - -portLONG prvGetFreeThreadState( void ) -{ -portLONG lIndex; - - DB_P("prvGetFreeThreadState\r\n"); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )NULL ) - { - break; - } - } - - if ( MAX_NUMBER_OF_TASKS == lIndex ) - { - printf( "No more free threads, please increase the maximum.\n" ); - lIndex = 0; - vPortEndScheduler(); - } - - return lIndex; -} -/*-----------------------------------------------------------*/ - -void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ) -{ -portLONG lIndex; - DB_P("prvSetTaskCriticalNesting\r\n"); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - pxThreads[ lIndex ].uxCriticalNesting = uxNesting; - break; - } - } -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ) -{ -unsigned portBASE_TYPE uxNesting = 0; -portLONG lIndex; - - DB_P("prvGetTaskCriticalNesting\r\n"); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - uxNesting = pxThreads[ lIndex ].uxCriticalNesting; - break; - } - } - return uxNesting; -} -/*-----------------------------------------------------------*/ - -void prvDeleteThread( void *xThreadId ) -{ -portLONG lIndex; - - DB_P("prvDeleteThread\r\n"); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )xThreadId ) - { - pxThreads[ lIndex ].hThread = (pthread_t)NULL; - pxThreads[ lIndex ].hTask = (xTaskHandle)NULL; - if ( pxThreads[ lIndex ].uxCriticalNesting > 0 ) - { - uxCriticalNesting = 0; - vPortEnableInterrupts(); - } - pxThreads[ lIndex ].uxCriticalNesting = 0; - break; - } - } -} -/*-----------------------------------------------------------*/ - -void vPortAddTaskHandle( void *pxTaskHandle ) -{ -portLONG lIndex; - - debug_printf("vPortAddTaskHandle\r\n"); - - pxThreads[ lIndexOfLastAddedTask ].hTask = ( xTaskHandle )pxTaskHandle; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == pxThreads[ lIndexOfLastAddedTask ].hThread ) - { - if ( pxThreads[ lIndex ].hTask != pxThreads[ lIndexOfLastAddedTask ].hTask ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - } - } -} -/*-----------------------------------------------------------*/ - -void vPortFindTicksPerSecond( void ) -{ - DB_P("vPortFindTicksPerSecond\r\n"); - - /* Needs to be reasonably high for accuracy. */ - //unsigned long ulTicksPerSecond = sysconf(_SC_CLK_TCK); - //printf( "Timer Resolution for Run TimeStats is %ld ticks per second.\n", ulTicksPerSecond ); -} -/*-----------------------------------------------------------*/ - -unsigned long ulPortGetTimerValue( void ) -{ -struct tms xTimes; - - DB_P("ulPortGetTimerValue\r\n"); - - unsigned long ulTotalTime = times( &xTimes ); - /* Return the application code times. - * The timer only increases when the application code is actually running - * which means that the total execution times should add up to 100%. - */ - return ( unsigned long ) xTimes.tms_utime; - - /* Should check ulTotalTime for being clock_t max minus 1. */ - (void)ulTotalTime; -} -/*-----------------------------------------------------------*/ diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/port.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/port.c deleted file mode 100644 index 128434fe3..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/port.c +++ /dev/null @@ -1,1085 +0,0 @@ -/* - Copyright (C) 2009 William Davy - william.davy@wittenstein.co.uk - Contributed to FreeRTOS.org V5.3.0. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org 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 FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the Posix port. - *----------------------------------------------------------*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" -/*-----------------------------------------------------------*/ - -#define MAX_NUMBER_OF_TASKS ( _POSIX_THREAD_THREADS_MAX ) -/*-----------------------------------------------------------*/ - -#ifndef __CYGWIN__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES - #define RUNNING_THREAD_MUTEX -#endif - -/* Parameters to pass to the newly created pthread. */ -typedef struct XPARAMS -{ - pdTASK_CODE pxCode; - void *pvParams; -} xParams; - -/* Each task maintains its own interrupt status in the critical nesting variable. */ -typedef struct THREAD_SUSPENSIONS -{ - pthread_t hThread; - pthread_cond_t * hCond; - pthread_mutex_t * hMutex; - xTaskHandle hTask; - portBASE_TYPE xThreadState; - unsigned portBASE_TYPE uxCriticalNesting; -} xThreadState; -/*-----------------------------------------------------------*/ - -static xThreadState *pxThreads; -static pthread_once_t hSigSetupThread = PTHREAD_ONCE_INIT; -static pthread_attr_t xThreadAttributes; -#ifdef RUNNING_THREAD_MUTEX -static pthread_mutex_t xRunningThread = PTHREAD_MUTEX_INITIALIZER; -#endif -static pthread_mutex_t xSuspendResumeThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xSwappingThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_t hMainThread = ( pthread_t )NULL; -/*-----------------------------------------------------------*/ - -static volatile portBASE_TYPE xSentinel = 0; -static volatile portBASE_TYPE xRunning = pdFALSE; -static volatile portBASE_TYPE xSuspended = pdFALSE; -static volatile portBASE_TYPE xStarted = pdFALSE; -static volatile portBASE_TYPE xHandover = 0; -static volatile portBASE_TYPE xSchedulerEnd = pdFALSE; -static volatile portBASE_TYPE xInterruptsEnabled = pdTRUE; -static volatile portBASE_TYPE xServicingTick = pdFALSE; -static volatile portBASE_TYPE xPendYield = pdFALSE; -static volatile portLONG lIndexOfLastAddedTask = 0; -static volatile unsigned portBASE_TYPE uxCriticalNesting; -/*-----------------------------------------------------------*/ - -/* - * Setup the timer to generate the tick interrupts. - */ -static void *prvWaitForStart( void * pvParams ); -static void prvSuspendSignalHandler(int sig); -static void prvSetupSignalsAndSchedulerPolicy( void ); -static void pauseThread( portBASE_TYPE pauseMode ); -static pthread_t prvGetThreadHandle( xTaskHandle hTask ); -#ifdef COND_SIGNALING -static pthread_cond_t * prvGetConditionHandle( xTaskHandle hTask ); -static pthread_mutex_t * prvGetMutexHandle( xTaskHandle hTask ); -#endif -static xTaskHandle prvGetTaskHandle( pthread_t hThread ); -static portLONG prvGetFreeThreadState( void ); -static void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ); -static unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ); -static void prvDeleteThread( void *xThreadId ); -/*-----------------------------------------------------------*/ - -/* - * Exception handlers. - */ -void vPortYield( void ); -void vPortSystemTickHandler( int sig ); - -#define THREAD_PAUSE_CREATED 0 -#define THREAD_PAUSE_YIELD 1 -#define THREAD_PAUSE_INTERRUPT 2 - -//#define DEBUG_OUTPUT -//#define ERROR_OUTPUT -#ifdef DEBUG_OUTPUT - - static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; - - #define debug_printf(...) ( (real_pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ","__unknown__",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?real_pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - - #define debug_error debug_printf - - int real_pthread_mutex_lock(pthread_mutex_t* mutex) { - return pthread_mutex_lock(mutex); - } - int real_pthread_mutex_unlock(pthread_mutex_t* mutex) { - return pthread_mutex_unlock(mutex); - } - #define pthread_mutex_lock(...) ( (debug_printf(" -!- pthread_mutex_lock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_lock(__VA_ARGS__):0 ) - #define pthread_mutex_unlock(...) ( (debug_printf(" -=- pthread_mutex_unlock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_unlock(__VA_ARGS__):0 ) - #define pthread_kill(thread,signal) ( (debug_printf("Sending signal %i to thread %li!\n",(int)signal,(long)thread)|1)?pthread_kill(thread,signal):0 ) - #define pthread_cond_signal( hCond ) (debug_printf( "pthread_cond_signals(%li)\r\n", *((long int *) hCond) ) ? 1 : pthread_cond_signal( hCond ) ) - #define pthread_cond_timedwait( hCond, hMutex, it ) (debug_printf( "pthread_cond_timedwait(%li,%li)\r\n", *((long int *) hCond), *((long int *) hMutex )) ? 1 : pthread_cond_timedwait( hCond, hMutex, it ) ) - #define pthread_sigmask( how, set, out ) (debug_printf( "pthread_sigmask( %i, %li )\r\n", how, *((long int*) set) ) ? 1 : pthread_sigmask( how, set, out ) ) - -#else - #ifdef ERROR_OUTPUT - static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; - #define debug_error(...) ( (pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ","__unknown__",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - - #define debug_printf(...) - #else - #define debug_printf(...) - #define debug_error(...) - #endif -#endif - - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -void vPortStartFirstTask( void ); -/*-----------------------------------------------------------*/ - - -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ -#endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - -#if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ -#endif - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; -#endif - -#if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ -#endif - -#if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ -#endif - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ -#endif - -} tskTCB; - -tskTCB *debug_task_handle; - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ -/* Should actually keep this struct on the stack. */ -xParams *pxThisThreadParams = pvPortMalloc( sizeof( xParams ) ); - - debug_printf("pxPortInitialiseStack\r\n"); - - (void)pthread_once( &hSigSetupThread, prvSetupSignalsAndSchedulerPolicy ); - - if ( (pthread_t)NULL == hMainThread ) - { - hMainThread = pthread_self(); - } - - /* No need to join the threads. */ - pthread_attr_init( &xThreadAttributes ); - pthread_attr_setdetachstate( &xThreadAttributes, PTHREAD_CREATE_DETACHED ); - - /* Add the task parameters. */ - pxThisThreadParams->pxCode = pxCode; - pxThisThreadParams->pvParams = pvParameters; - - vPortEnterCritical(); - - lIndexOfLastAddedTask = prvGetFreeThreadState(); - - debug_printf( "Got index for new task %i\r\n", lIndexOfLastAddedTask ); - -#ifdef COND_SIGNALING - /* Create a condition signal for this thread */ -// pthread_condattr_t condAttr; -// assert( 0 == pthread_condattr_init( &condAttr ) ); - pxThreads[ lIndexOfLastAddedTask ].hCond = ( pthread_cond_t *) malloc( sizeof( pthread_cond_t ) ); - assert( 0 == pthread_cond_init( pxThreads[ lIndexOfLastAddedTask ].hCond , NULL ) ); //&condAttr ) ); - debug_printf("Cond: %li\r\n", *( (long int *) &pxThreads[ lIndexOfLastAddedTask ].hCond) ); - - /* Create a condition mutex for this thread */ -// pthread_mutexattr_t mutexAttr; -// assert( 0 == pthread_mutexattr_init( &mutexAttr ) ); -// assert( 0 == pthread_mutexattr_settype( &mutexAttr, PTHREAD_MUTEX_ERRORCHECK ) ); - pxThreads[ lIndexOfLastAddedTask ].hMutex = ( pthread_mutex_t *) malloc( sizeof( pthread_mutex_t ) ); - assert( 0 == pthread_mutex_init( pxThreads[ lIndexOfLastAddedTask ].hMutex, NULL ) ); //&mutexAttr ) ); - debug_printf("Mutex: %li\r\n", *( (long int *) &pxThreads[ lIndexOfLastAddedTask ].hMutex) ); -#endif - - /* Create a thread and store it's handle number */ - xSentinel = 0; - assert( 0 == pthread_create( &( pxThreads[ lIndexOfLastAddedTask ].hThread ), &xThreadAttributes, prvWaitForStart, (void *)pxThisThreadParams ) ); - - /* Wait until the task suspends. */ - while ( xSentinel == 0 ); - vPortExitCritical(); - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortStartFirstTask( void ) -{ - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - debug_printf("vPortStartFirstTask\r\n"); - - /* Start the first task. */ - vPortEnableInterrupts(); - xRunning = 1; - - /* Start the first task. */ -#ifdef COND_SIGNALING - pthread_cond_t * hCond = prvGetConditionHandle( xTaskGetCurrentTaskHandle() ); - assert( pthread_cond_signal( hCond ) == 0 ); -#endif -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ -portBASE_TYPE xResult; -sigset_t xSignalToBlock; -portLONG lIndex; - - debug_printf( "xPortStartScheduler\r\n" ); - - /* Establish the signals to block before they are needed. */ - sigfillset( &xSignalToBlock ); - sigaddset( &xSignalToBlock, SIG_SUSPEND ); - - /* Block until the end */ - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, NULL ); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - /* Start the first task. Will not return unless all threads are killed. */ - vPortStartFirstTask(); - - struct timespec x; - usleep(1000000); - while( pdTRUE != xSchedulerEnd ) { - x.tv_sec=0; - x.tv_nsec=portTICK_RATE_MICROSECONDS * 1000; - nanosleep(&x,NULL); - //printf("."); fflush(stdout); - vPortSystemTickHandler(SIG_TICK); - } - - debug_printf( "Cleaning Up, Exiting.\n" ); - /* Cleanup the mutexes */ - xResult = pthread_mutex_destroy( &xSuspendResumeThreadMutex ); - xResult = pthread_mutex_destroy( &xSwappingThreadMutex ); - vPortFree( (void *)pxThreads ); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ -portBASE_TYPE xNumberOfThreads; -portBASE_TYPE xResult; - - - for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ ) - { - if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread ) - { - /* Kill all of the threads, they are in the detached state. */ - xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread ); - } - } - - /* Signal the scheduler to exit its loop. */ - xSchedulerEnd = pdTRUE; - (void)pthread_kill( hMainThread, SIG_RESUME ); -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Calling Yield from a Interrupt/Signal handler often doesn't work because the - * xSwappingThreadMutex is already owned by an original call to Yield. Therefore, - * simply indicate that a yield is required soon. - */ - - xPendYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - vPortDisableInterrupts(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - /* Check for unmatched exits. */ - if ( uxCriticalNesting > 0 ) - { - uxCriticalNesting--; - } - - /* If we have reached 0 then re-enable the interrupts. */ - if( uxCriticalNesting == 0 ) - { - /* Have we missed ticks? This is the equivalent of pending an interrupt. */ - if ( pdTRUE == xPendYield ) - { - xPendYield = pdFALSE; - vPortYield(); - } - vPortEnableInterrupts(); - } -} -/*-----------------------------------------------------------*/ - -void vPortYield( void ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -sigset_t xSignals; -tskTCB * oldTask, * newTask; - - /* We must mask the suspend signal here, because otherwise there can be an */ - /* interrupt while in pthread_mutex_lock and that will cause the next thread */ - /* to deadlock when it tries to get this mutex */ - - debug_printf( "Entering\r\n" ); - - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_SUSPEND ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL ); - - assert( pthread_mutex_lock( &xSwappingThreadMutex ) == 0); - - oldTask = xTaskGetCurrentTaskHandle(); - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - if(xTaskToSuspend != pthread_self() ) { - /* This means between masking the interrupt and getting the lock, there was an interrupt */ - /* and this task should suspend. Release the lock, then unmask interrupts to go ahead and */ - /* service the signal */ - - assert( 0 == pthread_mutex_unlock( &xSwappingThreadMutex ) ); - debug_printf( "The current task isn't even us, letting interrupt happen. Watch for swap.\r\n" ); - /* Now we are resuming, want to be able to catch this interrupt again */ - sigemptyset( &xSignals ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL); - return; - } - - xStarted = pdFALSE; - - /* Get new task then release the task switching mutex */ - vTaskSwitchContext(); - newTask = xTaskGetCurrentTaskHandle(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( pthread_self() != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - - debug_error( "Swapping From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); - -#ifdef COND_SIGNALING - /* Set resume condition for specific thread */ - pthread_cond_t * hCond = prvGetConditionHandle( xTaskGetCurrentTaskHandle() ); - assert( pthread_cond_signal( hCond ) == 0 ); -#endif -#ifdef CHECK_TASK_RESUMES - while( xStarted == pdFALSE ) - debug_printf( "Waiting for task to resume\r\n" ); -#endif - - debug_printf( "Detected task resuming. Pausing this task\r\n" ); - - /* Release swapping thread mutex and pause self */ - assert( pthread_mutex_unlock( &xSwappingThreadMutex ) == 0); - pauseThread( THREAD_PAUSE_YIELD ); - } - else { - assert( pthread_mutex_unlock( &xSwappingThreadMutex ) == 0); - } - - /* Now we are resuming, want to be able to catch this interrupt again */ - sigemptyset( &xSignals ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL); -} -/*-----------------------------------------------------------*/ - -void vPortDisableInterrupts( void ) -{ - //debug_printf("\r\n"); - xInterruptsEnabled = pdFALSE; -} -/*-----------------------------------------------------------*/ - -void vPortEnableInterrupts( void ) -{ - //debug_printf("\r\n"); - xInterruptsEnabled = pdTRUE; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xPortSetInterruptMask( void ) -{ -portBASE_TYPE xReturn = xInterruptsEnabled; - debug_printf("\r\n"); - xInterruptsEnabled = pdFALSE; - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vPortClearInterruptMask( portBASE_TYPE xMask ) -{ - debug_printf("\r\n"); - xInterruptsEnabled = xMask; -} -/*-----------------------------------------------------------*/ - - -void vPortSystemTickHandler( int sig ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -tskTCB * oldTask, * newTask; - - debug_printf( "\r\n\r\n" ); - debug_printf( "(xInterruptsEnabled = %i, xServicingTick = %i)\r\n", (int) xInterruptsEnabled != 0, (int) xServicingTick != 0); - if ( ( pdTRUE == xInterruptsEnabled ) && ( pdTRUE != xServicingTick ) ) - { -// debug_printf( "Checking for lock ...\r\n" ); - if ( 0 == pthread_mutex_trylock( &xSwappingThreadMutex ) ) - { - debug_printf( "Handling\r\n"); - xServicingTick = pdTRUE; - - oldTask = xTaskGetCurrentTaskHandle(); - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - /* Tick Increment. */ - vTaskIncrementTick(); - - /* Select Next Task. */ -#if ( configUSE_PREEMPTION == 1 ) - vTaskSwitchContext(); -#endif - - newTask = xTaskGetCurrentTaskHandle(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - debug_printf( "Want %s running\r\n", newTask->pcTaskName ); - /* The only thread that can process this tick is the running thread. */ - if ( xTaskToSuspend != xTaskToResume ) - { - xSuspended = pdFALSE; - xStarted = pdFALSE; - - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - - debug_printf( "Swapping From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); - -#ifdef CHECK_TASK_RESUMES - /* It shouldn't be possible for a second task swap to happen while waiting for this because */ - /* they can't get the xSwappingThreadMutex */ - while( xSuspended == pdFALSE ) -#endif - { - assert( pthread_kill( xTaskToSuspend, SIG_SUSPEND ) == 0); - sched_yield(); - } - -#ifdef CHECK_TASK_RESUMES - while( xStarted == pdFALSE) -#endif - { - -#ifdef COND_SIGNALING - // Set resume condition for specific thread - pthread_cond_t * hCond = prvGetConditionHandle( xTaskGetCurrentTaskHandle() ); - assert( pthread_cond_signal( hCond ) == 0 ); -#endif - assert( pthread_kill( xTaskToSuspend, SIG_SUSPEND ) == 0); - - sched_yield(); - } - - debug_printf( "Swapped From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); } - else - { - // debug_error ("Want %s running \r\n", newTask->pcTaskName ); - } - xServicingTick = pdFALSE; - (void)pthread_mutex_unlock( &xSwappingThreadMutex ); - } - else - { - debug_error( "Pending yield here (portYield has lock - hopefully)\r\n" ); - xPendYield = pdTRUE; - } - - } - else - { - debug_printf( "Pending yield or here\r\n"); - xPendYield = pdTRUE; - } -} -/*-----------------------------------------------------------*/ - -void vPortForciblyEndThread( void *pxTaskToDelete ) -{ -xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete; -pthread_t xTaskToDelete; -pthread_t xTaskToResume; -portBASE_TYPE xResult; - - printf("vPortForciblyEndThread\r\n"); - - if ( 0 == pthread_mutex_lock( &xSwappingThreadMutex ) ) - { - xTaskToDelete = prvGetThreadHandle( hTaskToDelete ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( xTaskToResume == xTaskToDelete ) - { - /* This is a suicidal thread, need to select a different task to run. */ - vTaskSwitchContext(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - } - - if ( pthread_self() != xTaskToDelete ) - { - /* Cancelling a thread that is not me. */ - if ( xTaskToDelete != ( pthread_t )NULL ) - { - /* Send a signal to wake the task so that it definitely cancels. */ - pthread_testcancel(); - xResult = pthread_cancel( xTaskToDelete ); - /* Pthread Clean-up function will note the cancellation. */ - } - (void)pthread_mutex_unlock( &xSwappingThreadMutex ); - } - else - { - /* Resume the other thread. */ - /* Assert zero - I never fixed this functionality */ - assert( 0 ); - - /* Pthread Clean-up function will note the cancellation. */ - /* Release the execution. */ - uxCriticalNesting = 0; - vPortEnableInterrupts(); - (void)pthread_mutex_unlock( &xSwappingThreadMutex ); - /* Commit suicide */ - pthread_exit( (void *)1 ); - } - } -} -/*-----------------------------------------------------------*/ - -void *prvWaitForStart( void * pvParams ) -{ -xParams * pxParams = ( xParams * )pvParams; -pdTASK_CODE pvCode = pxParams->pxCode; -void * pParams = pxParams->pvParams; - vPortFree( pvParams ); - - pthread_cleanup_push( prvDeleteThread, (void *)pthread_self() ); - - /* want to block suspend when not the active thread */ - sigset_t xSignals; - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_SUSPEND ); - assert( pthread_sigmask( SIG_BLOCK, &xSignals, NULL ) == 0); - - /* Because the FreeRTOS creates the TCB stack, which in this implementation */ - /* creates a thread, we need to wait until the task handle is added before */ - /* trying to pause. Must set xSentinel high so the creating task knows we're */ - /* here */ - - debug_printf("Thread started, waiting till handle is added\r\n"); - - xSentinel = 1; - - while( prvGetTaskHandle( pthread_self() ) == NULL ){ - sched_yield(); - } - - debug_printf("Handle added, pausing\r\n"); - - /* Want to delay briefly until we have explicit resume signal as otherwise the */ - /* current task variable might be in the wrong state */ - pauseThread( THREAD_PAUSE_CREATED ); - debug_printf("Starting first run\r\n"); - - sigemptyset( &xSignals ); - assert( pthread_sigmask( SIG_SETMASK, &xSignals, NULL ) == 0); - - pvCode( pParams ); - - pthread_cleanup_pop( 1 ); - return (void *)NULL; -} -/*-----------------------------------------------------------*/ - -void pauseThread( portBASE_TYPE pauseMode ) -{ - debug_printf( "Pausing thread %li. Set xSuspended false\r\n", (long int) pthread_self() ); - -#ifdef RUNNING_THREAD_MUTEX - if( pauseMode != THREAD_PAUSE_CREATED ) - assert( 0 == pthread_mutex_unlock( &xRunningThread ) ); -#endif - -#ifdef COND_SIGNALING - int xResult; - xTaskHandle hTask = prvGetTaskHandle( pthread_self() ); - pthread_cond_t * hCond = prvGetConditionHandle( hTask ); - pthread_mutex_t * hMutex = prvGetMutexHandle( hTask ); - debug_printf("Cond: %li\r\n", *( (long int *) hCond) ); - debug_printf("Mutex: %li\r\n", *( (long int *) hMutex) ); - - struct timeval tv; - struct timespec ts; - gettimeofday( &tv, NULL ); - ts.tv_sec = tv.tv_sec + 0; -#endif - - xSuspended = pdTRUE; - - while (1) { - if( pthread_self() == prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) && xRunning ) - { - - xStarted = pdTRUE; - -#ifdef RUNNING_THREAD_MUTEX - assert( 0 == pthread_mutex_lock( &xRunningThread ) ); -#endif - debug_error("Resuming\r\n"); - return; - } - else { -#ifdef COND_SIGNALING - gettimeofday( &tv, NULL ); - ts.tv_sec = ts.tv_sec + 1; - ts.tv_nsec = 0; - xResult = pthread_cond_timedwait( hCond, hMutex, &ts ); - assert( xResult != EINVAL ); -#else - /* For windows where conditional signaling is buggy */ - /* It would be wonderful to put a nanosleep here, but since its not reentrant safe */ - /* and there may be a sleep in the main code (this can be called from an ISR) we must */ - /* check this */ - if( pauseMode != THREAD_PAUSE_INTERRUPT ) - usleep(100); - sched_yield(); - -#endif -// debug_error( "Checked my status\r\n" ); - } - - } -} - -void prvSuspendSignalHandler(int sig) -{ -sigset_t xBlockSignals; - - /* This signal is set here instead of pauseThread because it is checked by the tick handler */ - /* which means if there were a swap it should result in a suspend interrupt */ - - debug_error( "Caught signal %i\r\n", sig ); - /* Check that we aren't suspending when we should be running. This bug would need tracking down */ - //assert( pthread_self() != prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) ); - if( pthread_self() == prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ) - { - debug_printf( "Suspend ISR called while this thread still marked active. Reflects buggy behavior in scheduler\r\n" ); - return; - } - - /* Block further suspend signals. They need to go to their thread */ - sigemptyset( &xBlockSignals ); - sigaddset( &xBlockSignals, SIG_SUSPEND ); - assert( pthread_sigmask( SIG_BLOCK, &xBlockSignals, NULL ) == 0); - - pauseThread( THREAD_PAUSE_INTERRUPT ); - -// assert( pthread_self() == prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ); - while( pthread_self() != prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ) - { - debug_printf( "Incorrectly woke up. Repausing\r\n" ); - pauseThread( THREAD_PAUSE_INTERRUPT ); - } - - /* Make sure the right thread is resuming */ - assert( pthread_self() == prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) ); - - /* Old synchronization code, may still be required - while( !xHandover ); - assert( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ); */ - - /* Respond to signals again */ - sigemptyset( &xBlockSignals ); - pthread_sigmask( SIG_SETMASK, &xBlockSignals, NULL ); - - debug_printf( "Resuming %li from signal %i\r\n", (long int) pthread_self(), sig ); - - /* Will resume here when the SIG_RESUME signal is received. */ - /* Need to set the interrupts based on the task's critical nesting. */ - if ( uxCriticalNesting == 0 ) - { - vPortEnableInterrupts(); - } - else - { - vPortDisableInterrupts(); - } - debug_printf("Exit\r\n"); -} - -/*-----------------------------------------------------------*/ - -void prvSetupSignalsAndSchedulerPolicy( void ) -{ -/* The following code would allow for configuring the scheduling of this task as a Real-time task. - * The process would then need to be run with higher privileges for it to take affect. -int iPolicy; -int iResult; -int iSchedulerPriority; - iResult = pthread_getschedparam( pthread_self(), &iPolicy, &iSchedulerPriority ); - iResult = pthread_attr_setschedpolicy( &xThreadAttributes, SCHED_FIFO ); - iPolicy = SCHED_FIFO; - iResult = pthread_setschedparam( pthread_self(), iPolicy, &iSchedulerPriority ); */ - -struct sigaction sigsuspendself; -portLONG lIndex; - - debug_printf("prvSetupSignalAndSchedulerPolicy\r\n"); - - pxThreads = ( xThreadState *)pvPortMalloc( sizeof( xThreadState ) * MAX_NUMBER_OF_TASKS ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = ( xTaskHandle )NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - sigsuspendself.sa_flags = 0; - sigsuspendself.sa_handler = prvSuspendSignalHandler; - sigfillset( &sigsuspendself.sa_mask ); - - assert ( 0 == sigaction( SIG_SUSPEND, &sigsuspendself, NULL ) ); -} - -/*-----------------------------------------------------------*/ -pthread_mutex_t * prvGetMutexHandle( xTaskHandle hTask ) -{ -pthread_mutex_t * hMutex; -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hMutex = pxThreads[ lIndex ].hMutex; - break; - } - } - return hMutex; -} - -/*-----------------------------------------------------------*/ -xTaskHandle prvGetTaskHandle( pthread_t hThread ) -{ -xTaskHandle hTask = NULL; -portLONG lIndex; - - /* If not initialized yet */ - if( pxThreads == NULL ) return NULL; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == hThread ) - { - hTask = pxThreads[ lIndex ].hTask; - break; - } - } - return hTask; -} - -/*-----------------------------------------------------------*/ -pthread_cond_t * prvGetConditionHandle( xTaskHandle hTask ) -{ -pthread_cond_t * hCond; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - debug_printf( "Found condition on %i task\r\n", lIndex ); - return pxThreads[ lIndex ].hCond; - break; - } - } - printf( "Failed to get handle, pausing then recursing\r\n" ); - usleep(1000); - return prvGetConditionHandle( hTask ); - assert(0); - return hCond; -} - -/*-----------------------------------------------------------*/ -pthread_t prvGetThreadHandle( xTaskHandle hTask ) -{ - pthread_t hThread = ( pthread_t )NULL; - portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hThread = pxThreads[ lIndex ].hThread; - break; - } - } - return hThread; -} -/*-----------------------------------------------------------*/ - -portLONG prvGetFreeThreadState( void ) -{ -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )NULL ) - { - break; - } - } - - if ( MAX_NUMBER_OF_TASKS == lIndex ) - { - printf( "No more free threads, please increase the maximum.\n" ); - lIndex = 0; - vPortEndScheduler(); - } - - return lIndex; -} -/*-----------------------------------------------------------*/ - -void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ) -{ -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - pxThreads[ lIndex ].uxCriticalNesting = uxNesting; - break; - } - } -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ) -{ -unsigned portBASE_TYPE uxNesting = 0; -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - uxNesting = pxThreads[ lIndex ].uxCriticalNesting; - break; - } - } - return uxNesting; -} -/*-----------------------------------------------------------*/ - -void prvDeleteThread( void *xThreadId ) -{ -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )xThreadId ) - { - pxThreads[ lIndex ].hThread = (pthread_t)NULL; - pxThreads[ lIndex ].hTask = (xTaskHandle)NULL; - if ( pxThreads[ lIndex ].uxCriticalNesting > 0 ) - { - uxCriticalNesting = 0; - vPortEnableInterrupts(); - } - pxThreads[ lIndex ].uxCriticalNesting = 0; - break; - } - } -} -/*-----------------------------------------------------------*/ - -void vPortAddTaskHandle( void *pxTaskHandle ) -{ -portLONG lIndex; - - debug_printf("vPortAddTaskHandle\r\n"); - - pxThreads[ lIndexOfLastAddedTask ].hTask = ( xTaskHandle )pxTaskHandle; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == pxThreads[ lIndexOfLastAddedTask ].hThread ) - { - if ( pxThreads[ lIndex ].hTask != pxThreads[ lIndexOfLastAddedTask ].hTask ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - } - } - usleep(10000); -} -/*-----------------------------------------------------------*/ - -void vPortFindTicksPerSecond( void ) -{ - - /* Needs to be reasonably high for accuracy. */ - unsigned long ulTicksPerSecond = sysconf(_SC_CLK_TCK); - printf( "Timer Resolution for Run TimeStats is %ld ticks per second.\n", ulTicksPerSecond ); -} -/*-----------------------------------------------------------*/ - -unsigned long ulPortGetTimerValue( void ) -{ -struct tms xTimes; - - unsigned long ulTotalTime = times( &xTimes ); - /* Return the application code times. - * The timer only increases when the application code is actually running - * which means that the total execution times should add up to 100%. - */ - return ( unsigned long ) xTimes.tms_utime; - - /* Should check ulTotalTime for being clock_t max minus 1. */ - (void)ulTotalTime; -} -/*-----------------------------------------------------------*/ diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c new file mode 100644 index 000000000..1deb36cc7 --- /dev/null +++ b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c @@ -0,0 +1,1092 @@ +/* + Copyright (C) 2011 Corvus Corax from OpenPilot.org + based on linux port from William Davy + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify it + under the terms of the GNU General Public License (version 2) as published + by the Free Software Foundation and modified by the FreeRTOS exception. + + FreeRTOS.org 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 FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 + Temple Place, Suite 330, Boston, MA 02111-1307 USA. + + A special exception to the GPL is included to allow you to distribute a + combined work that includes FreeRTOS.org without being obliged to provide + the source code for any proprietary components. See the licensing section + of http://www.FreeRTOS.org for full details. + + + *************************************************************************** + * * + * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * + * * + * This is a concise, step by step, 'hands on' guide that describes both * + * general multitasking concepts and FreeRTOS specifics. It presents and * + * explains numerous examples that are written using the FreeRTOS API. * + * Full source code for all the examples is provided in an accompanying * + * .zip file. * + * * + *************************************************************************** + + 1 tab == 4 spaces! + + Please ensure to read the configuration and relevant port sections of the + online documentation. + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/*----------------------------------------------------------- + * Implementation of functions defined in portable.h for the Posix port. + *----------------------------------------------------------*/ + + +/** Description of scheduler: + +This scheduler is based on posix signals to halt or preempt tasks, and on +pthread conditions to resume them. + +Each FreeRTOS thread is created as a posix thread, with a signal handler to +SIGUSR1 (SIG_SUSPEND) signals. + +Suspension of a thread is done by setting the threads state to +"YIELDING/PREEMPTING", then signaling the thread until the signal handler +changes that state to "SLEEPING", thus acknowledging the suspend. + +The thread will then wait within the signal handler for a thread specific +condition to be set, which allows it to resume operation, setting its state to +"RUNNING" + +The running thread also always holds a mutex (xRunningThreadMutex) which is +given up only when the thread suspends. + +On thread creation the new thread will acquire this mutex, then yield. + +Both preemption and yielding is done using the same mechanism, sending a +SIG_SUSPEND to the preempted thread respectively to itself, however different +synchronization safeguards apply depending if a thread suspends itself or is +suspended remotely + +Preemption is done by the main scheduler thread which attempts to run a tick +handler at accurate intervals using nanosleep and gettimeofday, which allows +more accurate high frequency ticks than a timer signal handler. + +All public functions in this port are protected by a safeguard mutex which +assures priority access on all data objects + +This approach is tested and works both on Linux and BSD style Unix (MAC OS X) + +*/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" +/*-----------------------------------------------------------*/ + +#define MAX_NUMBER_OF_TASKS ( _POSIX_THREAD_THREADS_MAX ) +/*-----------------------------------------------------------*/ + +#define PORT_PRINT(...) fprintf(stderr,__VA_ARGS__) +#define PORT_ASSERT(assertion) if ( !(assertion) ) { PORT_PRINT("Assertion failed in %s:%i " #assertion "\n",__FILE__,__LINE__); int volatile assfail=0; assfail=assfail/assfail; } + + +#define PORT_LOCK(mutex) PORT_ASSERT( 0 == pthread_mutex_lock(&(mutex)) ) +#define PORT_TRYLOCK(mutex) pthread_mutex_trylock(&(mutex)) +#define PORT_UNLOCK(mutex) PORT_ASSERT( 0 == pthread_mutex_unlock(&(mutex)) ) + + +/* Parameters to pass to the newly created pthread. */ +typedef struct XPARAMS +{ + pdTASK_CODE pxCode; + void *pvParams; +} xParams; + +/* Each task maintains its own interrupt status in the critical nesting variable. */ +typedef struct THREAD_SUSPENSIONS +{ + pthread_t hThread; + xTaskHandle hTask; + unsigned portBASE_TYPE uxCriticalNesting; + pthread_mutex_t threadSleepMutex; + pthread_cond_t threadSleepCond; + volatile enum {THREAD_SLEEPING,THREAD_RUNNING,THREAD_STARTING,THREAD_YIELDING,THREAD_PREEMPTING,THREAD_WAKING} threadStatus; +} xThreadState; +/*-----------------------------------------------------------*/ + +/* Needed to keep track of critical section depth before scheduler got started */ +static xThreadState xDummyThread = { .uxCriticalNesting=0, .threadStatus=THREAD_RUNNING }; + +static xThreadState *pxThreads = NULL; +static pthread_once_t hSigSetupThread = PTHREAD_ONCE_INIT; +static pthread_attr_t xThreadAttributes; +static pthread_mutex_t xRunningThreadMutex = PTHREAD_MUTEX_INITIALIZER; +static pthread_mutex_t xYieldingThreadMutex = PTHREAD_MUTEX_INITIALIZER; +static pthread_mutex_t xResumingThreadMutex = PTHREAD_MUTEX_INITIALIZER; +static pthread_mutex_t xGuardMutex = PTHREAD_MUTEX_INITIALIZER; +/*-----------------------------------------------------------*/ + +static volatile portBASE_TYPE xSchedulerEnd = pdFALSE; +static volatile portBASE_TYPE xSchedulerStarted = pdFALSE; +static volatile portBASE_TYPE xInterruptsEnabled = pdFALSE; +static volatile portBASE_TYPE xSchedulerNesting = 0; +static volatile portBASE_TYPE xPendYield = pdFALSE; +static volatile portLONG lIndexOfLastAddedTask = 0; +/*-----------------------------------------------------------*/ + +/* + * Setup the timer to generate the tick interrupts. + */ +static void *prvWaitForStart( void * pvParams ); +static void prvSuspendSignalHandler(int sig); +static void prvSetupSignalsAndSchedulerPolicy( void ); +static void prvResumeThread( xThreadState* xThreadId ); +static xThreadState* prvGetThreadHandle( xTaskHandle hTask ); +static xThreadState* prvGetThreadHandleByThread( pthread_t hThread ); +static portLONG prvGetFreeThreadState( void ); +static void prvDeleteThread( void *xThreadId ); +static void prvPortYield(); +/*-----------------------------------------------------------*/ + +/* + * Exception handlers. + */ +void vPortYield( void ); +void vPortSystemTickHandler( void ); + +/* + * Start first task is a separate function so it can be tested in isolation. + */ +void vPortStartFirstTask( void ); +/*-----------------------------------------------------------*/ + +/** + * inline macro functions + * (easierto debug than macros) + */ +static inline void PORT_ENTER() { + while( prvGetThreadHandleByThread(pthread_self())->threadStatus!=THREAD_RUNNING) sched_yield(); + PORT_LOCK( xGuardMutex ); + PORT_ASSERT( xSchedulerStarted?( prvGetThreadHandleByThread(pthread_self())==prvGetThreadHandle(xTaskGetCurrentTaskHandle()) ):pdTRUE ) +} + +static inline void PORT_LEAVE() { + PORT_ASSERT( xSchedulerStarted?( prvGetThreadHandleByThread(pthread_self())==prvGetThreadHandle(xTaskGetCurrentTaskHandle()) ):pdTRUE ); + PORT_ASSERT( prvGetThreadHandleByThread(pthread_self())->threadStatus==THREAD_RUNNING ); + PORT_UNLOCK( xGuardMutex ); +} + +/*-----------------------------------------------------------*/ + +/** + * Creates a new thread. + */ +portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) +{ + /* Should actually keep this struct on the stack. */ + xParams *pxThisThreadParams = pvPortMalloc( sizeof( xParams ) ); + + /* Initialize scheduler during first call */ + (void)pthread_once( &hSigSetupThread, prvSetupSignalsAndSchedulerPolicy ); + + /** + * port enter needs to be delayed since pvPortMalloc() and + * SetupSignalsAndSchedulerPolicy() both call critical section code + */ + PORT_ENTER(); + + /* No need to join the threads. */ + pthread_attr_init( &xThreadAttributes ); + pthread_attr_setdetachstate( &xThreadAttributes, PTHREAD_CREATE_DETACHED ); + + /* Add the task parameters. */ + pxThisThreadParams->pxCode = pxCode; + pxThisThreadParams->pvParams = pvParameters; + + lIndexOfLastAddedTask = prvGetFreeThreadState(); + + PORT_LOCK( xYieldingThreadMutex ); + + pxThreads[ lIndexOfLastAddedTask ].threadStatus = THREAD_STARTING; + pxThreads[ lIndexOfLastAddedTask ].uxCriticalNesting = 0; + + /* create the thead */ + PORT_ASSERT( 0 == pthread_create( &( pxThreads[ lIndexOfLastAddedTask ].hThread ), &xThreadAttributes, prvWaitForStart, (void *)pxThisThreadParams ) ); + + /* Let the task run a bit and wait until it suspends. */ + while ( pxThreads[ lIndexOfLastAddedTask ].threadStatus == THREAD_STARTING ) sched_yield(); + + /* this ensures the sleeping thread reached deep sleep (and not more) */ + PORT_UNLOCK( xYieldingThreadMutex ); + + PORT_LEAVE(); + + return pxTopOfStack; +} +/*-----------------------------------------------------------*/ + +/** + * Initially the schedulers main thread holds the running thread mutex. + * it needs to be given up, to allow the first running task to execute + */ +void vPortStartFirstTask( void ) +{ + /* Mark scheduler as started */ + xSchedulerStarted = pdTRUE; + + /* Start the first task. */ + prvResumeThread( prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ); + + /* Give up running thread handle */ + PORT_UNLOCK(xRunningThreadMutex); +} +/*-----------------------------------------------------------*/ + +/** + * After tasks have been set up the main thread goes into a sleeping loop, but + * allows to be interrupted by timer ticks. + */ +portBASE_TYPE xPortStartScheduler( void ) +{ + portBASE_TYPE xResult; + sigset_t xSignalToBlock; + + /** + * note: NO PORT_ENTER ! - this is the supervisor thread which runs outside + * of the schedulers context + */ + + /* do not respond to SUSPEND signal (but all others) */ + sigemptyset( &xSignalToBlock ); + (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, NULL ); + sigemptyset(&xSignalToBlock); + sigaddset(&xSignalToBlock,SIG_SUSPEND); + (void)pthread_sigmask(SIG_BLOCK, &xSignalToBlock, NULL); + + /* Start the first task. This gives up the RunningThreadMutex*/ + vPortStartFirstTask(); + + /** + * Main scheduling loop. Call the tick handler every + * portTICK_RATE_MICROSECONDS + */ + portLONG sleepTimeUS = portTICK_RATE_MICROSECONDS; + portLONG actualSleepTime; + struct timeval lastTime,currentTime; + gettimeofday( &lastTime, NULL ); + struct timespec wait; + + while ( pdTRUE != xSchedulerEnd ) + { + /* wait for the specified wait time */ + wait.tv_sec = sleepTimeUS / 1000000; + wait.tv_nsec = 1000 * ( sleepTimeUS % 1000000 ); + nanosleep( &wait, NULL ); + + /* check the time */ + gettimeofday( ¤tTime, NULL); + actualSleepTime = 1000000 * ( currentTime.tv_sec - lastTime.tv_sec ) + ( currentTime.tv_usec - lastTime.tv_usec ); + + /* only hit the tick if we slept at least half the period */ + if ( actualSleepTime >= sleepTimeUS/2 ) { + + vPortSystemTickHandler(); + + /* check the time again */ + gettimeofday( ¤tTime, NULL); + actualSleepTime = 1000000 * ( currentTime.tv_sec - lastTime.tv_sec ) + ( currentTime.tv_usec - lastTime.tv_usec ); + + /* sleep until the next tick is due */ + sleepTimeUS += portTICK_RATE_MICROSECONDS; + } + + /* reduce remaining sleep time by the slept time */ + sleepTimeUS -= actualSleepTime; + lastTime = currentTime; + + /* safety checks */ + if (sleepTimeUS <=0 || sleepTimeUS >= 3 * portTICK_RATE_MICROSECONDS) sleepTimeUS = portTICK_RATE_MICROSECONDS; + + } + + PORT_PRINT( "Cleaning Up, Exiting.\n" ); + /* Cleanup the mutexes */ + xResult = pthread_mutex_destroy( &xRunningThreadMutex ); + xResult = pthread_mutex_destroy( &xYieldingThreadMutex ); + xResult = pthread_mutex_destroy( &xGuardMutex ); + vPortFree( (void *)pxThreads ); + + /* Should not get here! */ + return 0; +} +/*-----------------------------------------------------------*/ + +/** + * quickly clean up all running threads, without asking them first + */ +void vPortEndScheduler( void ) +{ +portBASE_TYPE xNumberOfThreads; +portBASE_TYPE xResult; + for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ ) + { + if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread ) + { + /* Kill all of the threads, they are in the detached state. */ + xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread ); + } + } + + /* Signal the scheduler to exit its loop. */ + xSchedulerEnd = pdTRUE; +} +/*-----------------------------------------------------------*/ + +/** + * we must assume this one is called from outside the schedulers context + * (ISR's, signal handlers, or non-freertos threads) + * we cannot safely assume mutual exclusion + */ +void vPortYieldFromISR( void ) +{ + xPendYield = pdTRUE; +} +/*-----------------------------------------------------------*/ + +/** + * enter a critical section (public) + */ +void vPortEnterCritical( void ) +{ + PORT_ENTER(); + xInterruptsEnabled = pdFALSE; + prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting++; + PORT_LEAVE(); +} +/*-----------------------------------------------------------*/ + +/** + * leave a critical section (public) + */ +void vPortExitCritical( void ) +{ + PORT_ENTER(); + + /* Check for unmatched exits. */ + PORT_ASSERT( prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting > 0 ); + if ( prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting > 0 ) + { + prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting--; + } + + /* If we have reached 0 then re-enable the interrupts. */ + if( prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting == 0 ) + { + /* Have we missed ticks? This is the equivalent of pending an interrupt. */ + if ( pdTRUE == xPendYield ) + { + xPendYield = pdFALSE; + prvPortYield(); + } + + xInterruptsEnabled = pdTRUE; + + } + + PORT_LEAVE(); +} +/*-----------------------------------------------------------*/ + +/** + * code to self-yield a task + * (without the mutex encapsulation) + * for internal use + */ +void prvPortYield() +{ + xThreadState *xTaskToSuspend, *xTaskToResume; + + /* timer handler should NOT get in our way (just in case) */ + xInterruptsEnabled = pdFALSE; + + /* suspend the current task */ + xTaskToSuspend = prvGetThreadHandleByThread( pthread_self() ); + + /** + * make sure not to suspend threads that are already trying to do so + */ + PORT_ASSERT( xTaskToSuspend->threadStatus == THREAD_RUNNING ); + + /** + * FreeRTOS switch context + */ + vTaskSwitchContext(); + + /** + * find out which task to resume + */ + xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); + if ( xTaskToSuspend != xTaskToResume ) + { + /* Resume the other thread first */ + prvResumeThread( xTaskToResume ); + + /* prepare the current task for yielding */ + xTaskToSuspend->threadStatus = THREAD_YIELDING; + + /** + * Send signals until the signal handler acknowledges. How long that takes + * depends on the systems signal implementation. During a preemption we + * will see the actual THREAD_SLEEPING STATE - but when yielding we + * would only see a future THREAD_RUNNING after having woken up - both is + * OK + */ + while ( xTaskToSuspend->threadStatus == THREAD_YIELDING ) { + pthread_kill( xTaskToSuspend->hThread, SIG_SUSPEND ); + sched_yield(); + } + + /** + * mark: once we reach this point, the task has already slept and awaken anew + */ + + } else { + /** + * no context switch - keep running + */ + if (xTaskToResume->uxCriticalNesting==0) { + xInterruptsEnabled = pdTRUE; + } + } + +} +/*-----------------------------------------------------------*/ + +/** + * public yield function - secure + */ +void vPortYield( void ) +{ + PORT_ENTER(); + + prvPortYield(); + + PORT_LEAVE(); +} +/*-----------------------------------------------------------*/ + +/** + * public function to disable interrupts + */ +void vPortDisableInterrupts( void ) +{ + PORT_ENTER(); + + xInterruptsEnabled = pdFALSE; + + PORT_LEAVE(); +} +/*-----------------------------------------------------------*/ + +/** + * public function to enable interrupts + */ +void vPortEnableInterrupts( void ) +{ + PORT_ENTER(); + + /** + * It is bad practice to enable interrupts explicitly while in a critical section + * most likely this is a bug - better prevent the userspace from being stupid + */ + PORT_ASSERT( prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting == 0 ); + + xInterruptsEnabled = pdTRUE; + + PORT_LEAVE(); +} +/*-----------------------------------------------------------*/ + +/** + * set and clear interrupt masks are used by FreeRTOS to enter and leave critical sections + * with unknown nexting level - but we DO know the nesting level + */ +portBASE_TYPE xPortSetInterruptMask( void ) +{ + portBASE_TYPE xReturn; + + PORT_ENTER(); + + xReturn = xInterruptsEnabled; + + xInterruptsEnabled = pdFALSE; + + prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting++; + + PORT_LEAVE(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +/** + * sets the "interrupt mask back to a stored setting + */ +void vPortClearInterruptMask( portBASE_TYPE xMask ) +{ + PORT_ENTER(); + + /** + * we better make sure the calling code behaves + * if it doesn't it might indicate something went seriously wrong + */ + PORT_ASSERT( xMask == pdTRUE || xMask == pdFALSE ); + PORT_ASSERT( + ( prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting == 1 && xMask==pdTRUE ) + || + ( prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting > 1 && xMask==pdFALSE ) + ); + + xInterruptsEnabled = xMask; + if (prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting>0) { + prvGetThreadHandleByThread(pthread_self())->uxCriticalNesting--; + } + + PORT_LEAVE(); +} + +/*-----------------------------------------------------------*/ + +/** + * the tick handler is just an ordinary function, called by the supervisor thread periodically + */ +void vPortSystemTickHandler() +{ + /** + * the problem with the tick handler is, that it runs outside of the schedulers domain - worse, + * on a multi core machine there might be a task running *right now* + * - we need to stop it in order to do anything. However we need to make sure we are able to first + */ + PORT_LOCK( xGuardMutex ); + + /* thread MUST be running */ + if ( prvGetThreadHandle(xTaskGetCurrentTaskHandle())->threadStatus!=THREAD_RUNNING ) { + xPendYield = pdTRUE; + PORT_UNLOCK( xGuardMutex ); + return; + } + + /* interrupts MUST be enabled */ + if ( xInterruptsEnabled != pdTRUE ) { + xPendYield = pdTRUE; + PORT_UNLOCK( xGuardMutex ); + return; + } + + /* this should always be true, but it can't harm to check */ + PORT_ASSERT( prvGetThreadHandle(xTaskGetCurrentTaskHandle())->uxCriticalNesting==0 ); + + /* acquire switching mutex for synchronization */ + PORT_LOCK(xYieldingThreadMutex); + + xThreadState *xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); + + + /** + * halt current task - this means NO task is running! + * Send signals until the signal handler acknowledges. how long that takes + * depends on the systems signal implementation. During a preemption we + * will see the actual THREAD_SLEEPING STATE when yielding we would only + * see a future THREAD_RUNNING after having woken up both is OK + * note: we do NOT give up switchingThreadMutex! + */ + xTaskToSuspend->threadStatus = THREAD_PREEMPTING; + while ( xTaskToSuspend->threadStatus != THREAD_SLEEPING ) { + pthread_kill( xTaskToSuspend->hThread, SIG_SUSPEND ); + sched_yield(); + } + + /** + * synchronize and acquire the running thread mutex + */ + PORT_UNLOCK( xYieldingThreadMutex ); + PORT_LOCK( xRunningThreadMutex ); + + /** + * now the tick handler runs INSTEAD of the currently active thread + * - even on a multicore system + * failure to do so can lead to unexpected results during + * vTaskIncrementTick()... + */ + + /** + * call tick handler + */ + vTaskIncrementTick(); + + +#if ( configUSE_PREEMPTION == 1 ) + /** + * while we are here we can as well switch the running thread + */ + vTaskSwitchContext(); + + xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); +#endif + + /** + * wake up the task (again) + */ + prvResumeThread( xTaskToSuspend ); + + /** + * give control to the userspace task + */ + PORT_UNLOCK( xRunningThreadMutex ); + + /* finish up */ + PORT_UNLOCK( xGuardMutex ); +} +/*-----------------------------------------------------------*/ + +/** + * thread kill implementation + */ +void vPortForciblyEndThread( void *pxTaskToDelete ) +{ +xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete; +xThreadState* xTaskToDelete; +xThreadState* xTaskToResume; +portBASE_TYPE xResult; + + PORT_ENTER(); + + xTaskToDelete = prvGetThreadHandle( hTaskToDelete ); + xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); + + PORT_ASSERT( xTaskToDelete ); + PORT_ASSERT( xTaskToResume ); + + if ( xTaskToResume == xTaskToDelete ) + { + /* This is a suicidal thread, need to select a different task to run. */ + vTaskSwitchContext(); + xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); + } + + if ( pthread_self() != xTaskToDelete->hThread ) + { + /* Cancelling a thread that is not me. */ + + /* Send a signal to wake the task so that it definitely cancels. */ + pthread_testcancel(); + xResult = pthread_cancel( xTaskToDelete->hThread ); + + } + else + { + /* Resume the other thread. */ + prvResumeThread( xTaskToResume ); + /* Pthread Clean-up function will note the cancellation. */ + /* Release the execution. */ + + PORT_UNLOCK( xRunningThreadMutex ); + + //PORT_LEAVE(); + PORT_UNLOCK( xGuardMutex ); + /* Commit suicide */ + pthread_exit( (void *)1 ); + } + PORT_LEAVE(); +} +/*-----------------------------------------------------------*/ + +/** + * any new thread first acquires the runningThreadMutex, but then suspends + * immediately, giving control back to the thread starting the new one + */ +void *prvWaitForStart( void * pvParams ) +{ + xParams * pxParams = ( xParams * )pvParams; + pdTASK_CODE pvCode = pxParams->pxCode; + void * pParams = pxParams->pvParams; + sigset_t xSignalToBlock; + xThreadState * myself = prvGetThreadHandleByThread( pthread_self() ); + + pthread_cleanup_push( prvDeleteThread, (void *)pthread_self() ); + + /* do respond to signals */ + sigemptyset( &xSignalToBlock ); + (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, NULL ); + + /** + * Suspend ourselves. It's important to do that first + * because until we come back from this we run outside the schedulers scope + * and can't call functions like vPortFree() safely + */ + while ( myself->threadStatus == THREAD_STARTING ) { + pthread_kill( myself->hThread, SIG_SUSPEND ); + sched_yield(); + } + + /** + * now we have returned from the dead - reborn as a real thread inside the + * schedulers scope. + */ + vPortFree( pvParams ); + + /* run the actual payload */ + pvCode( pParams ); + + pthread_cleanup_pop( 1 ); + return (void *)NULL; +} +/*-----------------------------------------------------------*/ + +/** + * The suspend signal handler is called when a thread gets a SIGSUSPEND + * signal, which is supposed to send it to sleep + */ +void prvSuspendSignalHandler(int sig) +{ + + portBASE_TYPE hangover; + + /* make sure who we are */ + xThreadState* myself = prvGetThreadHandleByThread(pthread_self()); + PORT_ASSERT( myself ); + + /* make sure we are actually supposed to sleep */ + if (myself->threadStatus != THREAD_YIELDING && myself->threadStatus != THREAD_STARTING && myself->threadStatus != THREAD_PREEMPTING ) { + /* Spurious signal has arrived, we are not really supposed to halt. + * Not a real problem, we can safely ignore that. */ + return; + } + + /* we need that to wake up later (cond_wait needs a mutex locked) */ + PORT_LOCK(myself->threadSleepMutex); + + /* even waking up is a bit different depending on how we went to sleep */ + hangover = myself->threadStatus; + + myself->threadStatus = THREAD_SLEEPING; + + if ( hangover == THREAD_STARTING ) { + /** + * Synchronization with spawning thread through YieldingMutex + * This thread does NOT have the running thread mutex + * because it never officially ran before. + * It will get that mutex on wakeup though. + */ + PORT_LOCK(xYieldingThreadMutex); + PORT_UNLOCK(xYieldingThreadMutex); + } else if ( hangover == THREAD_YIELDING) { + /** + * The caller is the same thread as the signal handler. + * No synchronization possible or needed. + * But we need to unlock the mutexes it holds, so + * other threads can run. + */ + PORT_UNLOCK(xRunningThreadMutex ); + PORT_UNLOCK(xGuardMutex ); + } else if ( hangover == THREAD_PREEMPTING) { + /** + * The caller is the tick handler. + * Use YieldingMutex for synchronization + * Give up RunningThreadMutex, so the tick handler + * can take it and start another thread. + */ + PORT_LOCK(xYieldingThreadMutex); + PORT_UNLOCK(xRunningThreadMutex ); + PORT_UNLOCK(xYieldingThreadMutex); + } + + /* deep sleep until wake condition is met*/ + pthread_cond_wait( &myself->threadSleepCond, &myself->threadSleepMutex ); + + /* waking */ + myself->threadStatus = THREAD_WAKING; + + /* synchronize with waker - quick assertion if the right thread got the condition sent to*/ + PORT_LOCK(xResumingThreadMutex); + PORT_ASSERT(prvGetThreadHandle( xTaskGetCurrentTaskHandle())==myself); + PORT_UNLOCK(xResumingThreadMutex); + + /* we don't need that condition mutex anymore */ + PORT_UNLOCK(myself->threadSleepMutex); + + /* we ARE the running thread now (the one and only) */ + PORT_LOCK(xRunningThreadMutex); + + /** + * and we have important stuff to do, nobody should interfere with + * ( GuardMutex is usually set by PORT_ENTER() ) + * */ + PORT_LOCK( xGuardMutex ); + if ( myself->uxCriticalNesting == 0 ) + { + xInterruptsEnabled = pdTRUE; + } + else + { + xInterruptsEnabled = pdFALSE; + } + + myself->threadStatus = THREAD_RUNNING; + + /** + * if we jump back to user code, we are done with important stuff, + * but if we had yielded we are still in protected code after returning. + **/ + if (hangover!=THREAD_YIELDING) { + PORT_UNLOCK( xGuardMutex ); + } + +} +/*-----------------------------------------------------------*/ + +/** + * Signal the condition. + * Unlike pthread_kill this actually is supposed to be reliable, so we need no + * checks on the outcome. + */ +void prvResumeThread( xThreadState* xThreadId ) +{ + PORT_ASSERT( xThreadId ); + + PORT_LOCK( xResumingThreadMutex ); + + PORT_ASSERT(xThreadId->threadStatus == THREAD_SLEEPING); + + /** + * Unfortunately "is supposed to" does not hold on all Posix-ish systems + * but sending the cond_signal again doesn't hurt anyone. + */ + while ( xThreadId->threadStatus != THREAD_WAKING ) { + pthread_cond_signal(& xThreadId->threadSleepCond); + sched_yield(); + } + + PORT_UNLOCK( xResumingThreadMutex ); + +} +/*-----------------------------------------------------------*/ + +/** + * this is init code executed the first time a thread is created + */ +void prvSetupSignalsAndSchedulerPolicy( void ) +{ +/* The following code would allow for configuring the scheduling of this task as a Real-time task. + * The process would then need to be run with higher privileges for it to take affect. +int iPolicy; +int iResult; +int iSchedulerPriority; + iResult = pthread_getschedparam( pthread_self(), &iPolicy, &iSchedulerPriority ); + iResult = pthread_attr_setschedpolicy( &xThreadAttributes, SCHED_FIFO ); + iPolicy = SCHED_FIFO; + iResult = pthread_setschedparam( pthread_self(), iPolicy, &iSchedulerPriority ); */ + +struct sigaction sigsuspendself; +portLONG lIndex; + + pxThreads = ( xThreadState *)pvPortMalloc( sizeof( xThreadState ) * MAX_NUMBER_OF_TASKS ); + + const pthread_cond_t cinit = PTHREAD_COND_INITIALIZER; + const pthread_mutex_t minit = PTHREAD_MUTEX_INITIALIZER; + for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) + { + pxThreads[ lIndex ].hThread = ( pthread_t )NULL; + pxThreads[ lIndex ].hTask = ( xTaskHandle )NULL; + pxThreads[ lIndex ].uxCriticalNesting = 0; + pxThreads[ lIndex ].threadSleepMutex = minit; + pxThreads[ lIndex ].threadSleepCond = cinit; + } + + sigsuspendself.sa_flags = 0; + sigsuspendself.sa_handler = prvSuspendSignalHandler; + sigfillset( &sigsuspendself.sa_mask ); + + if ( 0 != sigaction( SIG_SUSPEND, &sigsuspendself, NULL ) ) + { + PORT_PRINT( "Problem installing SIG_SUSPEND_SELF\n" ); + } + PORT_PRINT( "Running as PID: %d\n", getpid() ); + + /* When scheduler is set up main thread first claims the running thread mutex */ + PORT_LOCK( xRunningThreadMutex ); + +} +/*-----------------------------------------------------------*/ + +/** + * get a thread handle based on a task handle + */ +xThreadState* prvGetThreadHandle( xTaskHandle hTask ) +{ +portLONG lIndex; +if (!pxThreads) return NULL; + for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) + { + if ( pxThreads[ lIndex ].hTask == hTask ) + { + return &pxThreads[ lIndex ]; + break; + } + } + return NULL; +} +/*-----------------------------------------------------------*/ + +/** + * get a thread handle based on a posix thread handle + */ +xThreadState* prvGetThreadHandleByThread( pthread_t hThread ) +{ +portLONG lIndex; + /** + * if the scheduler is NOT yet started, we can give back a dummy thread handle + * to allow keeping track of interrupt nesting. + * However once the scheduler is started we return a NULL, + * so any misbehaving code can nicely segfault. + */ + if (!xSchedulerStarted && !pxThreads) return &xDummyThread; + if (!pxThreads) return NULL; + for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) + { + if ( pxThreads[ lIndex ].hThread == hThread ) + { + return &pxThreads[ lIndex ]; + } + } + if (!xSchedulerStarted) return &xDummyThread; + return NULL; +} +/*-----------------------------------------------------------*/ + +/* next free task handle */ +portLONG prvGetFreeThreadState( void ) +{ +portLONG lIndex; + for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) + { + if ( pxThreads[ lIndex ].hThread == ( pthread_t )NULL ) + { + break; + } + } + + if ( MAX_NUMBER_OF_TASKS == lIndex ) + { + PORT_PRINT( "No more free threads, please increase the maximum.\n" ); + lIndex = 0; + vPortEndScheduler(); + } + + return lIndex; +} + +/*-----------------------------------------------------------*/ + +/** + * delete a thread from the list + */ +void prvDeleteThread( void *xThreadId ) +{ +portLONG lIndex; + for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) + { + if ( pxThreads[ lIndex ].hThread == ( pthread_t )xThreadId ) + { + pxThreads[ lIndex ].hThread = (pthread_t)NULL; + pxThreads[ lIndex ].hTask = (xTaskHandle)NULL; + if ( pxThreads[ lIndex ].uxCriticalNesting > 0 ) + { + //vPortEnableInterrupts(); + xInterruptsEnabled = pdTRUE; + } + pxThreads[ lIndex ].uxCriticalNesting = 0; + break; + } + } +} +/*-----------------------------------------------------------*/ + +/** + * add a thread to the list + */ +void vPortAddTaskHandle( void *pxTaskHandle ) +{ +portLONG lIndex; + + pxThreads[ lIndexOfLastAddedTask ].hTask = ( xTaskHandle )pxTaskHandle; + for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) + { + if ( pxThreads[ lIndex ].hThread == pxThreads[ lIndexOfLastAddedTask ].hThread ) + { + if ( pxThreads[ lIndex ].hTask != pxThreads[ lIndexOfLastAddedTask ].hTask ) + { + pxThreads[ lIndex ].hThread = ( pthread_t )NULL; + pxThreads[ lIndex ].hTask = NULL; + pxThreads[ lIndex ].uxCriticalNesting = 0; + } + } + } +} +/*-----------------------------------------------------------*/ + +/** + * find out system speed + */ +void vPortFindTicksPerSecond( void ) +{ + /* Needs to be reasonably high for accuracy. */ + unsigned long ulTicksPerSecond = sysconf(_SC_CLK_TCK); + PORT_PRINT( "Timer Resolution for Run TimeStats is %ld ticks per second.\n", ulTicksPerSecond ); +} +/*-----------------------------------------------------------*/ + +/** + * timer stuff + */ +unsigned long ulPortGetTimerValue( void ) +{ +struct tms xTimes; + unsigned long ulTotalTime = times( &xTimes ); + /* Return the application code times. + * The timer only increases when the application code is actually running + * which means that the total execution times should add up to 100%. + */ + return ( unsigned long ) xTimes.tms_utime; + + /* Should check ulTotalTime for being clock_t max minus 1. */ + (void)ulTotalTime; +} +/*-----------------------------------------------------------*/ + diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port_linux.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port_linux.c deleted file mode 100644 index 639dd1d33..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port_linux.c +++ /dev/null @@ -1,774 +0,0 @@ -/* - Copyright (C) 2009 William Davy - william.davy@wittenstein.co.uk - Contributed to FreeRTOS.org V5.3.0. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org 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 FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the Posix port. - *----------------------------------------------------------*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" -/*-----------------------------------------------------------*/ - -#define MAX_NUMBER_OF_TASKS ( _POSIX_THREAD_THREADS_MAX ) -/*-----------------------------------------------------------*/ - -/* Parameters to pass to the newly created pthread. */ -typedef struct XPARAMS -{ - pdTASK_CODE pxCode; - void *pvParams; -} xParams; - -/* Each task maintains its own interrupt status in the critical nesting variable. */ -typedef struct THREAD_SUSPENSIONS -{ - pthread_t hThread; - xTaskHandle hTask; - unsigned portBASE_TYPE uxCriticalNesting; -} xThreadState; -/*-----------------------------------------------------------*/ - -static xThreadState *pxThreads; -static pthread_once_t hSigSetupThread = PTHREAD_ONCE_INIT; -static pthread_attr_t xThreadAttributes; -static pthread_mutex_t xSuspendResumeThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xSingleThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_t hMainThread = ( pthread_t )NULL; -/*-----------------------------------------------------------*/ - -static volatile portBASE_TYPE xSentinel = 0; -static volatile portBASE_TYPE xSchedulerEnd = pdFALSE; -static volatile portBASE_TYPE xInterruptsEnabled = pdTRUE; -static volatile portBASE_TYPE xServicingTick = pdFALSE; -static volatile portBASE_TYPE xPendYield = pdFALSE; -static volatile portLONG lIndexOfLastAddedTask = 0; -static volatile unsigned portBASE_TYPE uxCriticalNesting; -/*-----------------------------------------------------------*/ - -/* - * Setup the timer to generate the tick interrupts. - */ -static void prvSetupTimerInterrupt( void ); -static void *prvWaitForStart( void * pvParams ); -static void prvSuspendSignalHandler(int sig); -static void prvResumeSignalHandler(int sig); -static void prvSetupSignalsAndSchedulerPolicy( void ); -static void prvSuspendThread( pthread_t xThreadId ); -static void prvResumeThread( pthread_t xThreadId ); -static pthread_t prvGetThreadHandle( xTaskHandle hTask ); -static portLONG prvGetFreeThreadState( void ); -static void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ); -static unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ); -static void prvDeleteThread( void *xThreadId ); -/*-----------------------------------------------------------*/ - -/* - * Exception handlers. - */ -void vPortYield( void ); -void vPortSystemTickHandler( int sig ); - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -void vPortStartFirstTask( void ); -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ -/* Should actually keep this struct on the stack. */ -xParams *pxThisThreadParams = pvPortMalloc( sizeof( xParams ) ); - - (void)pthread_once( &hSigSetupThread, prvSetupSignalsAndSchedulerPolicy ); - - if ( (pthread_t)NULL == hMainThread ) - { - hMainThread = pthread_self(); - } - - /* No need to join the threads. */ - pthread_attr_init( &xThreadAttributes ); - pthread_attr_setdetachstate( &xThreadAttributes, PTHREAD_CREATE_DETACHED ); - - /* Add the task parameters. */ - pxThisThreadParams->pxCode = pxCode; - pxThisThreadParams->pvParams = pvParameters; - - vPortEnterCritical(); - - lIndexOfLastAddedTask = prvGetFreeThreadState(); - - /* Create the new pThread. */ - if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) - { - xSentinel = 0; - if ( 0 != pthread_create( &( pxThreads[ lIndexOfLastAddedTask ].hThread ), &xThreadAttributes, prvWaitForStart, (void *)pxThisThreadParams ) ) - { - /* Thread create failed, signal the failure */ - pxTopOfStack = 0; - } - - /* Wait until the task suspends. */ - (void)pthread_mutex_unlock( &xSingleThreadMutex ); - while ( xSentinel == 0 ); - vPortExitCritical(); - } - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortStartFirstTask( void ) -{ - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - /* Start the first task. */ - vPortEnableInterrupts(); - - /* Start the first task. */ - prvResumeThread( prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ); -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ -portBASE_TYPE xResult; -int iSignal; -sigset_t xSignals; -sigset_t xSignalToBlock; -sigset_t xSignalsBlocked; -portLONG lIndex; - - /* Establish the signals to block before they are needed. */ - sigfillset( &xSignalToBlock ); - - /* Block until the end */ - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, &xSignalsBlocked ); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - /* Start the timer that generates the tick ISR. Interrupts are disabled - here already. */ - prvSetupTimerInterrupt(); - - /* Start the first task. Will not return unless all threads are killed. */ - vPortStartFirstTask(); - - /* This is the end signal we are looking for. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - - while ( pdTRUE != xSchedulerEnd ) - { - if ( 0 != sigwait( &xSignals, &iSignal ) ) - { - printf( "Main thread spurious signal: %d\n", iSignal ); - } - } - - printf( "Cleaning Up, Exiting.\n" ); - /* Cleanup the mutexes */ - xResult = pthread_mutex_destroy( &xSuspendResumeThreadMutex ); - xResult = pthread_mutex_destroy( &xSingleThreadMutex ); - vPortFree( (void *)pxThreads ); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ -portBASE_TYPE xNumberOfThreads; -portBASE_TYPE xResult; - for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ ) - { - if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread ) - { - /* Kill all of the threads, they are in the detached state. */ - xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread ); - } - } - - /* Signal the scheduler to exit its loop. */ - xSchedulerEnd = pdTRUE; - (void)pthread_kill( hMainThread, SIG_RESUME ); -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Calling Yield from a Interrupt/Signal handler often doesn't work because the - * xSingleThreadMutex is already owned by an original call to Yield. Therefore, - * simply indicate that a yield is required soon. - */ - xPendYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - vPortDisableInterrupts(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - /* Check for unmatched exits. */ - if ( uxCriticalNesting > 0 ) - { - uxCriticalNesting--; - } - - /* If we have reached 0 then re-enable the interrupts. */ - if( uxCriticalNesting == 0 ) - { - /* Have we missed ticks? This is the equivalent of pending an interrupt. */ - if ( pdTRUE == xPendYield ) - { - xPendYield = pdFALSE; - vPortYield(); - } - vPortEnableInterrupts(); - } -} -/*-----------------------------------------------------------*/ - -void vPortYield( void ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; - - if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) - { - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - vTaskSwitchContext(); - - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - if ( xTaskToSuspend != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - /* Switch tasks. */ - prvResumeThread( xTaskToResume ); - prvSuspendThread( xTaskToSuspend ); - } - else - { - /* Yielding to self */ - (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - } -} -/*-----------------------------------------------------------*/ - -void vPortDisableInterrupts( void ) -{ - xInterruptsEnabled = pdFALSE; -} -/*-----------------------------------------------------------*/ - -void vPortEnableInterrupts( void ) -{ - xInterruptsEnabled = pdTRUE; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xPortSetInterruptMask( void ) -{ -portBASE_TYPE xReturn = xInterruptsEnabled; - xInterruptsEnabled = pdFALSE; - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vPortClearInterruptMask( portBASE_TYPE xMask ) -{ - xInterruptsEnabled = xMask; -} -/*-----------------------------------------------------------*/ - -/* - * Setup the systick timer to generate the tick interrupts at the required - * frequency. - */ -void prvSetupTimerInterrupt( void ) -{ -struct itimerval itimer, oitimer; -portTickType xMicroSeconds = portTICK_RATE_MICROSECONDS; - - /* Initialise the structure with the current timer information. */ - if ( 0 == getitimer( TIMER_TYPE, &itimer ) ) - { - /* Set the interval between timer events. */ - itimer.it_interval.tv_sec = 0; - itimer.it_interval.tv_usec = xMicroSeconds; - - /* Set the current count-down. */ - itimer.it_value.tv_sec = 0; - itimer.it_value.tv_usec = xMicroSeconds; - - /* Set-up the timer interrupt. */ - if ( 0 != setitimer( TIMER_TYPE, &itimer, &oitimer ) ) - { - printf( "Set Timer problem.\n" ); - } - } - else - { - printf( "Get Timer problem.\n" ); - } -} -/*-----------------------------------------------------------*/ - -void vPortSystemTickHandler( int sig ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; - - if ( ( pdTRUE == xInterruptsEnabled ) && ( pdTRUE != xServicingTick ) ) - { - if ( 0 == pthread_mutex_trylock( &xSingleThreadMutex ) ) - { - xServicingTick = pdTRUE; - - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - /* Tick Increment. */ - vTaskIncrementTick(); - - /* Select Next Task. */ -#if ( configUSE_PREEMPTION == 1 ) - vTaskSwitchContext(); -#endif - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - /* The only thread that can process this tick is the running thread. */ - if ( xTaskToSuspend != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - /* Resume next task. */ - prvResumeThread( xTaskToResume ); - /* Suspend the current task. */ - prvSuspendThread( xTaskToSuspend ); - } - else - { - /* Release the lock as we are Resuming. */ - (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - xServicingTick = pdFALSE; - } - else - { - xPendYield = pdTRUE; - } - } - else - { - xPendYield = pdTRUE; - } -} -/*-----------------------------------------------------------*/ - -void vPortForciblyEndThread( void *pxTaskToDelete ) -{ -xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete; -pthread_t xTaskToDelete; -pthread_t xTaskToResume; -portBASE_TYPE xResult; - - if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) - { - xTaskToDelete = prvGetThreadHandle( hTaskToDelete ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( xTaskToResume == xTaskToDelete ) - { - /* This is a suicidal thread, need to select a different task to run. */ - vTaskSwitchContext(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - } - - if ( pthread_self() != xTaskToDelete ) - { - /* Cancelling a thread that is not me. */ - if ( xTaskToDelete != ( pthread_t )NULL ) - { - /* Send a signal to wake the task so that it definitely cancels. */ - pthread_testcancel(); - xResult = pthread_cancel( xTaskToDelete ); - /* Pthread Clean-up function will note the cancellation. */ - } - (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } - else - { - /* Resume the other thread. */ - prvResumeThread( xTaskToResume ); - /* Pthread Clean-up function will note the cancellation. */ - /* Release the execution. */ - uxCriticalNesting = 0; - vPortEnableInterrupts(); - (void)pthread_mutex_unlock( &xSingleThreadMutex ); - /* Commit suicide */ - pthread_exit( (void *)1 ); - } - } -} -/*-----------------------------------------------------------*/ - -void *prvWaitForStart( void * pvParams ) -{ -xParams * pxParams = ( xParams * )pvParams; -pdTASK_CODE pvCode = pxParams->pxCode; -void * pParams = pxParams->pvParams; - vPortFree( pvParams ); - - pthread_cleanup_push( prvDeleteThread, (void *)pthread_self() ); - - if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) - { - prvSuspendThread( pthread_self() ); - } - - pvCode( pParams ); - - pthread_cleanup_pop( 1 ); - return (void *)NULL; -} -/*-----------------------------------------------------------*/ - -void prvSuspendSignalHandler(int sig) -{ -sigset_t xSignals; - - /* Only interested in the resume signal. */ - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_RESUME ); - xSentinel = 1; - - /* Unlock the Single thread mutex to allow the resumed task to continue. */ - if ( 0 != pthread_mutex_unlock( &xSingleThreadMutex ) ) - { - printf( "Releasing someone else's lock.\n" ); - } - - /* Wait on the resume signal. */ - if ( 0 != sigwait( &xSignals, &sig ) ) - { - printf( "SSH: Sw %d\n", sig ); - } - - /* Will resume here when the SIG_RESUME signal is received. */ - /* Need to set the interrupts based on the task's critical nesting. */ - if ( uxCriticalNesting == 0 ) - { - vPortEnableInterrupts(); - } - else - { - vPortDisableInterrupts(); - } -} -/*-----------------------------------------------------------*/ - -void prvSuspendThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult = pthread_mutex_lock( &xSuspendResumeThreadMutex ); - if ( 0 == xResult ) - { - /* Set-up for the Suspend Signal handler? */ - xSentinel = 0; - xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - xResult = pthread_kill( xThreadId, SIG_SUSPEND ); - while ( ( xSentinel == 0 ) && ( pdTRUE != xServicingTick ) ) - { - sched_yield(); - } - } -} -/*-----------------------------------------------------------*/ - -void prvResumeSignalHandler(int sig) -{ - /* Yield the Scheduler to ensure that the yielding thread completes. */ - if ( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ) - { - (void)pthread_mutex_unlock( &xSingleThreadMutex ); - } -} -/*-----------------------------------------------------------*/ - -void prvResumeThread( pthread_t xThreadId ) -{ -portBASE_TYPE xResult; - if ( 0 == pthread_mutex_lock( &xSuspendResumeThreadMutex ) ) - { - if ( pthread_self() != xThreadId ) - { - xResult = pthread_kill( xThreadId, SIG_RESUME ); - } - xResult = pthread_mutex_unlock( &xSuspendResumeThreadMutex ); - } -} -/*-----------------------------------------------------------*/ - -void prvSetupSignalsAndSchedulerPolicy( void ) -{ -/* The following code would allow for configuring the scheduling of this task as a Real-time task. - * The process would then need to be run with higher privileges for it to take affect. -int iPolicy; -int iResult; -int iSchedulerPriority; - iResult = pthread_getschedparam( pthread_self(), &iPolicy, &iSchedulerPriority ); - iResult = pthread_attr_setschedpolicy( &xThreadAttributes, SCHED_FIFO ); - iPolicy = SCHED_FIFO; - iResult = pthread_setschedparam( pthread_self(), iPolicy, &iSchedulerPriority ); */ - -struct sigaction sigsuspendself, sigresume, sigtick; -portLONG lIndex; - - pxThreads = ( xThreadState *)pvPortMalloc( sizeof( xThreadState ) * MAX_NUMBER_OF_TASKS ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = ( xTaskHandle )NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - sigsuspendself.sa_flags = 0; - sigsuspendself.sa_handler = prvSuspendSignalHandler; - sigfillset( &sigsuspendself.sa_mask ); - - sigresume.sa_flags = 0; - sigresume.sa_handler = prvResumeSignalHandler; - sigfillset( &sigresume.sa_mask ); - - sigtick.sa_flags = 0; - sigtick.sa_handler = vPortSystemTickHandler; - sigfillset( &sigtick.sa_mask ); - - if ( 0 != sigaction( SIG_SUSPEND, &sigsuspendself, NULL ) ) - { - printf( "Problem installing SIG_SUSPEND_SELF\n" ); - } - if ( 0 != sigaction( SIG_RESUME, &sigresume, NULL ) ) - { - printf( "Problem installing SIG_RESUME\n" ); - } - if ( 0 != sigaction( SIG_TICK, &sigtick, NULL ) ) - { - printf( "Problem installing SIG_TICK\n" ); - } - printf( "Running as PID: %d\n", getpid() ); -} -/*-----------------------------------------------------------*/ - -pthread_t prvGetThreadHandle( xTaskHandle hTask ) -{ -pthread_t hThread = ( pthread_t )NULL; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hThread = pxThreads[ lIndex ].hThread; - break; - } - } - return hThread; -} -/*-----------------------------------------------------------*/ - -portLONG prvGetFreeThreadState( void ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )NULL ) - { - break; - } - } - - if ( MAX_NUMBER_OF_TASKS == lIndex ) - { - printf( "No more free threads, please increase the maximum.\n" ); - lIndex = 0; - vPortEndScheduler(); - } - - return lIndex; -} -/*-----------------------------------------------------------*/ - -void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - pxThreads[ lIndex ].uxCriticalNesting = uxNesting; - break; - } - } -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ) -{ -unsigned portBASE_TYPE uxNesting = 0; -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - uxNesting = pxThreads[ lIndex ].uxCriticalNesting; - break; - } - } - return uxNesting; -} -/*-----------------------------------------------------------*/ - -void prvDeleteThread( void *xThreadId ) -{ -portLONG lIndex; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )xThreadId ) - { - pxThreads[ lIndex ].hThread = (pthread_t)NULL; - pxThreads[ lIndex ].hTask = (xTaskHandle)NULL; - if ( pxThreads[ lIndex ].uxCriticalNesting > 0 ) - { - uxCriticalNesting = 0; - vPortEnableInterrupts(); - } - pxThreads[ lIndex ].uxCriticalNesting = 0; - break; - } - } -} -/*-----------------------------------------------------------*/ - -void vPortAddTaskHandle( void *pxTaskHandle ) -{ -portLONG lIndex; - - pxThreads[ lIndexOfLastAddedTask ].hTask = ( xTaskHandle )pxTaskHandle; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == pxThreads[ lIndexOfLastAddedTask ].hThread ) - { - if ( pxThreads[ lIndex ].hTask != pxThreads[ lIndexOfLastAddedTask ].hTask ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - } - } -} -/*-----------------------------------------------------------*/ - -void vPortFindTicksPerSecond( void ) -{ - /* Needs to be reasonably high for accuracy. */ - unsigned long ulTicksPerSecond = sysconf(_SC_CLK_TCK); - printf( "Timer Resolution for Run TimeStats is %ld ticks per second.\n", ulTicksPerSecond ); -} -/*-----------------------------------------------------------*/ - -unsigned long ulPortGetTimerValue( void ) -{ -struct tms xTimes; - unsigned long ulTotalTime = times( &xTimes ); - /* Return the application code times. - * The timer only increases when the application code is actually running - * which means that the total execution times should add up to 100%. - */ - return ( unsigned long ) xTimes.tms_utime; - - /* Should check ulTotalTime for being clock_t max minus 1. */ - (void)ulTotalTime; -} -/*-----------------------------------------------------------*/ diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port_posix.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port_posix.c deleted file mode 100644 index db0e4d71e..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port_posix.c +++ /dev/null @@ -1,1258 +0,0 @@ -/* - Copyright (C) 2009 William Davy - william.davy@wittenstein.co.uk - Contributed to FreeRTOS.org V5.3.0. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org 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 FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the Posix port. - *----------------------------------------------------------*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" -/*-----------------------------------------------------------*/ - -#define MAX_NUMBER_OF_TASKS ( _POSIX_THREAD_THREADS_MAX ) -/*-----------------------------------------------------------*/ - -/* Parameters to pass to the newly created pthread. */ -typedef struct XPARAMS -{ - pdTASK_CODE pxCode; - void *pvParams; -} xParams; - -/* Each task maintains its own interrupt status in the critical nesting variable. */ -typedef struct THREAD_SUSPENSIONS -{ - pthread_t hThread; - pthread_cond_t * hCond; - pthread_mutex_t * hMutex; - xTaskHandle hTask; - portBASE_TYPE xThreadState; - unsigned portBASE_TYPE uxCriticalNesting; -} xThreadState; -/*-----------------------------------------------------------*/ - -static xThreadState *pxThreads; -static pthread_once_t hSigSetupThread = PTHREAD_ONCE_INIT; -static pthread_attr_t xThreadAttributes; -#ifdef RUNNING_THREAD_MUTEX -static pthread_mutex_t xRunningThread = PTHREAD_MUTEX_INITIALIZER; -#endif -static pthread_mutex_t xSuspendResumeThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_mutex_t xSwappingThreadMutex = PTHREAD_MUTEX_INITIALIZER; -static pthread_t hMainThread = ( pthread_t )NULL; -/*-----------------------------------------------------------*/ - -static volatile portBASE_TYPE xSentinel = pdFALSE; -static volatile portBASE_TYPE xRunning = pdFALSE; -static volatile portBASE_TYPE xSchedulerEnd = pdFALSE; -static volatile portBASE_TYPE xInterruptsEnabled = pdTRUE; -static volatile portBASE_TYPE xServicingTick = pdFALSE; -static volatile portBASE_TYPE xPendYield = pdFALSE; -static volatile portLONG lIndexOfLastAddedTask = 0; -static volatile unsigned portBASE_TYPE uxCriticalNesting; -/*-----------------------------------------------------------*/ - -/* - * Setup the timer to generate the tick interrupts. - */ -static void *prvWaitForStart( void * pvParams ); -static void prvSuspendSignalHandler(int sig); -static void prvSetupSignalsAndSchedulerPolicy( void ); -static void pauseThread( portBASE_TYPE pauseMode ); -static pthread_t prvGetThreadHandle( xTaskHandle hTask ); -#ifdef COND_SIGNALING -static pthread_cond_t * prvGetConditionHandle( xTaskHandle hTask ); -static pthread_mutex_t * prvGetMutexHandle( xTaskHandle hTask ); -#endif -#ifdef CHECK_TASK_RESUMES -static portBASE_TYPE prvGetTaskState( xTaskHandle hTask ); -#endif -static void prvSetTaskState( xTaskHandle hTask, portBASE_TYPE state ); -static xTaskHandle prvGetTaskHandle( pthread_t hThread ); -static portLONG prvGetFreeThreadState( void ); -static void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ); -static unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ); -static void prvDeleteThread( void *xThreadId ); -/*-----------------------------------------------------------*/ - -/* - * Exception handlers. - */ -void vPortYield( void ); -void vPortSystemTickHandler( int sig ); - -#define THREAD_PAUSE_CREATED 0 -#define THREAD_PAUSE_YIELD 1 -#define THREAD_PAUSE_INTERRUPT 2 - -#define THREAD_STATE_PAUSE 1 -#define THREAD_STATE_RUNNING 2 - -//#define DEBUG_OUTPUT -//#define ERROR_OUTPUT -#ifdef DEBUG_OUTPUT - - static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; - - #define debug_printf(...) ( (real_pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ","__unknown__",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?real_pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - - #define debug_error debug_printf - - int real_pthread_mutex_lock(pthread_mutex_t* mutex) { - return pthread_mutex_lock(mutex); - } - int real_pthread_mutex_unlock(pthread_mutex_t* mutex) { - return pthread_mutex_unlock(mutex); - } - #define pthread_mutex_trylock(...) ( (debug_printf(" -!- pthread_mutex_trylock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_trylock(__VA_ARGS__):0 ) - #define pthread_mutex_lock(...) ( (debug_printf(" -!- pthread_mutex_lock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_lock(__VA_ARGS__):0 ) - #define pthread_mutex_unlock(...) ( (debug_printf(" -=- pthread_mutex_unlock(%s)\n",#__VA_ARGS__)|1)?pthread_mutex_unlock(__VA_ARGS__):0 ) - #define pthread_kill(thread,signal) ( (debug_printf("Sending signal %i to thread %li!\n",(int)signal,(long)thread)|1)?pthread_kill(thread,signal):0 ) - #define pthread_cond_signal( hCond ) (debug_printf( "pthread_cond_signals(%li)\r\n", *((long int *) hCond) ) ? 1 : pthread_cond_signal( hCond ) ) - #define pthread_cond_timedwait( hCond, hMutex, it ) (debug_printf( "pthread_cond_timedwait(%li,%li)\r\n", *((long int *) hCond), *((long int *) hMutex )) ? 1 : pthread_cond_timedwait( hCond, hMutex, it ) ) - #define pthread_sigmask( how, set, out ) (debug_printf( "pthread_sigmask( %i, %li )\r\n", how, *((long int*) set) ) ? 1 : pthread_sigmask( how, set, out ) ) - -#else - #ifdef ERROR_OUTPUT - static pthread_mutex_t xPrintfMutex = PTHREAD_MUTEX_INITIALIZER; - #define debug_error(...) ( (pthread_mutex_lock( &xPrintfMutex )|1)?( \ - ( \ - (NULL != (debug_task_handle = prvGetTaskHandle(pthread_self())) )? \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ",debug_task_handle->pcTaskName,(long)pthread_self(),__func__,__LINE__)): \ - (fprintf( stderr, "%20s(%li)\t%20s\t%i: ","__unknown__",(long)pthread_self(),__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?pthread_mutex_unlock( &xPrintfMutex ):0) \ - ):0 ):0 ) - - #define debug_printf(...) - #else - #define debug_printf(...) - #define debug_error(...) - #endif -#endif - - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -void vPortStartFirstTask( void ); -/*-----------------------------------------------------------*/ - - -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ -#endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - -#if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ -#endif - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; -#endif - -#if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ -#endif - -#if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ -#endif - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ -#endif - -} tskTCB; - -tskTCB *debug_task_handle; - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ -/* Should actually keep this struct on the stack. */ -xParams *pxThisThreadParams = pvPortMalloc( sizeof( xParams ) ); - - debug_printf("pxPortInitialiseStack\r\n"); - - (void)pthread_once( &hSigSetupThread, prvSetupSignalsAndSchedulerPolicy ); - - if ( (pthread_t)NULL == hMainThread ) - { - hMainThread = pthread_self(); - } - - /* No need to join the threads. */ - pthread_attr_init( &xThreadAttributes ); - pthread_attr_setdetachstate( &xThreadAttributes, PTHREAD_CREATE_DETACHED ); - - /* Add the task parameters. */ - pxThisThreadParams->pxCode = pxCode; - pxThisThreadParams->pvParams = pvParameters; - - vPortEnterCritical(); - - lIndexOfLastAddedTask = prvGetFreeThreadState(); - - debug_printf( "Got index for new task %i\r\n", lIndexOfLastAddedTask ); - -#ifdef COND_SIGNALING - /* Create a condition signal for this thread */ -// pthread_condattr_t condAttr; -// assert( 0 == pthread_condattr_init( &condAttr ) ); - pxThreads[ lIndexOfLastAddedTask ].hCond = ( pthread_cond_t *) malloc( sizeof( pthread_cond_t ) ); - assert( 0 == pthread_cond_init( pxThreads[ lIndexOfLastAddedTask ].hCond , NULL ) ); //&condAttr ) ); - debug_printf("Cond: %li\r\n", *( (long int *) &pxThreads[ lIndexOfLastAddedTask ].hCond) ); - - /* Create a condition mutex for this thread */ -// pthread_mutexattr_t mutexAttr; -// assert( 0 == pthread_mutexattr_init( &mutexAttr ) ); -// assert( 0 == pthread_mutexattr_settype( &mutexAttr, PTHREAD_MUTEX_ERRORCHECK ) ); - pxThreads[ lIndexOfLastAddedTask ].hMutex = ( pthread_mutex_t *) malloc( sizeof( pthread_mutex_t ) ); - assert( 0 == pthread_mutex_init( pxThreads[ lIndexOfLastAddedTask ].hMutex, NULL ) ); //&mutexAttr ) ); - debug_printf("Mutex: %li\r\n", *( (long int *) &pxThreads[ lIndexOfLastAddedTask ].hMutex) ); -#endif - - /* Create a thread and store it's handle number */ - xSentinel = 0; - assert( 0 == pthread_create( &( pxThreads[ lIndexOfLastAddedTask ].hThread ), &xThreadAttributes, prvWaitForStart, (void *)pxThisThreadParams ) ); - - /* Wait until the task suspends. */ - while ( xSentinel == 0 ); - vPortExitCritical(); - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortStartFirstTask( void ) -{ - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - debug_printf("vPortStartFirstTask\r\n"); - - /* Start the first task. */ - vPortEnableInterrupts(); - xRunning = 1; - - /* Start the first task. */ -#ifdef COND_SIGNALING - pthread_cond_t * hCond = prvGetConditionHandle( xTaskGetCurrentTaskHandle() ); -// careful! race condition? if u mutex lock here, could u start the tick handler more early? - assert( pthread_cond_signal( hCond ) == 0 ); -#endif -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ -portBASE_TYPE xResult; -sigset_t xSignalToBlock; -portLONG lIndex; - - debug_printf( "xPortStartScheduler\r\n" ); - - /* Establish the signals to block before they are needed. */ - sigemptyset( &xSignalToBlock ); - sigaddset( &xSignalToBlock, SIG_SUSPEND ); - sigaddset( &xSignalToBlock, SIG_TICK ); - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, NULL ); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - - /* Start the first task. Will not return unless all threads are killed. */ - vPortStartFirstTask(); - - /* Unfortunately things are stable if we start ticking during setup. This need to be */ - /* checked careful in startup on hardware */ - usleep(1000000); - -#if defined(TICK_SIGNAL) || defined(TICK_SIGWAIT) - - struct itimerval itimer; - portTickType xMicroSeconds = portTICK_RATE_MICROSECONDS; - - debug_printf("init %li microseconds\n",(long)xMicroSeconds); - /* Initialise the structure with the current timer information. */ - assert ( 0 == getitimer( TIMER_TYPE, &itimer ) ); - - /* Set the interval between timer events. */ - itimer.it_interval.tv_sec = 0; - itimer.it_interval.tv_usec = xMicroSeconds; - - /* Set the current count-down. */ - itimer.it_value.tv_sec = 0; - itimer.it_value.tv_usec = xMicroSeconds; - -#endif - -#ifdef TICK_SIGNAL - struct sigaction sigtick; - sigtick.sa_flags = 0; - sigtick.sa_handler = vPortSystemTickHandler; - sigfillset( &sigtick.sa_mask ); - assert ( 0 == sigaction( SIG_TICK, &sigtick, NULL ) ); - - /* Set-up the timer interrupt. */ - assert ( 0 == setitimer( TIMER_TYPE, &itimer, NULL ) ); - - sigemptyset( &xSignalToBlock ); - sigaddset( &xSignalToBlock, SIG_SUSPEND ); - (void)pthread_sigmask( SIG_SETMASK, &xSignalToBlock, NULL ); - - while(1) - { - usleep(1000); - sched_yield(); - } -#endif - -#ifdef TICK_SIGWAIT - /* Tick signal already blocked */ - sigset_t xSignalsToWait; - sigemptyset( &xSignalsToWait ); - sigaddset( &xSignalsToWait, SIG_TICK ); - - /* Set-up the timer interrupt. */ - assert ( 0 == setitimer( TIMER_TYPE, &itimer, NULL ) ); - - while( pdTRUE != xSchedulerEnd ) { - int xResult; - assert( 0 == sigwait( &xSignalsToWait, &xResult ) ); -// assert( xResult == SIG_TICK ); - vPortSystemTickHandler(SIG_TICK); - } -#endif - -#if !defined(TICK_SIGNAL) && !defined(TICK_SIGWAIT) - - struct timespec x; - while( pdTRUE != xSchedulerEnd ) { - x.tv_sec=0; - x.tv_nsec=portTICK_RATE_MICROSECONDS * 1000; - nanosleep(&x,NULL); -// careful - on some systems a signal to ANY thread in the process will -// end nanosleeps immediately - better sleep with pselect() and set the -// wakeup sigmask to all blocked (see test_case_x_pselect.c) -// printf("."); fflush(stdout); - vPortSystemTickHandler(SIG_TICK); -// printf("*"); fflush(stdout); - } - -#endif - debug_printf( "Cleaning Up, Exiting.\n" ); - /* Cleanup the mutexes */ - xResult = pthread_mutex_destroy( &xSuspendResumeThreadMutex ); - xResult = pthread_mutex_destroy( &xSwappingThreadMutex ); - vPortFree( (void *)pxThreads ); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ -portBASE_TYPE xNumberOfThreads; -portBASE_TYPE xResult; - - - for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ ) - { - if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread ) - { - /* Kill all of the threads, they are in the detached state. */ - xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread ); - } - } - - /* Signal the scheduler to exit its loop. */ - xSchedulerEnd = pdTRUE; - (void)pthread_kill( hMainThread, SIG_RESUME ); -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Calling Yield from a Interrupt/Signal handler often doesn't work because the - * xSwappingThreadMutex is already owned by an original call to Yield. Therefore, - * simply indicate that a yield is required soon. - */ - - xPendYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - vPortDisableInterrupts(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - /* Check for unmatched exits. */ - if ( uxCriticalNesting > 0 ) - { -// careful - race condition possible? - uxCriticalNesting--; - } - - /* If we have reached 0 then re-enable the interrupts. */ - if( uxCriticalNesting == 0 ) - { - /* Have we missed ticks? This is the equivalent of pending an interrupt. */ - if ( pdTRUE == xPendYield ) - { - xPendYield = pdFALSE; - vPortYield(); - } - vPortEnableInterrupts(); - } -} -/*-----------------------------------------------------------*/ - -void vPortYield( void ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -int retVal; -tskTCB * oldTask, * newTask; - - /* We must mask the suspend signal here, because otherwise there can be an */ - /* interrupt while in pthread_mutex_lock and that will cause the next thread */ - /* to deadlock when it tries to get this mutex */ - - debug_printf( "Entering\r\n" ); - - vPortEnterCritical(); - - retVal = pthread_mutex_trylock( &xSwappingThreadMutex ); - while( retVal != 0 ) { - - assert( retVal == EBUSY ); - - /* If we can't get the mutex, that means an interrupt is running and we */ - /* should keep an eye out if this task should suspend so the interrupt */ - /* routine doesn't stall waiting for this task to pause */ - debug_printf( "Waiting to get swapping mutex from ISR\r\n" ); - - assert( xTaskGetCurrentTaskHandle() != NULL ); - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); -// careful! race condition!!!! unprotected by mutex - - if( prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) != pthread_self() ) { -// careful! race condition!!!! unprotected by mutex - debug_printf( "The current task isn't even us. Pausing now, deal with possible interrupt later.\r\n" ); - vPortExitCritical(); - pauseThread( THREAD_PAUSE_YIELD ); - - return; - } - sched_yield(); - retVal = pthread_mutex_trylock( &xSwappingThreadMutex ); - } - - /* At this point we have the lock, active task shouldn't change */ - oldTask = xTaskGetCurrentTaskHandle(); - assert( oldTask != NULL ); - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if(xTaskToSuspend != pthread_self() ) { - debug_printf( "The current task isn't even us, letting interrupt happen. Watch for swap.\r\n" ); - - assert( pthread_mutex_unlock( &xSwappingThreadMutex ) == 0); - vPortExitCritical(); - pauseThread( THREAD_PAUSE_YIELD ); - - return; - } - - assert( xTaskToSuspend == pthread_self() ); // race condition I didn't account for - - /* Get new task then release the task switching mutex */ - vTaskSwitchContext(); - newTask = xTaskGetCurrentTaskHandle(); - assert( newTask != NULL ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( pthread_self() != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - - debug_error( "Swapping From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); - -#ifdef COND_SIGNALING - /* Set resume condition for specific thread */ - pthread_cond_t * hCond = prvGetConditionHandle( xTaskGetCurrentTaskHandle() ); - assert( pthread_cond_signal( hCond ) == 0 ); -#endif -#ifdef CHECK_TASK_RESUMES - while( prvGetTaskState( oldTask ) != THREAD_STATE_RUNNING ) - { - usleep(100); - sched_yield(); - debug_printf( "Waiting for task to resume\r\n" ); - } -#endif - - debug_printf( "Detected task resuming. Pausing this task\r\n" ); - - /* Release swapping thread mutex and pause self */ - assert( pthread_mutex_unlock( &xSwappingThreadMutex ) == 0); - pauseThread( THREAD_PAUSE_YIELD ); - } - else { - assert( pthread_mutex_unlock( &xSwappingThreadMutex ) == 0); - } - - /* Now we are resuming, want to be able to catch this interrupt again */ - vPortExitCritical(); - -} -/*-----------------------------------------------------------*/ - -void vPortDisableInterrupts( void ) -{ - //debug_printf("\r\n"); - sigset_t xSignals; - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_SUSPEND ); - pthread_sigmask( SIG_BLOCK, &xSignals, NULL ); - - xInterruptsEnabled = pdFALSE; -} -/*-----------------------------------------------------------*/ - -void vPortEnableInterrupts( void ) -{ - - xInterruptsEnabled = pdTRUE; - //debug_printf("\r\n"); - sigset_t xSignals; - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_SUSPEND ); - pthread_sigmask( SIG_UNBLOCK, &xSignals, NULL ); -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xPortSetInterruptMask( void ) -{ -portBASE_TYPE xReturn = xInterruptsEnabled; - debug_printf("\r\n"); - xInterruptsEnabled = pdFALSE; - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vPortClearInterruptMask( portBASE_TYPE xMask ) -{ - debug_printf("\r\n"); - xInterruptsEnabled = xMask; -} -/*-----------------------------------------------------------*/ - - -void vPortSystemTickHandler( int sig ) -{ -pthread_t xTaskToSuspend; -pthread_t xTaskToResume; -tskTCB * oldTask, * newTask; - -/* assert( SIG_TICK == sig ); - assert( prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) != NULL ); - assert( pthread_self() != prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ); */ - - debug_printf( "\r\n\r\n" ); - debug_printf( "(xInterruptsEnabled = %i, xServicingTick = %i)\r\n", (int) xInterruptsEnabled != 0, (int) xServicingTick != 0); - if ( ( pdTRUE == xInterruptsEnabled ) && ( pdTRUE != xServicingTick ) ) - { -// debug_printf( "Checking for lock ...\r\n" ); - if ( 0 == pthread_mutex_trylock( &xSwappingThreadMutex ) ) - { - debug_printf( "Handling\r\n"); - xServicingTick = pdTRUE; - - oldTask = xTaskGetCurrentTaskHandle(); - assert( oldTask != NULL ); - xTaskToSuspend = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - /* Tick Increment. */ - vTaskIncrementTick(); - - /* Select Next Task. */ -#if ( configUSE_PREEMPTION == 1 ) - vTaskSwitchContext(); -#endif - - newTask = xTaskGetCurrentTaskHandle(); - assert( newTask != NULL ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - debug_printf( "Want %s running\r\n", newTask->pcTaskName ); - /* The only thread that can process this tick is the running thread. */ - if ( xTaskToSuspend != xTaskToResume ) - { - /* Remember and switch the critical nesting. */ - prvSetTaskCriticalNesting( xTaskToSuspend, uxCriticalNesting ); - uxCriticalNesting = prvGetTaskCriticalNesting( xTaskToResume ); - - debug_printf( "Swapping From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); - - assert( pthread_kill( xTaskToSuspend, SIG_SUSPEND ) == 0); - -#ifdef CHECK_TASK_RESUMES - /* It shouldn't be possible for a second task swap to happen while waiting for this because */ - /* they can't get the xSwappingThreadMutex */ - while( prvGetTaskState( oldTask ) != THREAD_STATE_PAUSE ) -#endif - { - usleep(100); - debug_printf( "Waiting for old task to suspend\r\n" ); - debug_printf( "Sent signal\r\n" ); - sched_yield(); - } - debug_printf( "Suspended\r\n" ); - -#ifdef CHECK_TASK_RESUMES - while( prvGetTaskState( newTask ) != THREAD_STATE_RUNNING ) -#endif - { - debug_printf( "Waiting for new task to resume\r\n" ); -#ifdef COND_SIGNALING - // Set resume condition for specific thread - pthread_cond_t * hCond = prvGetConditionHandle( xTaskGetCurrentTaskHandle() ); - assert( pthread_cond_signal( hCond ) == 0 ); -#endif - - sched_yield(); - } - - debug_printf( "Swapped From %li(%s) to %li(%s)\r\n", (long int) xTaskToSuspend, oldTask->pcTaskName, (long int) xTaskToResume, newTask->pcTaskName); } - else - { - // debug_error ("Want %s running \r\n", newTask->pcTaskName ); - } - xServicingTick = pdFALSE; - (void)pthread_mutex_unlock( &xSwappingThreadMutex ); - } - else - { - debug_error( "Pending yield here (portYield has lock - hopefully)\r\n" ); - xPendYield = pdTRUE; - } - - } - else - { - debug_printf( "Pending yield or here\r\n"); - xPendYield = pdTRUE; - } - debug_printf("Exiting\r\n"); -} -/*-----------------------------------------------------------*/ - -void vPortForciblyEndThread( void *pxTaskToDelete ) -{ -xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete; -pthread_t xTaskToDelete; -pthread_t xTaskToResume; -portBASE_TYPE xResult; - - printf("vPortForciblyEndThread\r\n"); - - if ( 0 == pthread_mutex_lock( &xSwappingThreadMutex ) ) -// careful! windows bug - this thread won't be suspendable while waiting for mutex! -// so tick handler will wait forever for this thread to go to sleep -// might want to put a try_lock() - sched_yield() loop when on cygwin! - { - xTaskToDelete = prvGetThreadHandle( hTaskToDelete ); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - - if ( xTaskToResume == xTaskToDelete ) - { - /* This is a suicidal thread, need to select a different task to run. */ - vTaskSwitchContext(); - xTaskToResume = prvGetThreadHandle( xTaskGetCurrentTaskHandle() ); - } - - if ( pthread_self() != xTaskToDelete ) - { - /* Cancelling a thread that is not me. */ - if ( xTaskToDelete != ( pthread_t )NULL ) - { - /* Send a signal to wake the task so that it definitely cancels. */ - pthread_testcancel(); - xResult = pthread_cancel( xTaskToDelete ); - /* Pthread Clean-up function will note the cancellation. */ - } - (void)pthread_mutex_unlock( &xSwappingThreadMutex ); - } - else - { - /* Resume the other thread. */ - /* Assert zero - I never fixed this functionality */ - assert( 0 ); -// careful! will be hit every time a thread exits itself gracefully - better fix this, we might need -// it - - /* Pthread Clean-up function will note the cancellation. */ - /* Release the execution. */ - uxCriticalNesting = 0; - vPortEnableInterrupts(); - (void)pthread_mutex_unlock( &xSwappingThreadMutex ); - /* Commit suicide */ - pthread_exit( (void *)1 ); - } - } -} -/*-----------------------------------------------------------*/ - -void *prvWaitForStart( void * pvParams ) -{ -xParams * pxParams = ( xParams * )pvParams; -pdTASK_CODE pvCode = pxParams->pxCode; -void * pParams = pxParams->pvParams; - vPortFree( pvParams ); - - pthread_cleanup_push( prvDeleteThread, (void *)pthread_self() ); - - /* want to block suspend when not the active thread */ - sigset_t xSignals; - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_SUSPEND ); - sigaddset( &xSignals, SIG_TICK ); - assert( pthread_sigmask( SIG_SETMASK, &xSignals, NULL ) == 0); - - /* Because the FreeRTOS creates the TCB stack, which in this implementation */ - /* creates a thread, we need to wait until the task handle is added before */ - /* trying to pause. Must set xSentinel high so the creating task knows we're */ - /* here. Order is strange but because of how this is hacked onto the trace */ - /*handling code in tasks.c */ - xSentinel = 1; - - while( prvGetTaskHandle( pthread_self() ) == NULL ){ - sched_yield(); - } - - debug_printf("Handle added, pausing\r\n"); - - /* Want to delay briefly until we have explicit resume signal as otherwise the */ - /* current task variable might be in the wrong state */ - pauseThread( THREAD_PAUSE_CREATED ); - debug_printf("Starting first run\r\n"); - - /* Since all starting tasks have the critical nesting at zero, just enable interrupts */ - vPortEnableInterrupts(); - - pvCode( pParams ); - - pthread_cleanup_pop( 1 ); - return (void *)NULL; -} -/*-----------------------------------------------------------*/ - -void pauseThread( portBASE_TYPE pauseMode ) -{ - xTaskHandle hTask = prvGetTaskHandle( pthread_self() ); - - debug_printf( "Pausing thread %li. Set state to suspended\r\n", (long int) pthread_self() ); - prvSetTaskState( hTask, THREAD_STATE_PAUSE ); - -#ifdef RUNNING_THREAD_MUTEX - if( pauseMode != THREAD_PAUSE_CREATED ) - assert( 0 == pthread_mutex_unlock( &xRunningThread ) ); -#endif - -#ifdef COND_SIGNALING - int xResult; - pthread_cond_t * hCond = prvGetConditionHandle( hTask ); - pthread_mutex_t * hMutex = prvGetMutexHandle( hTask ); - debug_printf("Cond: %li\r\n", *( (long int *) hCond) ); - debug_printf("Mutex: %li\r\n", *( (long int *) hMutex) ); - - struct timeval tv; - struct timespec ts; - gettimeofday( &tv, NULL ); - ts.tv_sec = tv.tv_sec + 0; -#endif - - while (1) { - assert( xTaskGetCurrentTaskHandle() != NULL ); - if( pthread_self() == prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) && xRunning ) -// careful! race condition!!!! possibly unprotected by mutex when CHECK_TASK_RESUMES is not set? - { - - /* Must do this before trying to lock the mutex, because if CHECK_TASK_RESUMES */ - /* is defined then the mutex not unlocked until this is changed */ - debug_printf( "Resuming. Marking task as running\r\n" ); - prvSetTaskState( hTask, THREAD_STATE_RUNNING ); - -#ifdef RUNNING_THREAD_MUTEX - assert( 0 == pthread_mutex_lock( &xRunningThread ) ); -#endif - debug_error("Resuming\r\n"); - return; - } - else { -#ifdef COND_SIGNALING - gettimeofday( &tv, NULL ); - ts.tv_sec = ts.tv_sec + 1; - ts.tv_nsec = 0; - xResult = pthread_cond_timedwait( hCond, hMutex, &ts ); - assert( xResult != EINVAL ); -#else - /* For windows where conditional signaling is buggy */ - /* It would be wonderful to put a nanosleep here, but since its not reentrant safe */ - /* and there may be a sleep in the main code (this can be called from an ISR) we must */ - /* check this */ - if( pauseMode != THREAD_PAUSE_INTERRUPT ) - usleep(1000); - sched_yield(); - -#endif -// debug_error( "Checked my status\r\n" ); - } - - } -} - -void prvSuspendSignalHandler(int sig) -{ -//sigset_t xBlockSignals; - - /* This signal is set here instead of pauseThread because it is checked by the tick handler */ - /* which means if there were a swap it should result in a suspend interrupt */ - - debug_error( "Caught signal %i\r\n", sig ); - -#ifdef CHECK_TASK_RESUMES - /* This would seem like a major bug, but can happen because now we send extra suspend signals */ - /* if they aren't caught */ - assert( xTaskGetCurrentTaskHandle() != NULL ); - if( pthread_self() == prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ) { -// careful! race condition? Or does the tick handler wait for us to sleep before unlocking? - debug_printf( "Marked as current task, resuming\r\n" ); - return; - } -#endif - - /* Check that we aren't suspending when we should be running. This bug would need tracking down */ -// assert( pthread_self() != prvGetThreadHandle(xTaskGetCurrentTaskHandle() ) ); - - /* Block further suspend signals. They need to go to their thread */ -/* sigemptyset( &xBlockSignals ); - sigaddset( &xBlockSignals, SIG_SUSPEND ); - assert( pthread_sigmask( SIG_BLOCK, &xBlockSignals, NULL ) == 0); - - assert( xTaskGetCurrentTaskHandle() != NULL ); - while( pthread_self() != prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ) -// careful! race condition? could a port_yield mess with this? - { - debug_printf( "Incorrectly woke up. Repausing\r\n" ); */ - pauseThread( THREAD_PAUSE_INTERRUPT ); -/* } - - assert( xTaskGetCurrentTaskHandle() != NULL ); - assert( pthread_self() == prvGetThreadHandle( xTaskGetCurrentTaskHandle() ) ); */ - - /* Old synchronization code, may still be required - while( !xHandover ); - assert( 0 == pthread_mutex_lock( &xSingleThreadMutex ) ); */ - - /* Respond to signals again */ -/* sigemptyset( &xBlockSignals ); - sigaddset( &xBlockSignals, SIG_SUSPEND ); - assert( 0 == pthread_sigmask( SIG_UNBLOCK, &xBlockSignals, NULL ) ); - - debug_printf( "Resuming %li from signal %i\r\n", (long int) pthread_self(), sig ); */ - - /* Will resume here when the SIG_RESUME signal is received. */ - /* Need to set the interrupts based on the task's critical nesting. */ - if ( uxCriticalNesting == 0 ) - { - vPortEnableInterrupts(); - } - else - { - debug_printf( "Not reenabling interrupts\r\n" ); - vPortDisableInterrupts(); - } - debug_printf("Exit\r\n"); -} - -/*-----------------------------------------------------------*/ - -void prvSetupSignalsAndSchedulerPolicy( void ) -{ -/* The following code would allow for configuring the scheduling of this task as a Real-time task. - * The process would then need to be run with higher privileges for it to take affect. -int iPolicy; -int iResult; -int iSchedulerPriority; - iResult = pthread_getschedparam( pthread_self(), &iPolicy, &iSchedulerPriority ); - iResult = pthread_attr_setschedpolicy( &xThreadAttributes, SCHED_FIFO ); - iPolicy = SCHED_FIFO; - iResult = pthread_setschedparam( pthread_self(), iPolicy, &iSchedulerPriority ); */ - -struct sigaction sigsuspendself; -portLONG lIndex; - - debug_printf("prvSetupSignalAndSchedulerPolicy\r\n"); - - pxThreads = ( xThreadState *)pvPortMalloc( sizeof( xThreadState ) * MAX_NUMBER_OF_TASKS ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = ( xTaskHandle )NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - pxThreads[ lIndex ].xThreadState = 0; - } - - sigsuspendself.sa_flags = 0; - sigsuspendself.sa_handler = prvSuspendSignalHandler; - sigemptyset( &sigsuspendself.sa_mask ); - - assert ( 0 == sigaction( SIG_SUSPEND, &sigsuspendself, NULL ) ); -} - -/*-----------------------------------------------------------*/ -pthread_mutex_t * prvGetMutexHandle( xTaskHandle hTask ) -{ -pthread_mutex_t * hMutex; -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hMutex = pxThreads[ lIndex ].hMutex; - break; - } - } - return hMutex; -} - -/*-----------------------------------------------------------*/ -xTaskHandle prvGetTaskHandle( pthread_t hThread ) -{ -portLONG lIndex; - - /* If not initialized yet */ - if( pxThreads == NULL ) return NULL; - assert( hThread != (pthread_t) NULL ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == hThread ) - { - return pxThreads[ lIndex ].hTask; - } - } -// assert( 0 ); - return NULL; -} - -/*-----------------------------------------------------------*/ -pthread_cond_t * prvGetConditionHandle( xTaskHandle hTask ) -{ -pthread_cond_t * hCond = NULL; -portLONG lIndex; - - assert( hTask != NULL ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - debug_printf( "Found condition on %i task\r\n", lIndex ); - hCond = pxThreads[ lIndex ].hCond; - break; - } - } - assert( hCond != NULL ); - return hCond; - printf( "Failed to get handle, pausing then recursing\r\n" ); - usleep(1000); - return prvGetConditionHandle( hTask ); - assert(0); - return hCond; -} - -/*-----------------------------------------------------------*/ -#ifdef CHECK_TASK_RESUMES -static portBASE_TYPE prvGetTaskState( xTaskHandle hTask ) -{ -portLONG lIndex; - assert( hTask != NULL ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - debug_printf( "Found state (%li) on %i task\r\n",pxThreads[ lIndex ].xThreadState, lIndex ); - return pxThreads[ lIndex ].xThreadState; - } - } - assert(0); - return 0; -} -#endif - -void prvSetTaskState( xTaskHandle hTask, portBASE_TYPE state ) -{ -portLONG lIndex; - assert( hTask != NULL ); - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - pxThreads[ lIndex ].xThreadState = state; - return; - } - } - assert(0); - return; -} - - -/*-----------------------------------------------------------*/ -pthread_t prvGetThreadHandle( xTaskHandle hTask ) -{ - pthread_t hThread = ( pthread_t )NULL; - portLONG lIndex; - - assert( hTask != NULL ); - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hTask == hTask ) - { - hThread = pxThreads[ lIndex ].hThread; - break; - } - } - - assert( hThread != (pthread_t) NULL ); - return hThread; -} -/*-----------------------------------------------------------*/ - -portLONG prvGetFreeThreadState( void ) -{ -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )NULL ) - { - break; - } - } - - if ( MAX_NUMBER_OF_TASKS == lIndex ) - { - printf( "No more free threads, please increase the maximum.\n" ); - lIndex = 0; - vPortEndScheduler(); - } - - return lIndex; -} -/*-----------------------------------------------------------*/ - -void prvSetTaskCriticalNesting( pthread_t xThreadId, unsigned portBASE_TYPE uxNesting ) -{ -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - pxThreads[ lIndex ].uxCriticalNesting = uxNesting; - break; - } - } -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE prvGetTaskCriticalNesting( pthread_t xThreadId ) -{ -unsigned portBASE_TYPE uxNesting = 0; -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == xThreadId ) - { - uxNesting = pxThreads[ lIndex ].uxCriticalNesting; - break; - } - } - return uxNesting; -} -/*-----------------------------------------------------------*/ - -void prvDeleteThread( void *xThreadId ) -{ -portLONG lIndex; - - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == ( pthread_t )xThreadId ) - { - pxThreads[ lIndex ].hThread = (pthread_t)NULL; - pxThreads[ lIndex ].hTask = (xTaskHandle)NULL; - if ( pxThreads[ lIndex ].uxCriticalNesting > 0 ) - { - uxCriticalNesting = 0; - vPortEnableInterrupts(); - } - pxThreads[ lIndex ].uxCriticalNesting = 0; - break; - } - } -} -/*-----------------------------------------------------------*/ - -void vPortAddTaskHandle( void *pxTaskHandle ) -{ -portLONG lIndex; - - debug_printf("vPortAddTaskHandle\r\n"); - - pxThreads[ lIndexOfLastAddedTask ].hTask = ( xTaskHandle )pxTaskHandle; - for ( lIndex = 0; lIndex < MAX_NUMBER_OF_TASKS; lIndex++ ) - { - if ( pxThreads[ lIndex ].hThread == pxThreads[ lIndexOfLastAddedTask ].hThread ) - { - if ( pxThreads[ lIndex ].hTask != pxThreads[ lIndexOfLastAddedTask ].hTask ) - { - pxThreads[ lIndex ].hThread = ( pthread_t )NULL; - pxThreads[ lIndex ].hTask = NULL; - pxThreads[ lIndex ].uxCriticalNesting = 0; - } - } - } - usleep(10000); -} -/*-----------------------------------------------------------*/ - -void vPortFindTicksPerSecond( void ) -{ - - /* Needs to be reasonably high for accuracy. */ - unsigned long ulTicksPerSecond = sysconf(_SC_CLK_TCK); - printf( "Timer Resolution for Run TimeStats is %ld ticks per second.\n", ulTicksPerSecond ); -} -/*-----------------------------------------------------------*/ - -unsigned long ulPortGetTimerValue( void ) -{ -struct tms xTimes; - - unsigned long ulTotalTime = times( &xTimes ); - /* Return the application code times. - * The timer only increases when the application code is actually running - * which means that the total execution times should add up to 100%. - */ - return ( unsigned long ) xTimes.tms_utime; - - /* Should check ulTotalTime for being clock_t max minus 1. */ - (void)ulTotalTime; -} -/*-----------------------------------------------------------*/ diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h index 4da6b124b..775c2bac9 100644 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h +++ b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h @@ -142,17 +142,6 @@ extern void vPortAddTaskHandle( void *pxTaskHandle ); /* Posix Signal definitions that can be changed or read as appropriate. */ #define SIG_SUSPEND SIGUSR1 -#define SIG_RESUME SIGUSR2 - -/* Enable the following hash defines to make use of the real-time tick where time progresses at real-time. */ -#define SIG_TICK SIGALRM -#define TIMER_TYPE ITIMER_REAL -/* Enable the following hash defines to make use of the process tick where time progresses only when the process is executing. -#define SIG_TICK SIGVTALRM -#define TIMER_TYPE ITIMER_VIRTUAL */ -/* Enable the following hash defines to make use of the profile tick where time progresses when the process or system calls are executing. -#define SIG_TICK SIGPROF -#define TIMER_TYPE ITIMER_PROF */ /* Make use of times(man 2) to gather run-time statistics on the tasks. */ extern void vPortFindTicksPerSecond( void ); diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/tasks.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks.c similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/corvuscorax/tasks.c rename to flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks.c diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks_linux.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks_linux.c deleted file mode 100644 index 9b06c3f89..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks_linux.c +++ /dev/null @@ -1,2323 +0,0 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#include -#include -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "StackMacros.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* - * Macro to define the amount of stack available to the idle task. - */ -#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE - -/* - * Task control block. A task control block (TCB) is allocated to each task, - * and stores the context of the task. - */ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - - #if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ - #endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - - #if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ - #endif - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; - #endif - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ - #endif - - #if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ - #endif - -} tskTCB; - - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - -/*lint -e956 */ -PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; - -/* Lists for ready and blocked tasks. --------------------*/ - -PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ -PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ - -#if ( INCLUDE_vTaskDelete == 1 ) - - PRIVILEGED_DATA static volatile xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ - PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0; - -#endif - -#if ( INCLUDE_vTaskSuspend == 1 ) - - PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ - -#endif - -/* File private variables. --------------------------------*/ -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0; - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - PRIVILEGED_DATA static char pcStatsString[ 50 ] ; - PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; - -#endif - -/* Debugging and trace facilities private variables and macros. ------------*/ - -/* - * The value used to fill the stack of a task when the task is created. This - * is used purely for checking the high water mark for tasks. - */ -#define tskSTACK_FILL_BYTE ( 0xa5 ) - -/* - * Macros used by vListTask to indicate which state a task is in. - */ -#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) -#define tskREADY_CHAR ( ( signed char ) 'R' ) -#define tskDELETED_CHAR ( ( signed char ) 'D' ) -#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) - -/* - * Macros and private variables used by the trace facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define tskSIZE_OF_EACH_TRACE_LINE ( ( unsigned long ) ( sizeof( unsigned long ) + sizeof( unsigned long ) ) ) - PRIVILEGED_DATA static volatile signed char * volatile pcTraceBuffer; - PRIVILEGED_DATA static signed char *pcTraceBufferStart; - PRIVILEGED_DATA static signed char *pcTraceBufferEnd; - PRIVILEGED_DATA static signed portBASE_TYPE xTracing = pdFALSE; - static unsigned portBASE_TYPE uxPreviousTask = 255; - PRIVILEGED_DATA static char pcStatusString[ 50 ]; - -#endif - -/*-----------------------------------------------------------*/ - -/* - * Macro that writes a trace of scheduler activity to a buffer. This trace - * shows which task is running when and is very useful as a debugging tool. - * As this macro is called each context switch it is a good idea to undefine - * it if not using the facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define vWriteTraceToBuffer() \ - { \ - if( xTracing ) \ - { \ - if( uxPreviousTask != pxCurrentTCB->uxTCBNumber ) \ - { \ - if( ( pcTraceBuffer + tskSIZE_OF_EACH_TRACE_LINE ) < pcTraceBufferEnd ) \ - { \ - uxPreviousTask = pxCurrentTCB->uxTCBNumber; \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) xTickCount; \ - pcTraceBuffer += sizeof( unsigned long ); \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) uxPreviousTask; \ - pcTraceBuffer += sizeof( unsigned long ); \ - } \ - else \ - { \ - xTracing = pdFALSE; \ - } \ - } \ - } \ - } - -#else - - #define vWriteTraceToBuffer() - -#endif -/*-----------------------------------------------------------*/ - -/* - * Place the task represented by pxTCB into the appropriate ready queue for - * the task. It is inserted at the end of the list. One quirk of this is - * that if the task being inserted is at the same priority as the currently - * executing task, then it will only be rescheduled after the currently - * executing task has been rescheduled. - */ -#define prvAddTaskToReadyQueue( pxTCB ) \ -{ \ - if( pxTCB->uxPriority > uxTopReadyPriority ) \ - { \ - uxTopReadyPriority = pxTCB->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ); \ -} -/*-----------------------------------------------------------*/ - -/* - * Macro that looks at the list of tasks that are currently delayed to see if - * any require waking. - * - * Tasks are stored in the queue in the order of their wake time - meaning - * once one tasks has been found whose timer has not expired we need not look - * any further down the list. - */ -#define prvCheckDelayedTasks() \ -{ \ -register tskTCB *pxTCB; \ - \ - while( ( pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ) ) != NULL ) \ - { \ - if( xTickCount < listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ) ) \ - { \ - break; \ - } \ - vListRemove( &( pxTCB->xGenericListItem ) ); \ - /* Is the task waiting on an event also? */ \ - if( pxTCB->xEventListItem.pvContainer ) \ - { \ - vListRemove( &( pxTCB->xEventListItem ) ); \ - } \ - prvAddTaskToReadyQueue( pxTCB ); \ - } \ -} -/*-----------------------------------------------------------*/ - -/* - * Several functions take an xTaskHandle parameter that can optionally be NULL, - * where NULL is used to indicate that the handle of the currently executing - * task should be used in place of the parameter. This macro simply checks to - * see if the parameter is NULL and returns a pointer to the appropriate TCB. - */ -#define prvGetTCBFromHandle( pxHandle ) ( ( pxHandle == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) pxHandle ) - - -/* File private functions. --------------------------------*/ - -/* - * Utility to ready a TCB for a given task. Mainly just copies the parameters - * into the TCB structure. - */ -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first task. - */ -static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; - -/* - * The idle task, which as all tasks is implemented as a never ending loop. - * The idle task is automatically created and added to the ready lists upon - * creation of the first user task. - * - * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); - -/* - * Utility to free all memory allocated by the scheduler to hold a TCB, - * including the stack pointed to by the TCB. - * - * This does not free memory allocated by the task itself (i.e. memory - * allocated by calls to pvPortMalloc from within the tasks application code). - */ -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) - - static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; - -#endif - -/* - * Used only by the idle task. This checks to see if anything has been placed - * in the list of tasks waiting to be deleted. If so the task is cleaned up - * and its TCB deleted. - */ -static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; - -/* - * Allocates memory from the heap for a TCB and associated stack. Checks the - * allocation was successful. - */ -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; - -/* - * Called from vTaskList. vListTasks details all the tasks currently under - * control of the scheduler. The tasks may be in one of a number of lists. - * prvListTaskWithinSingleList accepts a list and details the tasks from - * within just that list. - * - * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM - * NORMAL APPLICATION CODE. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; - -#endif - -/* - * When a task is created, the stack of the task is filled with a known value. - * This function determines the 'high water mark' of the task stack by - * determining how much of the stack remains at the original preset value. - */ -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; - -#endif - - -/*lint +e956 */ - - - -/*----------------------------------------------------------- - * TASK CREATION API documented in task.h - *----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) -{ -signed portBASE_TYPE xReturn; -tskTCB * pxNewTCB; - - /* Allocate the memory required by the TCB and stack for the new task, - checking that the allocation was successful. */ - pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); - - if( pxNewTCB != NULL ) - { - portSTACK_TYPE *pxTopOfStack; - - #if( portUSING_MPU_WRAPPERS == 1 ) - /* Should the task be created in privileged mode? */ - portBASE_TYPE xRunPrivileged; - if( ( uxPriority & portPRIVILEGE_BIT ) != 0x00 ) - { - xRunPrivileged = pdTRUE; - } - else - { - xRunPrivileged = pdFALSE; - } - uxPriority &= ~portPRIVILEGE_BIT; - #endif /* portUSING_MPU_WRAPPERS == 1 */ - - /* Calculate the top of stack address. This depends on whether the - stack grows from high memory to low (as per the 80x86) or visa versa. - portSTACK_GROWTH is used to make the result positive or negative as - required by the port. */ - #if( portSTACK_GROWTH < 0 ) - { - pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( unsigned long ) pxTopOfStack ) & ( ( unsigned long ) ~portBYTE_ALIGNMENT_MASK ) ); - } - #else - { - pxTopOfStack = pxNewTCB->pxStack; - - /* If we want to use stack checking on architectures that use - a positive stack growth direction then we also need to store the - other extreme of the stack space. */ - pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - } - #endif - - /* Setup the newly allocated TCB with the initial state of the task. */ - prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); - - /* Initialize the TCB stack to look as if the task was already running, - but had been interrupted by the scheduler. The return address is set - to the start of the task function. Once the stack has been initialised - the top of stack variable is updated. */ - #if( portUSING_MPU_WRAPPERS == 1 ) - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); - } - #else - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); - } - #endif - - /* We are going to manipulate the task queues to add this task to a - ready list, so must make sure no interrupts occur. */ - portENTER_CRITICAL(); - { - uxCurrentNumberOfTasks++; - if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) - { - /* As this is the first task it must also be the current task. */ - pxCurrentTCB = pxNewTCB; - - /* This is the first task to be created so do the preliminary - initialisation required. We will not recover if this call - fails, but we will report the failure. */ - prvInitialiseTaskLists(); - } - else - { - /* If the scheduler is not already running, make this task the - current task if it is the highest priority task to be created - so far. */ - if( xSchedulerRunning == pdFALSE ) - { - if( pxCurrentTCB->uxPriority <= uxPriority ) - { - pxCurrentTCB = pxNewTCB; - } - } - } - - /* Remember the top priority to make context switching faster. Use - the priority in pxNewTCB as this has been capped to a valid value. */ - if( pxNewTCB->uxPriority > uxTopUsedPriority ) - { - uxTopUsedPriority = pxNewTCB->uxPriority; - } - - #if ( configUSE_TRACE_FACILITY == 1 ) - { - /* Add a counter into the TCB for tracing only. */ - pxNewTCB->uxTCBNumber = uxTaskNumber; - } - #endif - uxTaskNumber++; - - prvAddTaskToReadyQueue( pxNewTCB ); - - xReturn = pdPASS; - traceTASK_CREATE( pxNewTCB ); - } - portEXIT_CRITICAL(); - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - traceTASK_CREATE_FAILED( pxNewTCB ); - } - - if( xReturn == pdPASS ) - { - if( ( void * ) pxCreatedTask != NULL ) - { - /* Pass the TCB out - in an anonymous way. The calling function/ - task can use this as a handle to delete the task later if - required.*/ - *pxCreatedTask = ( xTaskHandle ) pxNewTCB; - } - - if( xSchedulerRunning != pdFALSE ) - { - /* If the created task is of a higher priority than the current task - then it should run now. */ - if( pxCurrentTCB->uxPriority < uxPriority ) - { - portYIELD_WITHIN_API(); - } - } - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - void vTaskDelete( xTaskHandle pxTaskToDelete ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - deleted. */ - if( pxTaskToDelete == pxCurrentTCB ) - { - pxTaskToDelete = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); - - /* Remove task from the ready list and place in the termination list. - This will stop the task from be scheduled. The idle task will check - the termination list and free up any memory allocated by the - scheduler for the TCB and stack. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); - - /* Increment the ucTasksDeleted variable so the idle task knows - there is a task that has been deleted and that it should therefore - check the xTasksWaitingTermination list. */ - ++uxTasksDeleted; - - /* Increment the uxTaskNumberVariable also so kernel aware debuggers - can detect that the task lists need re-generating. */ - uxTaskNumber++; - - traceTASK_DELETE( pxTCB ); - } - portEXIT_CRITICAL(); - - /* Force a reschedule if we have just deleted the current task. */ - if( xSchedulerRunning != pdFALSE ) - { - if( ( void * ) pxTaskToDelete == NULL ) - { - portYIELD_WITHIN_API(); - } - } - } - -#endif - - - - - - -/*----------------------------------------------------------- - * TASK CONTROL API documented in task.h - *----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelayUntil == 1 ) - - void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) - { - portTickType xTimeToWake; - portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; - - vTaskSuspendAll(); - { - /* Generate the tick time at which the task wants to wake. */ - xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; - - if( xTickCount < *pxPreviousWakeTime ) - { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - else - { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - - /* Update the wake time ready for the next call. */ - *pxPreviousWakeTime = xTimeToWake; - - if( xShouldDelay ) - { - traceTASK_DELAY_UNTIL(); - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - } - xAlreadyYielded = xTaskResumeAll(); - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( !xAlreadyYielded ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelay == 1 ) - - void vTaskDelay( portTickType xTicksToDelay ) - { - portTickType xTimeToWake; - signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* A delay time of zero just forces a reschedule. */ - if( xTicksToDelay > ( portTickType ) 0 ) - { - vTaskSuspendAll(); - { - traceTASK_DELAY(); - - /* A task that is removed from the event list while the - scheduler is suspended will not get placed in the ready - list or removed from the blocked list until the scheduler - is resumed. - - This task cannot be in an event list as it is the currently - executing task. */ - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - xAlreadyYielded = xTaskResumeAll(); - } - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( !xAlreadyYielded ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskPriorityGet == 1 ) - - unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxReturn; - - portENTER_CRITICAL(); - { - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - uxReturn = pxTCB->uxPriority; - } - portEXIT_CRITICAL(); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskPrioritySet == 1 ) - - void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxCurrentPriority, xYieldRequired = pdFALSE; - - /* Ensure the new priority is valid. */ - if( uxNewPriority >= configMAX_PRIORITIES ) - { - uxNewPriority = configMAX_PRIORITIES - 1; - } - - portENTER_CRITICAL(); - { - if( pxTask == pxCurrentTCB ) - { - pxTask = NULL; - } - - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - - traceTASK_PRIORITY_SET( pxTask, uxNewPriority ); - - #if ( configUSE_MUTEXES == 1 ) - { - uxCurrentPriority = pxTCB->uxBasePriority; - } - #else - { - uxCurrentPriority = pxTCB->uxPriority; - } - #endif - - if( uxCurrentPriority != uxNewPriority ) - { - /* The priority change may have readied a task of higher - priority than the calling task. */ - if( uxNewPriority > uxCurrentPriority ) - { - if( pxTask != NULL ) - { - /* The priority of another task is being raised. If we - were raising the priority of the currently running task - there would be no need to switch as it must have already - been the highest priority task. */ - xYieldRequired = pdTRUE; - } - } - else if( pxTask == NULL ) - { - /* Setting our own priority down means there may now be another - task of higher priority that is ready to execute. */ - xYieldRequired = pdTRUE; - } - - - - #if ( configUSE_MUTEXES == 1 ) - { - /* Only change the priority being used if the task is not - currently using an inherited priority. */ - if( pxTCB->uxBasePriority == pxTCB->uxPriority ) - { - pxTCB->uxPriority = uxNewPriority; - } - - /* The base priority gets set whatever. */ - pxTCB->uxBasePriority = uxNewPriority; - } - #else - { - pxTCB->uxPriority = uxNewPriority; - } - #endif - - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); - - /* If the task is in the blocked or suspended list we need do - nothing more than change it's priority variable. However, if - the task is in a ready list it needs to be removed and placed - in the queue appropriate to its new priority. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - /* The task is currently in its ready list - remove before adding - it to it's new ready list. As we are in a critical section we - can do this even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - - if( xYieldRequired == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - portEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskSuspend( xTaskHandle pxTaskToSuspend ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - suspended. */ - if( pxTaskToSuspend == pxCurrentTCB ) - { - pxTaskToSuspend = NULL; - } - - /* If null is passed in here then we are suspending ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); - - traceTASK_SUSPEND( pxTCB ); - - /* Remove task from the ready/delayed list and place in the suspended list. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); - } - portEXIT_CRITICAL(); - - /* We may have just suspended the current task. */ - if( ( void * ) pxTaskToSuspend == NULL ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) - { - portBASE_TYPE xReturn = pdFALSE; - const tskTCB * const pxTCB = ( tskTCB * ) xTask; - - /* Is the task we are attempting to resume actually in the - suspended list? */ - if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - /* Has the task already been resumed from within an ISR? */ - if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) - { - /* Is it in the suspended list because it is in the - Suspended state? It is possible to be in the suspended - list because it is blocked on a task with no timeout - specified. */ - if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) - { - xReturn = pdTRUE; - } - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskResume( xTaskHandle pxTaskToResume ) - { - tskTCB *pxTCB; - - /* Remove the task from whichever list it is currently in, and place - it in the ready list. */ - pxTCB = ( tskTCB * ) pxTaskToResume; - - /* The parameter cannot be NULL as it is impossible to resume the - currently executing task. */ - if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) - { - portENTER_CRITICAL(); - { - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME( pxTCB ); - - /* As we are in a critical section we can access the ready - lists even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* We may have just resumed a higher priority task. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* This yield may not cause the task just resumed to run, but - will leave the lists in the correct state for the next yield. */ - portYIELD_WITHIN_API(); - } - } - } - portEXIT_CRITICAL(); - } - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - tskTCB *pxTCB; - - pxTCB = ( tskTCB * ) pxTaskToResume; - - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME_FROM_ISR( pxTCB ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed, at which point a - yield will be performed if necessary. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); - } - } - - return xYieldRequired; - } - -#endif - - - - -/*----------------------------------------------------------- - * PUBLIC SCHEDULER CONTROL documented in task.h - *----------------------------------------------------------*/ - - -void vTaskStartScheduler( void ) -{ -portBASE_TYPE xReturn; - - /* Add the idle task at the lowest priority. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), ( xTaskHandle * ) NULL ); - - if( xReturn == pdPASS ) - { - /* Interrupts are turned off here, to ensure a tick does not occur - before or during the call to xPortStartScheduler(). The stacks of - the created tasks contain a status word with interrupts switched on - so interrupts will automatically get re-enabled when the first task - starts to run. - - STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE - DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ - portDISABLE_INTERRUPTS(); - - xSchedulerRunning = pdTRUE; - xTickCount = ( portTickType ) 0; - - /* If configGENERATE_RUN_TIME_STATS is defined then the following - macro must be defined to configure the timer/counter used to generate - the run time counter time base. */ - portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); - - /* Setting up the timer tick is hardware specific and thus in the - portable interface. */ - if( xPortStartScheduler() ) - { - /* Should not reach here as if the scheduler is running the - function will not return. */ - } - else - { - /* Should only reach here if a task calls xTaskEndScheduler(). */ - } - } -} -/*-----------------------------------------------------------*/ - -void vTaskEndScheduler( void ) -{ - /* Stop the scheduler interrupts and call the portable scheduler end - routine so the original ISRs can be restored if necessary. The port - layer must ensure interrupts enable bit is left in the correct state. */ - portDISABLE_INTERRUPTS(); - xSchedulerRunning = pdFALSE; - vPortEndScheduler(); -} -/*----------------------------------------------------------*/ - -void vTaskSuspendAll( void ) -{ - /* A critical section is not required as the variable is of type - portBASE_TYPE. */ - ++uxSchedulerSuspended; -} -/*----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskResumeAll( void ) -{ -register tskTCB *pxTCB; -signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* It is possible that an ISR caused a task to be removed from an event - list while the scheduler was suspended. If this was the case then the - removed task will have been added to the xPendingReadyList. Once the - scheduler has been resumed it is safe to move all the pending ready - tasks from this list into their appropriate ready list. */ - portENTER_CRITICAL(); - { - --uxSchedulerSuspended; - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0 ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - - /* Move any readied tasks from the pending list into the - appropriate ready list. */ - while( ( pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ) ) != NULL ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* If we have moved a task that has a priority higher than - the current task then we should yield. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - xYieldRequired = pdTRUE; - } - } - - /* If any ticks occurred while the scheduler was suspended then - they should be processed now. This ensures the tick count does not - slip, and that any delayed tasks are resumed at the correct time. */ - if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) - { - while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) - { - vTaskIncrementTick(); - --uxMissedTicks; - } - - /* As we have processed some ticks it is appropriate to yield - to ensure the highest priority task that is ready to run is - the task actually running. */ - #if configUSE_PREEMPTION == 1 - { - xYieldRequired = pdTRUE; - } - #endif - } - - if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) - { - xAlreadyYielded = pdTRUE; - xMissedYield = pdFALSE; - portYIELD_WITHIN_API(); - } - } - } - } - portEXIT_CRITICAL(); - - return xAlreadyYielded; -} - - - - - - -/*----------------------------------------------------------- - * PUBLIC TASK UTILITIES documented in task.h - *----------------------------------------------------------*/ - - - -portTickType xTaskGetTickCount( void ) -{ -portTickType xTicks; - - /* Critical section required if running on a 16 bit processor. */ - portENTER_CRITICAL(); - { - xTicks = xTickCount; - } - portEXIT_CRITICAL(); - - return xTicks; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) -{ - /* A critical section is not required because the variables are of type - portBASE_TYPE. */ - return uxCurrentNumberOfTasks; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskList( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB and - report the task name, state and stack high water mark. */ - - pcWriteBuffer[ 0 ] = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + 1; - - do - { - uxQueue--; - - if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); - } - - if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); - } - - #if( INCLUDE_vTaskDelete == 1 ) - { - if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, tskDELETED_CHAR ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, tskSUSPENDED_CHAR ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - unsigned long ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB, - generating a table of run timer percentages in the provided - buffer. */ - - pcWriteBuffer[ 0 ] = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + 1; - - do - { - uxQueue--; - - if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); - } - - if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); - } - - #if ( INCLUDE_vTaskDelete == 1 ) - { - if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, ulTotalRunTime ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, ulTotalRunTime ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) - { - portENTER_CRITICAL(); - { - pcTraceBuffer = ( signed char * )pcBuffer; - pcTraceBufferStart = pcBuffer; - pcTraceBufferEnd = pcBuffer + ( ulBufferSize - tskSIZE_OF_EACH_TRACE_LINE ); - xTracing = pdTRUE; - } - portEXIT_CRITICAL(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned long ulTaskEndTrace( void ) - { - unsigned long ulBufferLength; - - portENTER_CRITICAL(); - xTracing = pdFALSE; - portEXIT_CRITICAL(); - - ulBufferLength = ( unsigned long ) ( pcTraceBuffer - pcTraceBufferStart ); - - return ulBufferLength; - } - -#endif - - - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - * documented in task.h - *----------------------------------------------------------*/ - - -void vTaskIncrementTick( void ) -{ - /* Called by the portable layer each time a tick interrupt occurs. - Increments the tick then checks to see if the new tick value will cause any - tasks to be unblocked. */ - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - ++xTickCount; - if( xTickCount == ( portTickType ) 0 ) - { - xList *pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. - If there are any items in pxDelayedTaskList here then there is - an error! */ - pxTemp = pxDelayedTaskList; - pxDelayedTaskList = pxOverflowDelayedTaskList; - pxOverflowDelayedTaskList = pxTemp; - xNumOfOverflows++; - } - - /* See if this tick has made a timeout expire. */ - prvCheckDelayedTasks(); - } - else - { - ++uxMissedTicks; - - /* The tick hook gets called at regular intervals, even if the - scheduler is locked. */ - #if ( configUSE_TICK_HOOK == 1 ) - { - extern void vApplicationTickHook( void ); - - vApplicationTickHook(); - } - #endif - } - - #if ( configUSE_TICK_HOOK == 1 ) - { - extern void vApplicationTickHook( void ); - - /* Guard against the tick hook being called when the missed tick - count is being unwound (when the scheduler is being unlocked. */ - if( uxMissedTicks == 0 ) - { - vApplicationTickHook(); - } - } - #endif - - traceTASK_INCREMENT_TICK( xTickCount ); -} -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_vTaskCleanUpResources == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - void vTaskCleanUpResources( void ) - { - unsigned short usQueue; - volatile tskTCB *pxTCB; - - usQueue = ( unsigned short ) uxTopUsedPriority + ( unsigned short ) 1; - - /* Remove any TCB's from the ready queues. */ - do - { - usQueue--; - - while( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ usQueue ] ) ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &( pxReadyTasksLists[ usQueue ] ) ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - }while( usQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - /* Remove any TCB's from the delayed queue. */ - while( !listLIST_IS_EMPTY( &xDelayedTaskList1 ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList1 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - /* Remove any TCB's from the overflow delayed queue. */ - while( !listLIST_IS_EMPTY( &xDelayedTaskList2 ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList2 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - while( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xSuspendedTaskList ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxTagValue ) - { - tskTCB *xTCB; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - portENTER_CRITICAL(); - xTCB->pxTaskTag = pxTagValue; - portEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) - { - tskTCB *xTCB; - pdTASK_HOOK_CODE xReturn; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - portENTER_CRITICAL(); - xReturn = xTCB->pxTaskTag; - portEXIT_CRITICAL(); - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) - { - tskTCB *xTCB; - portBASE_TYPE xReturn; - - /* If xTask is NULL then we are calling our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - if( xTCB->pxTaskTag != NULL ) - { - xReturn = xTCB->pxTaskTag( pvParameter ); - } - else - { - xReturn = pdFAIL; - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -void vTaskSwitchContext( void ) -{ - if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) - { - /* The scheduler is currently suspended - do not allow a context - switch. */ - xMissedYield = pdTRUE; - return; - } - - traceTASK_SWITCHED_OUT(); - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - unsigned long ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); - - /* Add the amount of time the task has been running to the accumulated - time so far. The time the task started running was stored in - ulTaskSwitchedInTime. Note that there is no overflow protection here - so count values are only valid until the timer overflows. Generally - this will be about 1 hour assuming a 1uS timer increment. */ - pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); - ulTaskSwitchedInTime = ulTempCounter; - } - #endif - - taskFIRST_CHECK_FOR_STACK_OVERFLOW(); - taskSECOND_CHECK_FOR_STACK_OVERFLOW(); - - /* Find the highest priority queue that contains ready tasks. */ - while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) - { - --uxTopReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the - same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); - - traceTASK_SWITCHED_IN(); - vWriteTraceToBuffer(); -} -/*-----------------------------------------------------------*/ - -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) -{ -portTickType xTimeToWake; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. */ - - /* Place the event list item of the TCB in the appropriate event list. - This is placed in the list in priority order so the highest priority task - is the first to be woken by the event. */ - vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove ourselves from the ready list before adding ourselves - to the blocked list as the same list item is used for both lists. We have - exclusive access to the ready lists as the scheduler is locked. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( xTicksToWait == portMAX_DELAY ) - { - /* Add ourselves to the suspended task list instead of a delayed task - list to ensure we are not woken by a timing event. We will block - indefinitely. */ - vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - } - #else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - #endif -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) -{ -tskTCB *pxUnblockedTCB; -portBASE_TYPE xReturn; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. It can also be called from within an ISR. */ - - /* The event list is sorted in priority order, so we can remove the - first in the list, remove the TCB from the delayed list, and add - it to the ready list. - - If an event is for a queue that is locked then this function will never - get called - the lock count on the queue will get modified instead. This - means we can always expect exclusive access to the event list here. */ - pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - vListRemove( &( pxUnblockedTCB->xEventListItem ) ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxUnblockedTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); - } - - if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* Return true if the task removed from the event list has - a higher priority than the calling task. This allows - the calling task to know if it should force a context - switch now. */ - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) -{ - pxTimeOut->xOverflowCount = xNumOfOverflows; - pxTimeOut->xTimeOnEntering = xTickCount; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) -{ -portBASE_TYPE xReturn; - - portENTER_CRITICAL(); - { - #if ( INCLUDE_vTaskSuspend == 1 ) - /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is - the maximum block time then the task should block indefinitely, and - therefore never time out. */ - if( *pxTicksToWait == portMAX_DELAY ) - { - xReturn = pdFALSE; - } - else /* We are not blocking indefinitely, perform the checks below. */ - #endif - - if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) - { - /* The tick count is greater than the time at which vTaskSetTimeout() - was called, but has also overflowed since vTaskSetTimeOut() was called. - It must have wrapped all the way around and gone past us again. This - passed since vTaskSetTimeout() was called. */ - xReturn = pdTRUE; - } - else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) - { - /* Not a genuine timeout. Adjust parameters for time remaining. */ - *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); - vTaskSetTimeOutState( pxTimeOut ); - xReturn = pdFALSE; - } - else - { - xReturn = pdTRUE; - } - } - portEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskMissedYield( void ) -{ - xMissedYield = pdTRUE; -} - -/* - * ----------------------------------------------------------- - * The Idle task. - * ---------------------------------------------------------- - * - * The portTASK_FUNCTION() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION( prvIdleTask, pvParameters ) -{ - /* Stop warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* See if any tasks have been deleted. */ - prvCheckTasksWaitingTermination(); - - #if ( configUSE_PREEMPTION == 0 ) - { - /* If we are not using preemption we keep forcing a task switch to - see if any other task has become available. If we are using - preemption we don't need to do this as any task becoming available - will automatically get the processor anyway. */ - taskYIELD(); - } - #endif - - #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) - { - /* When using preemption tasks of equal priority will be - timesliced. If a task that is sharing the idle priority is ready - to run then the idle task should yield before the end of the - timeslice. - - A critical region is not required here as we are just reading from - the list, and an occasional incorrect value will not matter. If - the ready list at the idle priority contains more than one task - then a task other than the idle task is ready to execute. */ - if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) - { - taskYIELD(); - } - } - #endif - - #if ( configUSE_IDLE_HOOK == 1 ) - { - extern void vApplicationIdleHook( void ); - - /* Call the user defined function from within the idle task. This - allows the application designer to add background functionality - without the overhead of a separate task. - NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, - CALL A FUNCTION THAT MIGHT BLOCK. */ - vApplicationIdleHook(); - } - #endif - // call nanosleep for smalles sleep time possible - // (depending on kernel settings - around 100 microseconds) - // decreases idle thread CPU load from 100 to practically 0 - struct timespec x; - x.tv_sec=1; - x.tv_nsec=0; - nanosleep(&x,NULL); - } -} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ - - - - - - - -/*----------------------------------------------------------- - * File private functions documented at the top of the file. - *----------------------------------------------------------*/ - - - -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) -{ - /* Store the function name in the TCB. */ - #if configMAX_TASK_NAME_LEN > 1 - { - /* Don't bring strncpy into the build unnecessarily. */ - strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); - } - #endif - pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = '\0'; - - /* This is used as an array index so must ensure it's not too large. First - remove the privilege bit if one is present. */ - if( uxPriority >= configMAX_PRIORITIES ) - { - uxPriority = configMAX_PRIORITIES - 1; - } - - pxTCB->uxPriority = uxPriority; - #if ( configUSE_MUTEXES == 1 ) - { - pxTCB->uxBasePriority = uxPriority; - } - #endif - - vListInitialiseItem( &( pxTCB->xGenericListItem ) ); - vListInitialiseItem( &( pxTCB->xEventListItem ) ); - - /* Set the pxTCB as a link back from the xListItem. This is so we can get - back to the containing TCB from a generic item in a list. */ - listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - { - pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0; - } - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - { - pxTCB->pxTaskTag = NULL; - } - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - pxTCB->ulRunTimeCounter = 0UL; - } - #endif - - #if ( portUSING_MPU_WRAPPERS == 1 ) - { - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); - } - #else - { - ( void ) xRegions; - ( void ) usStackDepth; - } - #endif -} -/*-----------------------------------------------------------*/ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - - void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) - { - tskTCB *pxTCB; - - if( xTaskToModify == pxCurrentTCB ) - { - xTaskToModify = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( xTaskToModify ); - - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); - } - /*-----------------------------------------------------------*/ -#endif - -static void prvInitialiseTaskLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = 0; uxPriority < configMAX_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedTaskList1 ); - vListInitialise( ( xList * ) &xDelayedTaskList2 ); - vListInitialise( ( xList * ) &xPendingReadyList ); - - #if ( INCLUDE_vTaskDelete == 1 ) - { - vListInitialise( ( xList * ) &xTasksWaitingTermination ); - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - vListInitialise( ( xList * ) &xSuspendedTaskList ); - } - #endif - - /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList - using list2. */ - pxDelayedTaskList = &xDelayedTaskList1; - pxOverflowDelayedTaskList = &xDelayedTaskList2; -} -/*-----------------------------------------------------------*/ - -static void prvCheckTasksWaitingTermination( void ) -{ - #if ( INCLUDE_vTaskDelete == 1 ) - { - portBASE_TYPE xListIsEmpty; - - /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called - too often in the idle task. */ - if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0 ) - { - vTaskSuspendAll(); - xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); - xTaskResumeAll(); - - if( !xListIsEmpty ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - --uxCurrentNumberOfTasks; - --uxTasksDeleted; - } - portEXIT_CRITICAL(); - - prvDeleteTCB( pxTCB ); - } - } - } - #endif -} -/*-----------------------------------------------------------*/ - -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) -{ -tskTCB *pxNewTCB; - - /* Allocate space for the TCB. Where the memory comes from depends on - the implementation of the port malloc function. */ - pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); - - if( pxNewTCB != NULL ) - { - /* Allocate space for the stack used by the task being created. - The base of the stack memory stored in the TCB so the task can - be deleted later if required. */ - pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); - - if( pxNewTCB->pxStack == NULL ) - { - /* Could not allocate the stack. Delete the allocated TCB. */ - vPortFree( pxNewTCB ); - pxNewTCB = NULL; - } - else - { - /* Just to help debugging. */ - memset( pxNewTCB->pxStack, tskSTACK_FILL_BYTE, usStackDepth * sizeof( portSTACK_TYPE ) ); - } - } - - return pxNewTCB; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned short usStackRemaining; - - /* Write the details of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - #if ( portSTACK_GROWTH > 0 ) - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); - } - #else - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); - } - #endif - - sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned long ulStatsAsPercentage; - - /* Write the run time stats of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - /* Get next TCB in from the list. */ - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - - /* Divide by zero check. */ - if( ulTotalRunTime > 0UL ) - { - /* Has the task run at all? */ - if( pxNextTCB->ulRunTimeCounter == 0 ) - { - /* The task has used no CPU time at all. */ - sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); - } - else - { - /* What percentage of the total run time as the task used? - This will always be rounded down to the nearest integer. */ - ulStatsAsPercentage = ( 100UL * pxNextTCB->ulRunTimeCounter ) / ulTotalRunTime; - - if( ulStatsAsPercentage > 0UL ) - { - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); - } - else - { - /* If the percentage is zero here then the task has - consumed less than 1% of the total run time. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); - } - } - - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); - } - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) - { - register unsigned short usCount = 0; - - while( *pucStackByte == tskSTACK_FILL_BYTE ) - { - pucStackByte -= portSTACK_GROWTH; - usCount++; - } - - usCount /= sizeof( portSTACK_TYPE ); - - return usCount; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) - - unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) - { - tskTCB *pxTCB; - unsigned char *pcEndOfStack; - unsigned portBASE_TYPE uxReturn; - - pxTCB = prvGetTCBFromHandle( xTask ); - - #if portSTACK_GROWTH < 0 - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; - } - #else - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; - } - #endif - - uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) - - static void prvDeleteTCB( tskTCB *pxTCB ) - { - /* Free up the memory allocated by the scheduler for the task. It is up to - the task to free any memory allocated at the application level. */ - vPortFreeAligned( pxTCB->pxStack ); - vPortFree( pxTCB ); - } - -#endif - - -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) - - xTaskHandle xTaskGetCurrentTaskHandle( void ) - { - xTaskHandle xReturn; - - /* A critical section is not required as this is not called from - an interrupt and the current TCB will always be the same for any - individual execution thread. */ - xReturn = pxCurrentTCB; - - return xReturn; - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetSchedulerState == 1 ) - - portBASE_TYPE xTaskGetSchedulerState( void ) - { - portBASE_TYPE xReturn; - - if( xSchedulerRunning == pdFALSE ) - { - xReturn = taskSCHEDULER_NOT_STARTED; - } - else - { - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xReturn = taskSCHEDULER_RUNNING; - } - else - { - xReturn = taskSCHEDULER_SUSPENDED; - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) - { - /* Adjust the mutex holder state to account for its new priority. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); - - /* If the task being modified is in the ready state it will need to - be moved in to a new list. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Inherit the priority before being moved into the new list. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* Just inherit the priority. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxMutexHolder != NULL ) - { - if( pxTCB->uxPriority != pxTCB->uxBasePriority ) - { - /* We must be the running task to be able to give the mutex back. - Remove ourselves from the ready list we currently appear in. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Disinherit the priority before adding ourselves into the new - ready list. */ - pxTCB->uxPriority = pxTCB->uxBasePriority; - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); - prvAddTaskToReadyQueue( pxTCB ); - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - - void vTaskEnterCritical( void ) - { - portDISABLE_INTERRUPTS(); - - if( xSchedulerRunning != pdFALSE ) - { - pxCurrentTCB->uxCriticalNesting++; - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - -void vTaskExitCritical( void ) -{ - if( xSchedulerRunning != pdFALSE ) - { - if( pxCurrentTCB->uxCriticalNesting > 0 ) - { - pxCurrentTCB->uxCriticalNesting--; - - if( pxCurrentTCB->uxCriticalNesting == 0 ) - { - portENABLE_INTERRUPTS(); - } - } - } -} - -#endif -/*-----------------------------------------------------------*/ - - - - diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks_posix.c b/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks_posix.c deleted file mode 100644 index f9fb0dcc0..000000000 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks_posix.c +++ /dev/null @@ -1,2333 +0,0 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#include -#include -#include -#include -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "StackMacros.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* - * Macro to define the amount of stack available to the idle task. - */ -#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE - -/* - * Task control block. A task control block (TCB) is allocated to each task, - * and stores the context of the task. - */ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - - #if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ - #endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - - #if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ - #endif - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; - #endif - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ - #endif - - #if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ - #endif - -} tskTCB; - - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - -/*lint -e956 */ -PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; - -/* Lists for ready and blocked tasks. --------------------*/ - -PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ -PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ - -#if ( INCLUDE_vTaskDelete == 1 ) - - PRIVILEGED_DATA static volatile xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ - PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0; - -#endif - -#if ( INCLUDE_vTaskSuspend == 1 ) - - PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ - -#endif - -/* File private variables. --------------------------------*/ -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0; - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - PRIVILEGED_DATA static char pcStatsString[ 50 ] ; - PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; - -#endif - -/* Debugging and trace facilities private variables and macros. ------------*/ - -/* - * The value used to fill the stack of a task when the task is created. This - * is used purely for checking the high water mark for tasks. - */ -#define tskSTACK_FILL_BYTE ( 0xa5 ) - -/* - * Macros used by vListTask to indicate which state a task is in. - */ -#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) -#define tskREADY_CHAR ( ( signed char ) 'R' ) -#define tskDELETED_CHAR ( ( signed char ) 'D' ) -#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) - -/* - * Macros and private variables used by the trace facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define tskSIZE_OF_EACH_TRACE_LINE ( ( unsigned long ) ( sizeof( unsigned long ) + sizeof( unsigned long ) ) ) - PRIVILEGED_DATA static volatile signed char * volatile pcTraceBuffer; - PRIVILEGED_DATA static signed char *pcTraceBufferStart; - PRIVILEGED_DATA static signed char *pcTraceBufferEnd; - PRIVILEGED_DATA static signed portBASE_TYPE xTracing = pdFALSE; - static unsigned portBASE_TYPE uxPreviousTask = 255; - PRIVILEGED_DATA static char pcStatusString[ 50 ]; - -#endif - -/*-----------------------------------------------------------*/ - -/* - * Macro that writes a trace of scheduler activity to a buffer. This trace - * shows which task is running when and is very useful as a debugging tool. - * As this macro is called each context switch it is a good idea to undefine - * it if not using the facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define vWriteTraceToBuffer() \ - { \ - if( xTracing ) \ - { \ - if( uxPreviousTask != pxCurrentTCB->uxTCBNumber ) \ - { \ - if( ( pcTraceBuffer + tskSIZE_OF_EACH_TRACE_LINE ) < pcTraceBufferEnd ) \ - { \ - uxPreviousTask = pxCurrentTCB->uxTCBNumber; \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) xTickCount; \ - pcTraceBuffer += sizeof( unsigned long ); \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) uxPreviousTask; \ - pcTraceBuffer += sizeof( unsigned long ); \ - } \ - else \ - { \ - xTracing = pdFALSE; \ - } \ - } \ - } \ - } - -#else - - #define vWriteTraceToBuffer() - -#endif -/*-----------------------------------------------------------*/ - -/* - * Place the task represented by pxTCB into the appropriate ready queue for - * the task. It is inserted at the end of the list. One quirk of this is - * that if the task being inserted is at the same priority as the currently - * executing task, then it will only be rescheduled after the currently - * executing task has been rescheduled. - */ -#define prvAddTaskToReadyQueue( pxTCB ) \ -{ \ - if( pxTCB->uxPriority > uxTopReadyPriority ) \ - { \ - uxTopReadyPriority = pxTCB->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ); \ -} -/*-----------------------------------------------------------*/ - -/* - * Macro that looks at the list of tasks that are currently delayed to see if - * any require waking. - * - * Tasks are stored in the queue in the order of their wake time - meaning - * once one tasks has been found whose timer has not expired we need not look - * any further down the list. - */ -#define prvCheckDelayedTasks() \ -{ \ -register tskTCB *pxTCB; \ - \ - while( ( pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ) ) != NULL ) \ - { \ - if( xTickCount < listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ) ) \ - { \ - break; \ - } \ - vListRemove( &( pxTCB->xGenericListItem ) ); \ - /* Is the task waiting on an event also? */ \ - if( pxTCB->xEventListItem.pvContainer ) \ - { \ - vListRemove( &( pxTCB->xEventListItem ) ); \ - } \ - prvAddTaskToReadyQueue( pxTCB ); \ - } \ -} -/*-----------------------------------------------------------*/ - -/* - * Several functions take an xTaskHandle parameter that can optionally be NULL, - * where NULL is used to indicate that the handle of the currently executing - * task should be used in place of the parameter. This macro simply checks to - * see if the parameter is NULL and returns a pointer to the appropriate TCB. - */ -#define prvGetTCBFromHandle( pxHandle ) ( ( pxHandle == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) pxHandle ) - - -/* File private functions. --------------------------------*/ - -/* - * Utility to ready a TCB for a given task. Mainly just copies the parameters - * into the TCB structure. - */ -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first task. - */ -static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; - -/* - * The idle task, which as all tasks is implemented as a never ending loop. - * The idle task is automatically created and added to the ready lists upon - * creation of the first user task. - * - * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); - -/* - * Utility to free all memory allocated by the scheduler to hold a TCB, - * including the stack pointed to by the TCB. - * - * This does not free memory allocated by the task itself (i.e. memory - * allocated by calls to pvPortMalloc from within the tasks application code). - */ -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) - - static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; - -#endif - -/* - * Used only by the idle task. This checks to see if anything has been placed - * in the list of tasks waiting to be deleted. If so the task is cleaned up - * and its TCB deleted. - */ -static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; - -/* - * Allocates memory from the heap for a TCB and associated stack. Checks the - * allocation was successful. - */ -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; - -/* - * Called from vTaskList. vListTasks details all the tasks currently under - * control of the scheduler. The tasks may be in one of a number of lists. - * prvListTaskWithinSingleList accepts a list and details the tasks from - * within just that list. - * - * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM - * NORMAL APPLICATION CODE. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; - -#endif - -/* - * When a task is created, the stack of the task is filled with a known value. - * This function determines the 'high water mark' of the task stack by - * determining how much of the stack remains at the original preset value. - */ -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; - -#endif - - -/*lint +e956 */ - - - -/*----------------------------------------------------------- - * TASK CREATION API documented in task.h - *----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) -{ -signed portBASE_TYPE xReturn; -tskTCB * pxNewTCB; - - /* Allocate the memory required by the TCB and stack for the new task, - checking that the allocation was successful. */ - pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); - - if( pxNewTCB != NULL ) - { - portSTACK_TYPE *pxTopOfStack; - - #if( portUSING_MPU_WRAPPERS == 1 ) - /* Should the task be created in privileged mode? */ - portBASE_TYPE xRunPrivileged; - if( ( uxPriority & portPRIVILEGE_BIT ) != 0x00 ) - { - xRunPrivileged = pdTRUE; - } - else - { - xRunPrivileged = pdFALSE; - } - uxPriority &= ~portPRIVILEGE_BIT; - #endif /* portUSING_MPU_WRAPPERS == 1 */ - - /* Calculate the top of stack address. This depends on whether the - stack grows from high memory to low (as per the 80x86) or visa versa. - portSTACK_GROWTH is used to make the result positive or negative as - required by the port. */ - #if( portSTACK_GROWTH < 0 ) - { - pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( unsigned long ) pxTopOfStack ) & ( ( unsigned long ) ~portBYTE_ALIGNMENT_MASK ) ); - } - #else - { - pxTopOfStack = pxNewTCB->pxStack; - - /* If we want to use stack checking on architectures that use - a positive stack growth direction then we also need to store the - other extreme of the stack space. */ - pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - } - #endif - - /* Setup the newly allocated TCB with the initial state of the task. */ - prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); - - /* Initialize the TCB stack to look as if the task was already running, - but had been interrupted by the scheduler. The return address is set - to the start of the task function. Once the stack has been initialised - the top of stack variable is updated. */ - #if( portUSING_MPU_WRAPPERS == 1 ) - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); - } - #else - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); - } - #endif - - /* We are going to manipulate the task queues to add this task to a - ready list, so must make sure no interrupts occur. */ - portENTER_CRITICAL(); - { - uxCurrentNumberOfTasks++; - if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) - { - /* As this is the first task it must also be the current task. */ - pxCurrentTCB = pxNewTCB; - - /* This is the first task to be created so do the preliminary - initialisation required. We will not recover if this call - fails, but we will report the failure. */ - prvInitialiseTaskLists(); - } - else - { - /* If the scheduler is not already running, make this task the - current task if it is the highest priority task to be created - so far. */ - if( xSchedulerRunning == pdFALSE ) - { - if( pxCurrentTCB->uxPriority <= uxPriority ) - { - pxCurrentTCB = pxNewTCB; - } - } - } - - /* Remember the top priority to make context switching faster. Use - the priority in pxNewTCB as this has been capped to a valid value. */ - if( pxNewTCB->uxPriority > uxTopUsedPriority ) - { - uxTopUsedPriority = pxNewTCB->uxPriority; - } - - #if ( configUSE_TRACE_FACILITY == 1 ) - { - /* Add a counter into the TCB for tracing only. */ - pxNewTCB->uxTCBNumber = uxTaskNumber; - } - #endif - uxTaskNumber++; - - prvAddTaskToReadyQueue( pxNewTCB ); - - xReturn = pdPASS; - traceTASK_CREATE( pxNewTCB ); - } - portEXIT_CRITICAL(); - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - traceTASK_CREATE_FAILED( pxNewTCB ); - } - - if( xReturn == pdPASS ) - { - if( ( void * ) pxCreatedTask != NULL ) - { - /* Pass the TCB out - in an anonymous way. The calling function/ - task can use this as a handle to delete the task later if - required.*/ - *pxCreatedTask = ( xTaskHandle ) pxNewTCB; - } - - if( xSchedulerRunning != pdFALSE ) - { - /* If the created task is of a higher priority than the current task - then it should run now. */ - if( pxCurrentTCB->uxPriority < uxPriority ) - { - portYIELD_WITHIN_API(); - } - } - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - void vTaskDelete( xTaskHandle pxTaskToDelete ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - deleted. */ - if( pxTaskToDelete == pxCurrentTCB ) - { - pxTaskToDelete = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); - - /* Remove task from the ready list and place in the termination list. - This will stop the task from be scheduled. The idle task will check - the termination list and free up any memory allocated by the - scheduler for the TCB and stack. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); - - /* Increment the ucTasksDeleted variable so the idle task knows - there is a task that has been deleted and that it should therefore - check the xTasksWaitingTermination list. */ - ++uxTasksDeleted; - - /* Increment the uxTaskNumberVariable also so kernel aware debuggers - can detect that the task lists need re-generating. */ - uxTaskNumber++; - - traceTASK_DELETE( pxTCB ); - } - portEXIT_CRITICAL(); - - /* Force a reschedule if we have just deleted the current task. */ - if( xSchedulerRunning != pdFALSE ) - { - if( ( void * ) pxTaskToDelete == NULL ) - { - portYIELD_WITHIN_API(); - } - } - } - -#endif - - - - - - -/*----------------------------------------------------------- - * TASK CONTROL API documented in task.h - *----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelayUntil == 1 ) - - void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) - { - portTickType xTimeToWake; - portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; - - vTaskSuspendAll(); - { - /* Generate the tick time at which the task wants to wake. */ - xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; - - if( xTickCount < *pxPreviousWakeTime ) - { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - else - { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - - /* Update the wake time ready for the next call. */ - *pxPreviousWakeTime = xTimeToWake; - - if( xShouldDelay ) - { - traceTASK_DELAY_UNTIL(); - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - } - xAlreadyYielded = xTaskResumeAll(); - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( !xAlreadyYielded ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelay == 1 ) - - void vTaskDelay( portTickType xTicksToDelay ) - { - portTickType xTimeToWake; - signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* A delay time of zero just forces a reschedule. */ - if( xTicksToDelay > ( portTickType ) 0 ) - { - vTaskSuspendAll(); - { - traceTASK_DELAY(); - - /* A task that is removed from the event list while the - scheduler is suspended will not get placed in the ready - list or removed from the blocked list until the scheduler - is resumed. - - This task cannot be in an event list as it is the currently - executing task. */ - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - xAlreadyYielded = xTaskResumeAll(); - } - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( !xAlreadyYielded ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskPriorityGet == 1 ) - - unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxReturn; - - portENTER_CRITICAL(); - { - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - uxReturn = pxTCB->uxPriority; - } - portEXIT_CRITICAL(); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskPrioritySet == 1 ) - - void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxCurrentPriority, xYieldRequired = pdFALSE; - - /* Ensure the new priority is valid. */ - if( uxNewPriority >= configMAX_PRIORITIES ) - { - uxNewPriority = configMAX_PRIORITIES - 1; - } - - portENTER_CRITICAL(); - { - if( pxTask == pxCurrentTCB ) - { - pxTask = NULL; - } - - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - - traceTASK_PRIORITY_SET( pxTask, uxNewPriority ); - - #if ( configUSE_MUTEXES == 1 ) - { - uxCurrentPriority = pxTCB->uxBasePriority; - } - #else - { - uxCurrentPriority = pxTCB->uxPriority; - } - #endif - - if( uxCurrentPriority != uxNewPriority ) - { - /* The priority change may have readied a task of higher - priority than the calling task. */ - if( uxNewPriority > uxCurrentPriority ) - { - if( pxTask != NULL ) - { - /* The priority of another task is being raised. If we - were raising the priority of the currently running task - there would be no need to switch as it must have already - been the highest priority task. */ - xYieldRequired = pdTRUE; - } - } - else if( pxTask == NULL ) - { - /* Setting our own priority down means there may now be another - task of higher priority that is ready to execute. */ - xYieldRequired = pdTRUE; - } - - - - #if ( configUSE_MUTEXES == 1 ) - { - /* Only change the priority being used if the task is not - currently using an inherited priority. */ - if( pxTCB->uxBasePriority == pxTCB->uxPriority ) - { - pxTCB->uxPriority = uxNewPriority; - } - - /* The base priority gets set whatever. */ - pxTCB->uxBasePriority = uxNewPriority; - } - #else - { - pxTCB->uxPriority = uxNewPriority; - } - #endif - - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); - - /* If the task is in the blocked or suspended list we need do - nothing more than change it's priority variable. However, if - the task is in a ready list it needs to be removed and placed - in the queue appropriate to its new priority. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - /* The task is currently in its ready list - remove before adding - it to it's new ready list. As we are in a critical section we - can do this even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - - if( xYieldRequired == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - portEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskSuspend( xTaskHandle pxTaskToSuspend ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - suspended. */ - if( pxTaskToSuspend == pxCurrentTCB ) - { - pxTaskToSuspend = NULL; - } - - /* If null is passed in here then we are suspending ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); - - traceTASK_SUSPEND( pxTCB ); - - /* Remove task from the ready/delayed list and place in the suspended list. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); - } - portEXIT_CRITICAL(); - - /* We may have just suspended the current task. */ - if( ( void * ) pxTaskToSuspend == NULL ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) - { - portBASE_TYPE xReturn = pdFALSE; - const tskTCB * const pxTCB = ( tskTCB * ) xTask; - - /* Is the task we are attempting to resume actually in the - suspended list? */ - if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - /* Has the task already been resumed from within an ISR? */ - if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) - { - /* Is it in the suspended list because it is in the - Suspended state? It is possible to be in the suspended - list because it is blocked on a task with no timeout - specified. */ - if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) - { - xReturn = pdTRUE; - } - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskResume( xTaskHandle pxTaskToResume ) - { - tskTCB *pxTCB; - - /* Remove the task from whichever list it is currently in, and place - it in the ready list. */ - pxTCB = ( tskTCB * ) pxTaskToResume; - - /* The parameter cannot be NULL as it is impossible to resume the - currently executing task. */ - if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) - { - portENTER_CRITICAL(); - { - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME( pxTCB ); - - /* As we are in a critical section we can access the ready - lists even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* We may have just resumed a higher priority task. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* This yield may not cause the task just resumed to run, but - will leave the lists in the correct state for the next yield. */ - portYIELD_WITHIN_API(); - } - } - } - portEXIT_CRITICAL(); - } - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - tskTCB *pxTCB; - - pxTCB = ( tskTCB * ) pxTaskToResume; - - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME_FROM_ISR( pxTCB ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed, at which point a - yield will be performed if necessary. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); - } - } - - return xYieldRequired; - } - -#endif - - - - -/*----------------------------------------------------------- - * PUBLIC SCHEDULER CONTROL documented in task.h - *----------------------------------------------------------*/ - - -void vTaskStartScheduler( void ) -{ -portBASE_TYPE xReturn; - - /* Add the idle task at the lowest priority. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), ( xTaskHandle * ) NULL ); - - if( xReturn == pdPASS ) - { - /* Interrupts are turned off here, to ensure a tick does not occur - before or during the call to xPortStartScheduler(). The stacks of - the created tasks contain a status word with interrupts switched on - so interrupts will automatically get re-enabled when the first task - starts to run. - - STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE - DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ - portDISABLE_INTERRUPTS(); - - xSchedulerRunning = pdTRUE; - xTickCount = ( portTickType ) 0; - - /* If configGENERATE_RUN_TIME_STATS is defined then the following - macro must be defined to configure the timer/counter used to generate - the run time counter time base. */ - portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); - - /* Setting up the timer tick is hardware specific and thus in the - portable interface. */ - if( xPortStartScheduler() ) - { - /* Should not reach here as if the scheduler is running the - function will not return. */ - } - else - { - /* Should only reach here if a task calls xTaskEndScheduler(). */ - } - } -} -/*-----------------------------------------------------------*/ - -void vTaskEndScheduler( void ) -{ - /* Stop the scheduler interrupts and call the portable scheduler end - routine so the original ISRs can be restored if necessary. The port - layer must ensure interrupts enable bit is left in the correct state. */ - portDISABLE_INTERRUPTS(); - xSchedulerRunning = pdFALSE; - vPortEndScheduler(); -} -/*----------------------------------------------------------*/ - -void vTaskSuspendAll( void ) -{ - /* A critical section is not required as the variable is of type - portBASE_TYPE. */ - ++uxSchedulerSuspended; -} -/*----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskResumeAll( void ) -{ -register tskTCB *pxTCB; -signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* It is possible that an ISR caused a task to be removed from an event - list while the scheduler was suspended. If this was the case then the - removed task will have been added to the xPendingReadyList. Once the - scheduler has been resumed it is safe to move all the pending ready - tasks from this list into their appropriate ready list. */ - portENTER_CRITICAL(); - { - --uxSchedulerSuspended; - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0 ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - - /* Move any readied tasks from the pending list into the - appropriate ready list. */ - while( ( pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ) ) != NULL ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* If we have moved a task that has a priority higher than - the current task then we should yield. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - xYieldRequired = pdTRUE; - } - } - - /* If any ticks occurred while the scheduler was suspended then - they should be processed now. This ensures the tick count does not - slip, and that any delayed tasks are resumed at the correct time. */ - if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) - { - while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) - { - vTaskIncrementTick(); - --uxMissedTicks; - } - - /* As we have processed some ticks it is appropriate to yield - to ensure the highest priority task that is ready to run is - the task actually running. */ - #if configUSE_PREEMPTION == 1 - { - xYieldRequired = pdTRUE; - } - #endif - } - - if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) - { - xAlreadyYielded = pdTRUE; - xMissedYield = pdFALSE; - portYIELD_WITHIN_API(); - } - } - } - } - portEXIT_CRITICAL(); - - return xAlreadyYielded; -} - - - - - - -/*----------------------------------------------------------- - * PUBLIC TASK UTILITIES documented in task.h - *----------------------------------------------------------*/ - - - -portTickType xTaskGetTickCount( void ) -{ -portTickType xTicks; - - /* Critical section required if running on a 16 bit processor. */ - portENTER_CRITICAL(); - { - xTicks = xTickCount; - } - portEXIT_CRITICAL(); - - return xTicks; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) -{ - /* A critical section is not required because the variables are of type - portBASE_TYPE. */ - return uxCurrentNumberOfTasks; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskList( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB and - report the task name, state and stack high water mark. */ - - pcWriteBuffer[ 0 ] = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + 1; - - do - { - uxQueue--; - - if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); - } - - if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); - } - - #if( INCLUDE_vTaskDelete == 1 ) - { - if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, tskDELETED_CHAR ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, tskSUSPENDED_CHAR ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - unsigned long ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB, - generating a table of run timer percentages in the provided - buffer. */ - - pcWriteBuffer[ 0 ] = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + 1; - - do - { - uxQueue--; - - if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); - } - - if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); - } - - #if ( INCLUDE_vTaskDelete == 1 ) - { - if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, ulTotalRunTime ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, ulTotalRunTime ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) - { - portENTER_CRITICAL(); - { - pcTraceBuffer = ( signed char * )pcBuffer; - pcTraceBufferStart = pcBuffer; - pcTraceBufferEnd = pcBuffer + ( ulBufferSize - tskSIZE_OF_EACH_TRACE_LINE ); - xTracing = pdTRUE; - } - portEXIT_CRITICAL(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned long ulTaskEndTrace( void ) - { - unsigned long ulBufferLength; - - portENTER_CRITICAL(); - xTracing = pdFALSE; - portEXIT_CRITICAL(); - - ulBufferLength = ( unsigned long ) ( pcTraceBuffer - pcTraceBufferStart ); - - return ulBufferLength; - } - -#endif - - - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - * documented in task.h - *----------------------------------------------------------*/ - - -void vTaskIncrementTick( void ) -{ - /* Called by the portable layer each time a tick interrupt occurs. - Increments the tick then checks to see if the new tick value will cause any - tasks to be unblocked. */ - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - ++xTickCount; - if( xTickCount == ( portTickType ) 0 ) - { - xList *pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. - If there are any items in pxDelayedTaskList here then there is - an error! */ - pxTemp = pxDelayedTaskList; - pxDelayedTaskList = pxOverflowDelayedTaskList; - pxOverflowDelayedTaskList = pxTemp; - xNumOfOverflows++; - } - - /* See if this tick has made a timeout expire. */ - prvCheckDelayedTasks(); - } - else - { - ++uxMissedTicks; - - /* The tick hook gets called at regular intervals, even if the - scheduler is locked. */ - #if ( configUSE_TICK_HOOK == 1 ) - { - extern void vApplicationTickHook( void ); - - vApplicationTickHook(); - } - #endif - } - - #if ( configUSE_TICK_HOOK == 1 ) - { - extern void vApplicationTickHook( void ); - - /* Guard against the tick hook being called when the missed tick - count is being unwound (when the scheduler is being unlocked. */ - if( uxMissedTicks == 0 ) - { - vApplicationTickHook(); - } - } - #endif - - traceTASK_INCREMENT_TICK( xTickCount ); -} -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_vTaskCleanUpResources == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - void vTaskCleanUpResources( void ) - { - unsigned short usQueue; - volatile tskTCB *pxTCB; - - usQueue = ( unsigned short ) uxTopUsedPriority + ( unsigned short ) 1; - - /* Remove any TCB's from the ready queues. */ - do - { - usQueue--; - - while( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ usQueue ] ) ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &( pxReadyTasksLists[ usQueue ] ) ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - }while( usQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - /* Remove any TCB's from the delayed queue. */ - while( !listLIST_IS_EMPTY( &xDelayedTaskList1 ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList1 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - /* Remove any TCB's from the overflow delayed queue. */ - while( !listLIST_IS_EMPTY( &xDelayedTaskList2 ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList2 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - while( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xSuspendedTaskList ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxTagValue ) - { - tskTCB *xTCB; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - portENTER_CRITICAL(); - xTCB->pxTaskTag = pxTagValue; - portEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) - { - tskTCB *xTCB; - pdTASK_HOOK_CODE xReturn; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - portENTER_CRITICAL(); - xReturn = xTCB->pxTaskTag; - portEXIT_CRITICAL(); - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) - { - tskTCB *xTCB; - portBASE_TYPE xReturn; - - /* If xTask is NULL then we are calling our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - if( xTCB->pxTaskTag != NULL ) - { - xReturn = xTCB->pxTaskTag( pvParameter ); - } - else - { - xReturn = pdFAIL; - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -void vTaskSwitchContext( void ) -{ - if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) - { - /* The scheduler is currently suspended - do not allow a context - switch. */ - xMissedYield = pdTRUE; - return; - } - - traceTASK_SWITCHED_OUT(); - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - unsigned long ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); - - /* Add the amount of time the task has been running to the accumulated - time so far. The time the task started running was stored in - ulTaskSwitchedInTime. Note that there is no overflow protection here - so count values are only valid until the timer overflows. Generally - this will be about 1 hour assuming a 1uS timer increment. */ - pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); - ulTaskSwitchedInTime = ulTempCounter; - } - #endif - - taskFIRST_CHECK_FOR_STACK_OVERFLOW(); - taskSECOND_CHECK_FOR_STACK_OVERFLOW(); - - /* Find the highest priority queue that contains ready tasks. */ - while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) - { - --uxTopReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the - same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); - - traceTASK_SWITCHED_IN(); - vWriteTraceToBuffer(); -} -/*-----------------------------------------------------------*/ - -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) -{ -portTickType xTimeToWake; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. */ - - /* Place the event list item of the TCB in the appropriate event list. - This is placed in the list in priority order so the highest priority task - is the first to be woken by the event. */ - vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove ourselves from the ready list before adding ourselves - to the blocked list as the same list item is used for both lists. We have - exclusive access to the ready lists as the scheduler is locked. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( xTicksToWait == portMAX_DELAY ) - { - /* Add ourselves to the suspended task list instead of a delayed task - list to ensure we are not woken by a timing event. We will block - indefinitely. */ - vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - } - #else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - #endif -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) -{ -tskTCB *pxUnblockedTCB; -portBASE_TYPE xReturn; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. It can also be called from within an ISR. */ - - /* The event list is sorted in priority order, so we can remove the - first in the list, remove the TCB from the delayed list, and add - it to the ready list. - - If an event is for a queue that is locked then this function will never - get called - the lock count on the queue will get modified instead. This - means we can always expect exclusive access to the event list here. */ - pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - vListRemove( &( pxUnblockedTCB->xEventListItem ) ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxUnblockedTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); - } - - if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* Return true if the task removed from the event list has - a higher priority than the calling task. This allows - the calling task to know if it should force a context - switch now. */ - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) -{ - pxTimeOut->xOverflowCount = xNumOfOverflows; - pxTimeOut->xTimeOnEntering = xTickCount; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) -{ -portBASE_TYPE xReturn; - - portENTER_CRITICAL(); - { - #if ( INCLUDE_vTaskSuspend == 1 ) - /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is - the maximum block time then the task should block indefinitely, and - therefore never time out. */ - if( *pxTicksToWait == portMAX_DELAY ) - { - xReturn = pdFALSE; - } - else /* We are not blocking indefinitely, perform the checks below. */ - #endif - - if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) - { - /* The tick count is greater than the time at which vTaskSetTimeout() - was called, but has also overflowed since vTaskSetTimeOut() was called. - It must have wrapped all the way around and gone past us again. This - passed since vTaskSetTimeout() was called. */ - xReturn = pdTRUE; - } - else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) - { - /* Not a genuine timeout. Adjust parameters for time remaining. */ - *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); - vTaskSetTimeOutState( pxTimeOut ); - xReturn = pdFALSE; - } - else - { - xReturn = pdTRUE; - } - } - portEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskMissedYield( void ) -{ - xMissedYield = pdTRUE; -} - -/* - * ----------------------------------------------------------- - * The Idle task. - * ---------------------------------------------------------- - * - * The portTASK_FUNCTION() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION( prvIdleTask, pvParameters ) -{ - /* Stop warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* See if any tasks have been deleted. */ - prvCheckTasksWaitingTermination(); - - #if ( configUSE_PREEMPTION == 0 ) - { - /* If we are not using preemption we keep forcing a task switch to - see if any other task has become available. If we are using - preemption we don't need to do this as any task becoming available - will automatically get the processor anyway. */ - taskYIELD(); - } - #endif - - #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) - { - /* When using preemption tasks of equal priority will be - timesliced. If a task that is sharing the idle priority is ready - to run then the idle task should yield before the end of the - timeslice. - - A critical region is not required here as we are just reading from - the list, and an occasional incorrect value will not matter. If - the ready list at the idle priority contains more than one task - then a task other than the idle task is ready to execute. */ - if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) - { - taskYIELD(); - } - } - #endif - - #if ( configUSE_IDLE_HOOK == 1 ) - { - extern void vApplicationIdleHook( void ); - - /* Call the user defined function from within the idle task. This - allows the application designer to add background functionality - without the overhead of a separate task. - NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, - CALL A FUNCTION THAT MIGHT BLOCK. */ - vApplicationIdleHook(); - } - #endif - // call nanosleep for smalles sleep time possible - // (depending on kernel settings - around 100 microseconds) - // decreases idle thread CPU load from 100 to practically 0 -#ifdef IDLE_SLEEPS - sigset_t xSignals; - sigfillset( &xSignals ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL ); - struct timespec x; - x.tv_sec=0; - x.tv_nsec=10000; - nanosleep(&x,NULL); - sigemptyset( &xSignals ); - sigaddset( &xSignals, SIG_TICK ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL ); -#endif - } -} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ - - - - - - - -/*----------------------------------------------------------- - * File private functions documented at the top of the file. - *----------------------------------------------------------*/ - - - -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) -{ - /* Store the function name in the TCB. */ - #if configMAX_TASK_NAME_LEN > 1 - { - /* Don't bring strncpy into the build unnecessarily. */ - strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); - } - #endif - pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = '\0'; - - /* This is used as an array index so must ensure it's not too large. First - remove the privilege bit if one is present. */ - if( uxPriority >= configMAX_PRIORITIES ) - { - uxPriority = configMAX_PRIORITIES - 1; - } - - pxTCB->uxPriority = uxPriority; - #if ( configUSE_MUTEXES == 1 ) - { - pxTCB->uxBasePriority = uxPriority; - } - #endif - - vListInitialiseItem( &( pxTCB->xGenericListItem ) ); - vListInitialiseItem( &( pxTCB->xEventListItem ) ); - - /* Set the pxTCB as a link back from the xListItem. This is so we can get - back to the containing TCB from a generic item in a list. */ - listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - { - pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0; - } - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - { - pxTCB->pxTaskTag = NULL; - } - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - pxTCB->ulRunTimeCounter = 0UL; - } - #endif - - #if ( portUSING_MPU_WRAPPERS == 1 ) - { - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); - } - #else - { - ( void ) xRegions; - ( void ) usStackDepth; - } - #endif -} -/*-----------------------------------------------------------*/ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - - void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) - { - tskTCB *pxTCB; - - if( xTaskToModify == pxCurrentTCB ) - { - xTaskToModify = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( xTaskToModify ); - - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); - } - /*-----------------------------------------------------------*/ -#endif - -static void prvInitialiseTaskLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = 0; uxPriority < configMAX_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedTaskList1 ); - vListInitialise( ( xList * ) &xDelayedTaskList2 ); - vListInitialise( ( xList * ) &xPendingReadyList ); - - #if ( INCLUDE_vTaskDelete == 1 ) - { - vListInitialise( ( xList * ) &xTasksWaitingTermination ); - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - vListInitialise( ( xList * ) &xSuspendedTaskList ); - } - #endif - - /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList - using list2. */ - pxDelayedTaskList = &xDelayedTaskList1; - pxOverflowDelayedTaskList = &xDelayedTaskList2; -} -/*-----------------------------------------------------------*/ - -static void prvCheckTasksWaitingTermination( void ) -{ - #if ( INCLUDE_vTaskDelete == 1 ) - { - portBASE_TYPE xListIsEmpty; - - /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called - too often in the idle task. */ - if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0 ) - { - vTaskSuspendAll(); - xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); - xTaskResumeAll(); - - if( !xListIsEmpty ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - --uxCurrentNumberOfTasks; - --uxTasksDeleted; - } - portEXIT_CRITICAL(); - - prvDeleteTCB( pxTCB ); - } - } - } - #endif -} -/*-----------------------------------------------------------*/ - -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) -{ -tskTCB *pxNewTCB; - - /* Allocate space for the TCB. Where the memory comes from depends on - the implementation of the port malloc function. */ - pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); - - if( pxNewTCB != NULL ) - { - /* Allocate space for the stack used by the task being created. - The base of the stack memory stored in the TCB so the task can - be deleted later if required. */ - pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); - - if( pxNewTCB->pxStack == NULL ) - { - /* Could not allocate the stack. Delete the allocated TCB. */ - vPortFree( pxNewTCB ); - pxNewTCB = NULL; - } - else - { - /* Just to help debugging. */ - memset( pxNewTCB->pxStack, tskSTACK_FILL_BYTE, usStackDepth * sizeof( portSTACK_TYPE ) ); - } - } - - return pxNewTCB; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned short usStackRemaining; - - /* Write the details of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - #if ( portSTACK_GROWTH > 0 ) - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); - } - #else - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); - } - #endif - - sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned long ulStatsAsPercentage; - - /* Write the run time stats of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - /* Get next TCB in from the list. */ - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - - /* Divide by zero check. */ - if( ulTotalRunTime > 0UL ) - { - /* Has the task run at all? */ - if( pxNextTCB->ulRunTimeCounter == 0 ) - { - /* The task has used no CPU time at all. */ - sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); - } - else - { - /* What percentage of the total run time as the task used? - This will always be rounded down to the nearest integer. */ - ulStatsAsPercentage = ( 100UL * pxNextTCB->ulRunTimeCounter ) / ulTotalRunTime; - - if( ulStatsAsPercentage > 0UL ) - { - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); - } - else - { - /* If the percentage is zero here then the task has - consumed less than 1% of the total run time. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); - } - } - - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); - } - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) - { - register unsigned short usCount = 0; - - while( *pucStackByte == tskSTACK_FILL_BYTE ) - { - pucStackByte -= portSTACK_GROWTH; - usCount++; - } - - usCount /= sizeof( portSTACK_TYPE ); - - return usCount; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) - - unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) - { - tskTCB *pxTCB; - unsigned char *pcEndOfStack; - unsigned portBASE_TYPE uxReturn; - - pxTCB = prvGetTCBFromHandle( xTask ); - - #if portSTACK_GROWTH < 0 - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; - } - #else - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; - } - #endif - - uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) - - static void prvDeleteTCB( tskTCB *pxTCB ) - { - /* Free up the memory allocated by the scheduler for the task. It is up to - the task to free any memory allocated at the application level. */ - vPortFreeAligned( pxTCB->pxStack ); - vPortFree( pxTCB ); - } - -#endif - - -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) - - xTaskHandle xTaskGetCurrentTaskHandle( void ) - { - xTaskHandle xReturn; - - /* A critical section is not required as this is not called from - an interrupt and the current TCB will always be the same for any - individual execution thread. */ - xReturn = pxCurrentTCB; - - return xReturn; - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetSchedulerState == 1 ) - - portBASE_TYPE xTaskGetSchedulerState( void ) - { - portBASE_TYPE xReturn; - - if( xSchedulerRunning == pdFALSE ) - { - xReturn = taskSCHEDULER_NOT_STARTED; - } - else - { - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xReturn = taskSCHEDULER_RUNNING; - } - else - { - xReturn = taskSCHEDULER_SUSPENDED; - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) - { - /* Adjust the mutex holder state to account for its new priority. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); - - /* If the task being modified is in the ready state it will need to - be moved in to a new list. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Inherit the priority before being moved into the new list. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* Just inherit the priority. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxMutexHolder != NULL ) - { - if( pxTCB->uxPriority != pxTCB->uxBasePriority ) - { - /* We must be the running task to be able to give the mutex back. - Remove ourselves from the ready list we currently appear in. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Disinherit the priority before adding ourselves into the new - ready list. */ - pxTCB->uxPriority = pxTCB->uxBasePriority; - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); - prvAddTaskToReadyQueue( pxTCB ); - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - - void vTaskEnterCritical( void ) - { - portDISABLE_INTERRUPTS(); - - if( xSchedulerRunning != pdFALSE ) - { - pxCurrentTCB->uxCriticalNesting++; - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - -void vTaskExitCritical( void ) -{ - if( xSchedulerRunning != pdFALSE ) - { - if( pxCurrentTCB->uxCriticalNesting > 0 ) - { - pxCurrentTCB->uxCriticalNesting--; - - if( pxCurrentTCB->uxCriticalNesting == 0 ) - { - portENABLE_INTERRUPTS(); - } - } - } -} - -#endif -/*-----------------------------------------------------------*/ - - - - diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/library.mk b/flight/PiOS.posix/posix/Libraries/FreeRTOS/library.mk new file mode 100644 index 000000000..ae65aff82 --- /dev/null +++ b/flight/PiOS.posix/posix/Libraries/FreeRTOS/library.mk @@ -0,0 +1,11 @@ +# +# Rules to add FreeRTOS to a PiOS target +# +# Note that the PIOS target-specific makefile will detect that FREERTOS_DIR +# has been defined and add in the target-specific pieces separately. +# + +FREERTOS_DIR := $(dir $(lastword $(MAKEFILE_LIST)))/Source +SRC += $(wildcard $(FREERTOS_DIR)/*.c) +EXTRAINCDIRS += $(FREERTOS_DIR)/include + diff --git a/flight/PiOS.posix/posix/library.mk b/flight/PiOS.posix/posix/library.mk new file mode 100644 index 000000000..530431210 --- /dev/null +++ b/flight/PiOS.posix/posix/library.mk @@ -0,0 +1,76 @@ +# +# Rules to (help) build the F4xx device support. +# + +# +# Directory containing this makefile +# +PIOS_DEVLIB := $(dir $(lastword $(MAKEFILE_LIST))) + +# +# Hardcoded linker script names for now +# +#LINKER_SCRIPTS_APP = $(PIOS_DEVLIB)/link_STM32F4xx_OP_memory.ld \ + $(PIOS_DEVLIB)/link_STM32F4xx_sections.ld + +#LINKER_SCRIPTS_BL = $(PIOS_DEVLIB)/link_STM32F4xx_BL_memory.ld \ + $(PIOS_DEVLIB)/link_STM32F4xx_sections.ld + +# +# Compiler options implied by the F4xx +# +#CDEFS += -DSTM32F4XX +#CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ) +#CDEFS += -DUSE_STDPERIPH_DRIVER +ARCHFLAGS += -DARCH_POSIX + +# +# PIOS device library source and includes +# +SRC += $(wildcard $(PIOS_DEVLIB)*.c) +EXTRAINCDIRS += $(PIOS_DEVLIB)/inc + +# +# CMSIS for the F4 +# +#include $(PIOSCOMMONLIB)/CMSIS2/library.mk +#CMSIS2_DEVICEDIR := $(PIOS_DEVLIB)/Libraries/CMSIS2/Device/ST/STM32F4xx +#SRC += $(wildcard $(CMSIS2_DEVICEDIR)/Source/*.c) +#EXTRAINCDIRS += $(CMSIS2_DEVICEDIR)/Include + +# +# ST Peripheral library +# +#PERIPHLIB = $(PIOS_DEVLIB)/Libraries/STM32F4xx_StdPeriph_Driver +#SRC += $(wildcard $(PERIPHLIB)/src/*.c) +#EXTRAINCDIRS += $(PERIPHLIB)/inc + +# +# ST USB OTG library +# +#USBOTGLIB = $(PIOS_DEVLIB)/Libraries/STM32_USB_OTG_Driver +#USBOTGLIB_SRC = usb_core.c usb_dcd.c usb_dcd_int.c +#SRC += $(addprefix $(USBOTGLIB)/src/,$(USBOTGLIB_SRC)) +#EXTRAINCDIRS += $(USBOTGLIB)/inc + +# +# ST USB Device library +# +#USBDEVLIB = $(PIOS_DEVLIB)/Libraries/STM32_USB_Device_Library +#SRC += $(wildcard $(USBDEVLIB)/Core/src/*.c) +#EXTRAINCDIRS += $(USBDEVLIB)/Core/inc + +# +# FreeRTOS +# +# If the application has included the generic FreeRTOS support, then add in +# the device-specific pieces of the code. +# +ifneq ($(FREERTOS_DIR),) +FREERTOS_PORTDIR := $(PIOS_DEVLIB)/Libraries/FreeRTOS/Source +SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/Posix/*.c) +SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/MemMang/*.c) + +EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/Posix +endif + diff --git a/flight/PiOS.posix/posix/pios_debug.c b/flight/PiOS.posix/posix/pios_debug.c index 7f3dc99da..02d41ee64 100644 --- a/flight/PiOS.posix/posix/pios_debug.c +++ b/flight/PiOS.posix/posix/pios_debug.c @@ -72,11 +72,10 @@ void PIOS_DEBUG_PinValue4BitL(uint8_t value) /** * Report a serious error and halt */ -void PIOS_DEBUG_Panic(const char *msg) __attribute__ ((noreturn)) +void PIOS_DEBUG_Panic(const char *msg) { -#ifdef PIOS_COM_DEBUG - register int *lr asm("lr"); // Link-register holds the PC of the caller - PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, "\r%s @0x%x\r", msg, lr); +#ifdef PIOS_COM_AUX + PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, "\r%s\r", msg); #endif // tell the user whats going on on commandline too diff --git a/flight/PiOS.posix/posix/pios_delay.c b/flight/PiOS.posix/posix/pios_delay.c index cec10467c..386e2bb2f 100644 --- a/flight/PiOS.posix/posix/pios_delay.c +++ b/flight/PiOS.posix/posix/pios_delay.c @@ -59,7 +59,7 @@ int32_t PIOS_DELAY_Init(void) * \param[in] uS delay (1..65535 microseconds) * \return < 0 on errors */ -int32_t PIOS_DELAY_WaituS(uint16_t uS) +int32_t PIOS_DELAY_WaituS(uint32_t uS) { static struct timespec wait,rest; wait.tv_sec=0; @@ -83,7 +83,7 @@ int32_t PIOS_DELAY_WaituS(uint16_t uS) * \param[in] mS delay (1..65535 milliseconds) * \return < 0 on errors */ -int32_t PIOS_DELAY_WaitmS(uint16_t mS) +int32_t PIOS_DELAY_WaitmS(uint32_t mS) { //for(int i = 0; i < mS; i++) { // PIOS_DELAY_WaituS(1000); @@ -99,4 +99,44 @@ int32_t PIOS_DELAY_WaitmS(uint16_t mS) return 0; } +/** + * @brief Query the Delay timer for the current uS + * @return A microsecond value + */ +uint32_t PIOS_DELAY_GetuS() +{ + static struct timespec current; + clock_gettime(CLOCK_REALTIME, ¤t); + return ((current.tv_sec * 1000000) + (current.tv_nsec / 1000)); +} + +/** + * @brief Calculate time in microseconds since a previous time + * @param[in] t previous time + * @return time in us since previous time t. + */ +uint32_t PIOS_DELAY_GetuSSince(uint32_t t) +{ + return (PIOS_DELAY_GetuS() - t); +} + +/** + * @brief Get the raw delay timer, useful for timing + * @return Unitless value (uint32 wrap around) + */ +uint32_t PIOS_DELAY_GetRaw() +{ + return (PIOS_DELAY_GetuS()); +} + +/** + * @brief Compare to raw times to and convert to us + * @return A microsecond value + */ +uint32_t PIOS_DELAY_DiffuS(uint32_t raw) +{ + return ( PIOS_DELAY_GetuS() - raw ); +} + + #endif diff --git a/flight/PiOS.posix/posix/pios_led.c b/flight/PiOS.posix/posix/pios_led.c index b35477d45..8e0776883 100644 --- a/flight/PiOS.posix/posix/pios_led.c +++ b/flight/PiOS.posix/posix/pios_led.c @@ -41,7 +41,7 @@ static uint8_t LED_GPIO[PIOS_LED_NUM]; -static inline void PIOS_SetLED(LedTypeDef LED,uint8_t stat) { +static inline void PIOS_SetLED(uint32_t LED,uint8_t stat) { printf("PIOS: LED %i status %i\n",LED,stat); LED_GPIO[LED]=stat; } @@ -71,7 +71,7 @@ void PIOS_LED_Init(void) * Turn on LED * \param[in] LED LED Name (LED1, LED2) */ -void PIOS_LED_On(LedTypeDef LED) +void PIOS_LED_On(uint32_t LED) { //LED_GPIO_PORT[LED]->BRR = LED_GPIO_PIN[LED]; PIOS_SetLED(LED,1); @@ -82,7 +82,7 @@ void PIOS_LED_On(LedTypeDef LED) * Turn off LED * \param[in] LED LED Name (LED1, LED2) */ -void PIOS_LED_Off(LedTypeDef LED) +void PIOS_LED_Off(uint32_t LED) { //LED_GPIO_PORT[LED]->BSRR = LED_GPIO_PIN[LED]; PIOS_SetLED(LED,0); @@ -93,7 +93,7 @@ void PIOS_LED_Off(LedTypeDef LED) * Toggle LED on/off * \param[in] LED LED Name (LED1, LED2) */ -void PIOS_LED_Toggle(LedTypeDef LED) +void PIOS_LED_Toggle(uint32_t LED) { //LED_GPIO_PORT[LED]->ODR ^= LED_GPIO_PIN[LED]; PIOS_SetLED(LED,LED_GPIO[LED]?0:1); diff --git a/flight/PiOS.posix/posix/pios_udp.c b/flight/PiOS.posix/posix/pios_udp.c index 5ccbae767..2c98c42ee 100644 --- a/flight/PiOS.posix/posix/pios_udp.c +++ b/flight/PiOS.posix/posix/pios_udp.c @@ -78,11 +78,6 @@ static pios_udp_dev * find_udp_dev_by_id (uint8_t udp) void * PIOS_UDP_RxThread(void * udp_dev_n) { - /* needed because of FreeRTOS.posix scheduling */ - sigset_t set; - sigfillset(&set); - sigprocmask(SIG_BLOCK, &set, NULL); - pios_udp_dev * udp_dev = (pios_udp_dev*) udp_dev_n; /** @@ -151,7 +146,13 @@ int32_t PIOS_UDP_Init(uint32_t * udp_id, const struct pios_udp_cfg * cfg) int res= bind(udp_dev->socket, (struct sockaddr *)&udp_dev->server,sizeof(udp_dev->server)); /* Create transmit thread for this connection */ +#if defined(PIOS_INCLUDE_FREERTOS) +//( pdTASK_CODE pvTaskCode, const portCHAR * const pcName, unsigned portSHORT usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pvCreatedTask ); + xTaskCreate((pdTASK_CODE)PIOS_UDP_RxThread, (const signed char *)"UDP_Rx_Thread",1024,(void*)udp_dev,(tskIDLE_PRIORITY + 1),&udp_dev->rxThread); +#else pthread_create(&udp_dev->rxThread, NULL, PIOS_UDP_RxThread, (void*)udp_dev); +#endif + printf("udp dev %i - socket %i opened - result %i\n",pios_udp_num_devices-1,udp_dev->socket,res); diff --git a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h index 0b1884a42..10a7a41cd 100644 --- a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h @@ -215,6 +215,7 @@ extern uint32_t pios_com_telem_usb_id; //------------------------ #define PIOS_RCVR_MAX_DEVS 3 #define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_GCSRCVR_TIMEOUT_MS 100 //------------------------- // Receiver PPM input @@ -254,20 +255,11 @@ extern uint32_t pios_com_telem_usb_id; //------------------------- // GPIO //------------------------- -#define PIOS_GPIO_1_PORT GPIOA -#define PIOS_GPIO_1_PIN GPIO_Pin_7 -#define PIOS_GPIO_1_GPIO_CLK RCC_APB2Periph_GPIOA +#define PIOS_GPIO_PORTS { } +#define PIOS_GPIO_PINS { } +#define PIOS_GPIO_CLKS { } +#define PIOS_GPIO_NUM 0 -#define PIOS_GPIO_PORTS { PIOS_GPIO_1_PORT } -#define PIOS_GPIO_PINS { PIOS_GPIO_1_PIN } -#define PIOS_GPIO_CLKS { PIOS_GPIO_1_GPIO_CLK } -#define PIOS_GPIO_NUM 1 - -#define PIOS_FLASH_CS_PIN 0 -#define PIOS_FLASH_ENABLE PIOS_GPIO_On(0) -#define PIOS_FLASH_DISABLE PIOS_GPIO_Off(0) -#define PIOS_ADXL_ENABLE PIOS_SPI_RC_PinSet(PIOS_SPI_ACCEL,0) -#define PIOS_ADXL_DISABLE PIOS_SPI_RC_PinSet(PIOS_SPI_ACCEL,1) //------------------------- // USB diff --git a/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h b/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h old mode 100644 new mode 100755 index 8d04e05a4..868bba722 --- a/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h @@ -23,20 +23,22 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef PIOS_BOARD_H -#define PIOS_BOARD_H +#ifndef STM32103CB_PIPXTREME_H_ +#define STM32103CB_PIPXTREME_H_ -// ***************************************************************** +#define ADD_ONE_ADC + +//------------------------ // Timers and Channels Used - +//------------------------ /* -Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 -------+------------+------------+------------+------------ -TIM1 | DELAY | -TIM2 | | PPM Output | PPM Input | -TIM3 | TIMER INTERRUPT | -TIM4 | STOPWATCH | -------+------------+------------+------------+------------ +Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 +------+-----------+-----------+-----------+---------- +TIM1 | Servo 4 | | | +TIM2 | RC In 5 | RC In 6 | Servo 6 | +TIM3 | Servo 5 | RC In 2 | RC In 3 | RC In 4 +TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1 +------+-----------+-----------+-----------+---------- */ //------------------------ @@ -55,6 +57,7 @@ TIM4 | STOPWATCH | /* Channel 11 - */ /* Channel 12 - */ + //------------------------ // BOOTLOADER_SETTINGS //------------------------ @@ -63,23 +66,26 @@ TIM4 | STOPWATCH | #define MAX_DEL_RETRYS 3 -// ***************************************************************** -// System Settings +//------------------------ +// WATCHDOG_SETTINGS +//------------------------ +#define PIOS_WATCHDOG_TIMEOUT 500 +#define PIOS_WDG_REGISTER BKP_DR4 +#define PIOS_WDG_COMUAVTALK 0x0001 +#define PIOS_WDG_RADIORECEIVE 0x0002 +#define PIOS_WDG_SENDPACKET 0x0004 +#define PIOS_WDG_SENDDATA 0x0008 +#define PIOS_WDG_TRANSCOMM 0x0010 +#define PIOS_WDG_PPMINPUT 0x0020 -#define PIOS_MASTER_CLOCK 72000000ul -#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) +//------------------------ +// TELEMETRY +//------------------------ +#define TELEM_QUEUE_SIZE 20 -// ***************************************************************** -// Interrupt Priorities - -#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS -#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS -#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... -#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... - -// ***************************************************************** +//------------------------ // PIOS_LED - +//------------------------ #define PIOS_LED_USB 0 #define PIOS_LED_LINK 1 #define PIOS_LED_RX 2 @@ -104,17 +110,27 @@ TIM4 | STOPWATCH | #define TX_LED_OFF PIOS_LED_Off(PIOS_LED_TX) #define TX_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_TX) -// ***************************************************************** -// Timer interrupt +//------------------------- +// System Settings +//------------------------- +#define PIOS_MASTER_CLOCK 72000000 +#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) -#define TIMER_INT_TIMER TIM3 -#define TIMER_INT_FUNC TIM3_IRQHandler -#define TIMER_INT_PRIORITY 2 +//------------------------- +// Interrupt Priorities +//------------------------- +#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS +#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS +#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... +#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... -// ***************************************************************** -// Stop watch timer - -#define STOPWATCH_TIMER TIM4 +//------------------------ +// PIOS_I2C +// See also pios_board.c +//------------------------ +#define PIOS_I2C_MAX_DEVS 1 +extern uint32_t pios_i2c_flexi_adapter_id; +#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexi_adapter_id) //------------------------ // PIOS_SPI @@ -126,286 +142,170 @@ extern uint32_t pios_spi_port_id; //------------------------- // PIOS_USART -// -// See also pios_board.c //------------------------- -#define PIOS_USART_MAX_DEVS 1 +#define PIOS_USART_MAX_DEVS 3 //------------------------- // PIOS_COM // // See also pios_board.c //------------------------- -#define PIOS_COM_MAX_DEVS 2 +#define PIOS_COM_MAX_DEVS 5 -extern uint32_t pios_com_serial_id; -#define PIOS_COM_SERIAL (pios_com_serial_id) -//#define PIOS_COM_DEBUG PIOS_COM_SERIAL // uncomment this to send debug info out the serial port - -#if defined(PIOS_INCLUDE_USB_HID) extern uint32_t pios_com_telem_usb_id; -#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#endif +extern uint32_t pios_com_telemetry_id; +extern uint32_t pios_com_flexi_id; +extern uint32_t pios_com_vcp_id; +extern uint32_t pios_com_uavtalk_com_id; +extern uint32_t pios_com_trans_com_id; +extern uint32_t pios_com_debug_id; +extern uint32_t pios_com_rfm22b_id; +extern uint32_t pios_ppm_rcvr_id; +#define PIOS_COM_USB_HID (pios_com_telem_usb_id) +#define PIOS_COM_TELEMETRY (pios_com_telemetry_id) +#define PIOS_COM_FLEXI (pios_com_flexi_id) +#define PIOS_COM_VCP (pios_com_vcp_id) +#define PIOS_COM_UAVTALK (pios_com_uavtalk_com_id) +#define PIOS_COM_TRANS_COM (pios_com_trans_com_id) +#define PIOS_COM_DEBUG (pios_com_debug_id) +#define PIOS_COM_RADIO (pios_com_rfm22b_id) +#define PIOS_COM_TELEM_USB PIOS_COM_USB_HID +#define PIOS_PPM_RECEIVER (pios_ppm_rcvr_id) -#if defined(PIOS_COM_DEBUG) -// #define DEBUG_PRINTF(...) PIOS_COM_SendFormattedString(PIOS_COM_DEBUG, __VA_ARGS__) - #define DEBUG_PRINTF(...) PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, __VA_ARGS__) +#define DEBUG_LEVEL 2 +#if DEBUG_LEVEL > 0 +#define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && PIOS_COM_DEBUG > 0) { PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, __VA_ARGS__); }} #else - #define DEBUG_PRINTF(...) +#define DEBUG_PRINTF(...) #endif +#define RFM22_DEBUG 1 //------------------------- -// PPM input/output -//------------------------- -#define PIOS_PPM_IN_GPIO_PORT GPIOB -#define PIOS_PPM_IN_GPIO_PIN GPIO_Pin_11 -#define PIOS_PPM_IN_TIM_CHANNEL TIM_Channel_4 -#define PIOS_PPM_IN_TIM_CCR TIM_IT_CC4 -#define PIOS_PPM_IN_TIM_GETCAP_FUNC TIM_GetCapture4 - -#define PIOS_PPM_OUT_GPIO_PORT GPIOB -#define PIOS_PPM_OUT_GPIO_PIN GPIO_Pin_10 -#define PIOS_PPM_OUT_TIM_CHANNEL TIM_Channel_3 -#define PIOS_PPM_OUT_TIM_CCR TIM_IT_CC3 - -#define PIOS_PPM_MAX_CHANNELS 7 -#define PIOS_PPM_TIM_PORT TIM2 -#define PIOS_PPM_TIM TIM2 -#define PIOS_PPM_TIM_IRQ TIM2_IRQn -#define PIOS_PPM_CC_IRQ_FUNC TIM2_IRQHandler -#define PIOS_PPM_TIMER_EN_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE) -#define PIOS_PPM_TIMER_DIS_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, DISABLE) - -// ***************************************************************** // ADC +// None +//------------------------- +//#define PIOS_ADC_OVERSAMPLING_RATE 1 +#define PIOS_ADC_USE_TEMP_SENSOR 0 +#define PIOS_ADC_TEMP_SENSOR_ADC ADC1 +#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1 -// PIOS_ADC_PinGet(0) = Temperature Sensor (On-board) -// PIOS_ADC_PinGet(1) = PSU Voltage +#define PIOS_ADC_NUM_PINS 0 -#define PIOS_ADC_OVERSAMPLING_RATE 2 +#define PIOS_ADC_PORTS { } +#define PIOS_ADC_PINS { } +#define PIOS_ADC_CHANNELS { } +#define PIOS_ADC_MAPPING { } +#define PIOS_ADC_CHANNEL_MAPPING { } +#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR) +#define PIOS_ADC_NUM_ADC_CHANNELS 0 +#define PIOS_ADC_USE_ADC2 0 +#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE) +#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8 +/* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */ +/* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */ +/* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */ +/* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */ +#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5 +/* Sample time: */ +/* With an ADCCLK = 14 MHz and a sampling time of 239.5 cycles: */ +/* Tconv = 239.5 + 12.5 = 252 cycles = 18�s */ +/* (1 / (ADCCLK / CYCLES)) = Sample Time (�S) */ +#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW -#define PIOS_ADC_USE_TEMP_SENSOR 1 -#define PIOS_ADC_TEMP_SENSOR_ADC ADC1 -#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 16 // Temperature sensor channel -//#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 17 // VREF channel +// Currently analog acquistion hard coded at 480 Hz +// PCKL2 = HCLK / 16 +// ADCCLK = PCLK2 / 2 +#define PIOS_ADC_RATE (72.0e6 / 1.0 / 8.0 / 252.0 / (PIOS_ADC_NUM_CHANNELS >> PIOS_ADC_USE_ADC2)) +#define PIOS_ADC_MAX_OVERSAMPLING 36 -#define PIOS_ADC_PIN1_GPIO_PORT GPIOB // Port B (PSU Voltage) -#define PIOS_ADC_PIN1_GPIO_PIN GPIO_Pin_1 // PB1 .. ADC12_IN9 -#define PIOS_ADC_PIN1_GPIO_CHANNEL ADC_Channel_9 -#define PIOS_ADC_PIN1_ADC ADC2 -#define PIOS_ADC_PIN1_ADC_NUMBER 1 +//------------------------ +// PIOS_RCVR +// See also pios_board.c +//------------------------ +#define PIOS_RCVR_MAX_DEVS 3 +#define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_GCSRCVR_TIMEOUT_MS 100 -#define PIOS_ADC_NUM_PINS 1 +//------------------------- +// Receiver PPM input +//------------------------- +#define PIOS_PPM_MAX_DEVS 1 +#define PIOS_PPM_NUM_INPUTS 12 +#define PIOS_PPM_PACKET_UPDATE_PERIOD_MS 25 -#define PIOS_ADC_PORTS { PIOS_ADC_PIN1_GPIO_PORT } -#define PIOS_ADC_PINS { PIOS_ADC_PIN1_GPIO_PIN } -#define PIOS_ADC_CHANNELS { PIOS_ADC_PIN1_GPIO_CHANNEL } -#define PIOS_ADC_MAPPING { PIOS_ADC_PIN1_ADC } -#define PIOS_ADC_CHANNEL_MAPPING { PIOS_ADC_PIN1_ADC_NUMBER } +//------------------------- +// Servo outputs +//------------------------- +#define PIOS_SERVO_UPDATE_HZ 50 +#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ -#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR) -#define PIOS_ADC_NUM_ADC_CHANNELS 2 -#define PIOS_ADC_USE_ADC2 1 -#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE) -//#define PIOS_ADC_ADCCLK RCC_PCLK2_Div2 // ADC clock = PCLK2/2 -//#define PIOS_ADC_ADCCLK RCC_PCLK2_Div4 // ADC clock = PCLK2/4 -//#define PIOS_ADC_ADCCLK RCC_PCLK2_Div6 // ADC clock = PCLK2/6 -#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8 // ADC clock = PCLK2/8 -//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_1Cycles5 -//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_7Cycles5 -//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_13Cycles5 -//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_28Cycles5 -//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_41Cycles5 -//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_55Cycles5 -//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_71Cycles5 -#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5 - /* Sample time: */ - /* With an ADCCLK = 14 MHz and a sampling time of 293.5 cycles: */ - /* Tconv = 239.5 + 12.5 = 252 cycles = 18�s */ - /* (1 / (ADCCLK / CYCLES)) = Sample Time (�S) */ -#define PIOS_ADC_IRQ_PRIO 3 -#define PIOS_ADC_MAX_OVERSAMPLING 1 -#define PIOS_ADC_RATE (72.0e6 / 1 / 8 / 252 / (PIOS_ADC_NUM_ADC_CHANNELS >> PIOS_ADC_USE_ADC2)) +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 3 -// ***************************************************************** -// GPIO output pins +//------------------------- +// GPIO +//------------------------- +#define PIOS_GPIO_PORTS { } +#define PIOS_GPIO_PINS { } +#define PIOS_GPIO_CLKS { } +#define PIOS_GPIO_NUM 0 -// GPIO_Mode_Out_OD Open Drain Output -// GPIO_Mode_Out_PP Push-Pull Output -// GPIO_Mode_AF_OD Open Drain Output Alternate-Function -// GPIO_Mode_AF_PP Push-Pull Output Alternate-Function - -// Serial port RTS line -#define PIOS_GPIO_OUT_0_PORT GPIOB -#define PIOS_GPIO_OUT_0_PIN GPIO_Pin_15 -#define PIOS_GPIO_OUT_0_GPIO_CLK RCC_APB2Periph_GPIOB - -// RF module chip-select line -#define PIOS_GPIO_OUT_1_PORT GPIOA -#define PIOS_GPIO_OUT_1_PIN GPIO_Pin_4 -#define PIOS_GPIO_OUT_1_GPIO_CLK RCC_APB2Periph_GPIOA - -// PPM OUT line -#define PIOS_GPIO_OUT_2_PORT GPIOB -#define PIOS_GPIO_OUT_2_PIN GPIO_Pin_10 -#define PIOS_GPIO_OUT_2_GPIO_CLK RCC_APB2Periph_GPIOB - -// spare pin -#define PIOS_GPIO_OUT_3_PORT GPIOA -#define PIOS_GPIO_OUT_3_PIN GPIO_Pin_0 -#define PIOS_GPIO_OUT_3_GPIO_CLK RCC_APB2Periph_GPIOA - -// spare pin -#define PIOS_GPIO_OUT_4_PORT GPIOA -#define PIOS_GPIO_OUT_4_PIN GPIO_Pin_1 -#define PIOS_GPIO_OUT_4_GPIO_CLK RCC_APB2Periph_GPIOA - -// spare pin -#define PIOS_GPIO_OUT_5_PORT GPIOC -#define PIOS_GPIO_OUT_5_PIN GPIO_Pin_13 -#define PIOS_GPIO_OUT_5_GPIO_CLK RCC_APB2Periph_GPIOC - -// spare pin -#define PIOS_GPIO_OUT_6_PORT GPIOC -#define PIOS_GPIO_OUT_6_PIN GPIO_Pin_14 -#define PIOS_GPIO_OUT_6_GPIO_CLK RCC_APB2Periph_GPIOC - -// spare pin -#define PIOS_GPIO_OUT_7_PORT GPIOC -#define PIOS_GPIO_OUT_7_PIN GPIO_Pin_15 -#define PIOS_GPIO_OUT_7_GPIO_CLK RCC_APB2Periph_GPIOC - -#define PIOS_GPIO_NUM 8 -#define PIOS_GPIO_PORTS {PIOS_GPIO_OUT_0_PORT, PIOS_GPIO_OUT_1_PORT, PIOS_GPIO_OUT_2_PORT, PIOS_GPIO_OUT_3_PORT, PIOS_GPIO_OUT_4_PORT, PIOS_GPIO_OUT_5_PORT, PIOS_GPIO_OUT_6_PORT, PIOS_GPIO_OUT_7_PORT} -#define PIOS_GPIO_PINS {PIOS_GPIO_OUT_0_PIN, PIOS_GPIO_OUT_1_PIN, PIOS_GPIO_OUT_2_PIN, PIOS_GPIO_OUT_3_PIN, PIOS_GPIO_OUT_4_PIN, PIOS_GPIO_OUT_5_PIN, PIOS_GPIO_OUT_6_PIN, PIOS_GPIO_OUT_7_PIN} -#define PIOS_GPIO_CLKS {PIOS_GPIO_OUT_0_GPIO_CLK, PIOS_GPIO_OUT_1_GPIO_CLK, PIOS_GPIO_OUT_2_GPIO_CLK, PIOS_GPIO_OUT_3_GPIO_CLK, PIOS_GPIO_OUT_4_GPIO_CLK, PIOS_GPIO_OUT_5_GPIO_CLK, PIOS_GPIO_OUT_6_GPIO_CLK, PIOS_GPIO_OUT_7_GPIO_CLK} - -#define SERIAL_RTS_ENABLE PIOS_GPIO_Enable(0) -#define SERIAL_RTS_SET PIOS_GPIO_Off(0) -#define SERIAL_RTS_CLEAR PIOS_GPIO_On(0) - -#define RF_CS_ENABLE PIOS_GPIO_Enable(1) -#define RF_CS_HIGH PIOS_GPIO_Off(1) -#define RF_CS_LOW PIOS_GPIO_On(1) - -#define PPM_OUT_PIN PIOS_GPIO_OUT_2_PIN -#define PPM_OUT_PORT PIOS_GPIO_OUT_2_PORT -#define PPM_OUT_ENABLE PIOS_GPIO_Enable(2) -#define PPM_OUT_HIGH PIOS_GPIO_Off(2) -#define PPM_OUT_LOW PIOS_GPIO_On(2) - -#define SPARE1_ENABLE PIOS_GPIO_Enable(3) -#define SPARE1_HIGH PIOS_GPIO_Off(3) -#define SPARE1_LOW PIOS_GPIO_On(3) - -#define SPARE2_ENABLE PIOS_GPIO_Enable(4) -#define SPARE2_HIGH PIOS_GPIO_Off(4) -#define SPARE2_LOW PIOS_GPIO_On(4) - -#define SPARE3_ENABLE PIOS_GPIO_Enable(5) -#define SPARE3_HIGH PIOS_GPIO_Off(5) -#define SPARE3_LOW PIOS_GPIO_On(5) - -#define SPARE4_ENABLE PIOS_GPIO_Enable(6) -#define SPARE4_HIGH PIOS_GPIO_Off(6) -#define SPARE4_LOW PIOS_GPIO_On(6) - -#define SPARE5_ENABLE PIOS_GPIO_Enable(7) -#define SPARE5_HIGH PIOS_GPIO_Off(7) -#define SPARE5_LOW PIOS_GPIO_On(7) - -// ***************************************************************** -// GPIO input pins - -// GPIO_Mode_AIN Analog Input -// GPIO_Mode_IN_FLOATING Input Floating -// GPIO_Mode_IPD Input Pull-Down -// GPIO_Mode_IPU Input Pull-up - -// API mode line -#define GPIO_IN_0_PORT GPIOB -#define GPIO_IN_0_PIN GPIO_Pin_13 -#define GPIO_IN_0_MODE GPIO_Mode_IPU - -// Serial port CTS line -#define GPIO_IN_1_PORT GPIOB -#define GPIO_IN_1_PIN GPIO_Pin_14 -#define GPIO_IN_1_MODE GPIO_Mode_IPU - -// VBUS sense line -#define GPIO_IN_2_PORT GPIOA -#define GPIO_IN_2_PIN GPIO_Pin_8 -#define GPIO_IN_2_MODE GPIO_Mode_IN_FLOATING - -// 868MHz jumper option -#define GPIO_IN_3_PORT GPIOB -#define GPIO_IN_3_PIN GPIO_Pin_8 -#define GPIO_IN_3_MODE GPIO_Mode_IPU - -// 915MHz jumper option -#define GPIO_IN_4_PORT GPIOB -#define GPIO_IN_4_PIN GPIO_Pin_9 -#define GPIO_IN_4_MODE GPIO_Mode_IPU - -// RF INT line -#define GPIO_IN_5_PORT GPIOA -#define GPIO_IN_5_PIN GPIO_Pin_2 -#define GPIO_IN_5_MODE GPIO_Mode_IN_FLOATING - -// RF misc line -#define GPIO_IN_6_PORT GPIOB -#define GPIO_IN_6_PIN GPIO_Pin_0 -#define GPIO_IN_6_MODE GPIO_Mode_IN_FLOATING - -// PPM IN line -#define PPM_IN_PORT GPIOB -#define PPM_IN_PIN GPIO_Pin_11 -#define PPM_IN_MODE GPIO_Mode_IPD - -#define GPIO_IN_NUM 8 -#define GPIO_IN_PORTS { GPIO_IN_0_PORT, GPIO_IN_1_PORT, GPIO_IN_2_PORT, GPIO_IN_3_PORT, GPIO_IN_4_PORT, GPIO_IN_5_PORT, GPIO_IN_6_PORT, PPM_IN_PORT } -#define GPIO_IN_PINS { GPIO_IN_0_PIN, GPIO_IN_1_PIN, GPIO_IN_2_PIN, GPIO_IN_3_PIN, GPIO_IN_4_PIN, GPIO_IN_5_PIN, GPIO_IN_6_PIN, PPM_IN_PIN } -#define GPIO_IN_MODES { GPIO_IN_0_MODE, GPIO_IN_1_MODE, GPIO_IN_2_MODE, GPIO_IN_3_MODE, GPIO_IN_4_MODE, GPIO_IN_5_MODE, GPIO_IN_6_MODE, PPM_IN_MODE } - -#define API_MODE_PIN 0 -#define SERIAL_CTS_PIN 1 -#define VBUS_SENSE_PIN 2 -#define _868MHz_PIN 3 -#define _915MHz_PIN 4 -#define RF_INT_PIN 5 -#define RF_MISC_PIN 6 - -// ***************************************************************** +//------------------------- // USB +//------------------------- +#define PIOS_USB_HID_MAX_DEVS 1 +#define PIOS_USB_ENABLED 1 +#define PIOS_USB_HID_MAX_DEVS 1 +#define PIOS_USB_MAX_DEVS 1 +#define PIOS_USB_DETECT_GPIO_PORT GPIOC +#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15 +#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line15 -#if defined(PIOS_INCLUDE_USB_HID) - #define PIOS_USB_ENABLED 1 - #define PIOS_USB_MAX_DEVS 1 - #define PIOS_USB_DETECT_GPIO_PORT GPIO_IN_2_PORT - #define PIOS_USB_DETECT_GPIO_PIN GPIO_IN_2_PIN - #define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4 - #define PIOS_IRQ_USB_PRIORITY 8 -#endif -#define PIOS_USB_HID_MAX_DEVS 1 - -// ***************************************************************** +//------------------------- // RFM22 +//------------------------- -//#define RFM22_EXT_INT_USE - -#define RFM22_PIOS_SPI PIOS_SPI_PORT // SPIx +extern uint32_t pios_rfm22b_id; +#define RFM22_EXT_INT_USE +#define RFM22_PIOS_SPI PIOS_SPI_PORT // SPIx #if defined(RFM22_EXT_INT_USE) - #define RFM22_EXT_INT_PORT_SOURCE GPIO_PortSourceGPIOA - #define RFM22_EXT_INT_PIN_SOURCE GPIO_PinSource2 - - #define RFM22_EXT_INT_LINE EXTI_Line2 - #define RFM22_EXT_INT_IRQn EXTI2_IRQn - #define RFM22_EXT_INT_FUNC EXTI2_IRQHandler - - #define RFM22_EXT_INT_PRIORITY 1 +#define PIOS_RFM22_EXTI_GPIO_PORT GPIOA +#define PIOS_RFM22_EXTI_GPIO_PIN GPIO_Pin_2 +#define PIOS_RFM22_EXTI_PORT_SOURCE GPIO_PortSourceGPIOA +#define PIOS_RFM22_EXTI_PIN_SOURCE GPIO_PinSource2 +#define PIOS_RFM22_EXTI_CLK RCC_APB2Periph_GPIOA +#define PIOS_RFM22_EXTI_LINE EXTI_Line2 +#define PIOS_RFM22_EXTI_IRQn EXTI2_IRQn +#define PIOS_RFM22_EXTI_PRIO PIOS_IRQ_PRIO_LOW #endif -// ***************************************************************** +//------------------------- +// Packet Handler +//------------------------- -#endif /* PIOS_BOARD_H */ +uint32_t pios_packet_handler; +#define PIOS_INCLUDE_PACKET_HANDLER +#define PIOS_PH_MAX_PACKET 255 +#define PIOS_PH_WIN_SIZE 3 +#define PIOS_PH_MAX_CONNECTIONS 1 + +//------------------------- +// Reed-Solomon ECC +//------------------------- + +#define RS_ECC_NPARITY 4 + +//------------------------- +// Flash EEPROM Emulation +//------------------------- + +#define PIOS_FLASH_SIZE 0x20000 +#define PIOS_FLASH_EEPROM_START_ADDR 0x08000000 +#define PIOS_FLASH_PAGE_SIZE 1024 +#define PIOS_FLASH_EEPROM_ADDR (PIOS_FLASH_EEPROM_START_ADDR + PIOS_FLASH_SIZE - PIOS_FLASH_PAGE_SIZE) +#define PIOS_FLASH_EEPROM_LEN PIOS_FLASH_PAGE_SIZE + +#endif /* STM32103CB_PIPXTREME_H_ */ diff --git a/flight/PiOS/Boards/STM3210E_INS.h b/flight/PiOS/Boards/STM32F4xx_Revolution.h similarity index 53% rename from flight/PiOS/Boards/STM3210E_INS.h rename to flight/PiOS/Boards/STM32F4xx_Revolution.h index 77283a5e4..88e636390 100644 --- a/flight/PiOS/Boards/STM3210E_INS.h +++ b/flight/PiOS/Boards/STM32F4xx_Revolution.h @@ -5,8 +5,7 @@ * @addtogroup OpenPilotCore OpenPilot Core * @{ * @file pios_board.h - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. * @see The GNU Public License (GPL) Version 3 * @@ -31,7 +30,7 @@ #ifndef STM3210E_INS_H_ #define STM3210E_INS_H_ - +#include //------------------------ // Timers and Channels Used @@ -69,10 +68,11 @@ TIM8 | | | | //------------------------ // BOOTLOADER_SETTINGS //------------------------ -#define BOARD_READABLE TRUE -#define BOARD_WRITABLE TRUE +#define BOARD_READABLE true +#define BOARD_WRITABLE true #define MAX_DEL_RETRYS 3 + //------------------------ // PIOS_LED //------------------------ @@ -83,63 +83,94 @@ TIM8 | | | | // PIOS_SPI // See also pios_board.c //------------------------ -#define PIOS_SPI_MAX_DEVS 2 +#define PIOS_SPI_MAX_DEVS 3 + +//------------------------ +// PIOS_WDG +//------------------------ +#define PIOS_WATCHDOG_TIMEOUT 250 +#define PIOS_WDG_REGISTER RTC_BKP_DR4 +#define PIOS_WDG_ACTUATOR 0x0001 +#define PIOS_WDG_STABILIZATION 0x0002 +#define PIOS_WDG_ATTITUDE 0x0004 +#define PIOS_WDG_MANUAL 0x0008 +#define PIOS_WDG_SENSORS 0x0010 //------------------------ // PIOS_I2C // See also pios_board.c //------------------------ #define PIOS_I2C_MAX_DEVS 3 -extern uint32_t pios_i2c_pres_mag_adapter_id; -#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_pres_mag_adapter_id) -#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_pres_mag_adapter_id) -extern uint32_t pios_i2c_gyro_adapter_id; -#define PIOS_I2C_GYRO_ADAPTER (pios_i2c_gyro_adapter_id) - -//------------------------ -// PIOS_BMP085 -//------------------------ -#define PIOS_BMP085_HAS_GPIOS -#define PIOS_BMP085_EOC_GPIO_PORT GPIOC -#define PIOS_BMP085_EOC_GPIO_PIN GPIO_Pin_2 -#define PIOS_BMP085_EOC_PORT_SOURCE GPIO_PortSourceGPIOC -#define PIOS_BMP085_EOC_PIN_SOURCE GPIO_PinSource2 -#define PIOS_BMP085_EOC_CLK RCC_APB2Periph_GPIOC -#define PIOS_BMP085_EOC_EXTI_LINE EXTI_Line2 -#define PIOS_BMP085_EOC_IRQn EXTI15_10_IRQn -#define PIOS_BMP085_EOC_PRIO PIOS_IRQ_PRIO_LOW -#define PIOS_BMP085_XCLR_GPIO_PORT GPIOC -#define PIOS_BMP085_XCLR_GPIO_PIN GPIO_Pin_1 -#define PIOS_BMP085_OVERSAMPLING 3 +extern uint32_t pios_i2c_mag_adapter_id; +#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_adapter_id) //------------------------- // PIOS_USART // // See also pios_board.c //------------------------- -#define PIOS_USART_MAX_DEVS 2 +#define PIOS_USART_MAX_DEVS 5 //------------------------- // PIOS_COM // // See also pios_board.c //------------------------- -#define PIOS_COM_MAX_DEVS 2 - +#define PIOS_COM_MAX_DEVS 4 +extern uint32_t pios_com_telem_rf_id; extern uint32_t pios_com_gps_id; -#define PIOS_COM_GPS (pios_com_gps_id) - -#ifdef PIOS_ENABLE_AUX_UART extern uint32_t pios_com_aux_id; +extern uint32_t pios_com_telem_usb_id; +extern uint32_t pios_com_bridge_id; +extern uint32_t pios_com_vcp_id; #define PIOS_COM_AUX (pios_com_aux_id) +#define PIOS_COM_GPS (pios_com_gps_id) +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) +#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) +#define PIOS_COM_BRIDGE (pios_com_bridge_id) +#define PIOS_COM_VCP (pios_com_vcp_id) #define PIOS_COM_DEBUG PIOS_COM_AUX -#endif + +//------------------------ +// TELEMETRY +//------------------------ +#define TELEM_QUEUE_SIZE 20 +#define PIOS_TELEM_STACK_SIZE 624 //------------------------- // System Settings +// +// See also System_stm32f4xx.c //------------------------- -#define PIOS_MASTER_CLOCK 72000000 -#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) +//These macros are deprecated +//please use PIOS_PERIPHERAL_APBx_CLOCK According to the table below +//#define PIOS_MASTER_CLOCK +//#define PIOS_PERIPHERAL_CLOCK +//#define PIOS_PERIPHERAL_CLOCK + +#define PIOS_SYSCLK 168000000 +// Peripherals that belongs to APB1 are: +// DAC |PWR |CAN1,2 +// I2C1,2,3 |UART4,5 |USART3,2 +// I2S3Ext |SPI3/I2S3 |SPI2/I2S2 +// I2S2Ext |IWDG |WWDG +// RTC/BKP reg +// TIM2,3,4,5,6,7,12,13,14 + +// Calculated as SYSCLK / APBPresc * (APBPre == 1 ? 1 : 2) +// Default APB1 Prescaler = 4 +#define PIOS_PERIPHERAL_APB1_CLOCK (PIOS_SYSCLK / 2) + +// Peripherals belonging to APB2 +// SDIO |EXTI |SYSCFG |SPI1 +// ADC1,2,3 +// USART1,6 +// TIM1,8,9,10,11 +// +// Default APB2 Prescaler = 2 +// +#define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK + //------------------------- // Interrupt Priorities @@ -149,54 +180,65 @@ extern uint32_t pios_com_aux_id; #define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... #define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... +//------------------------ +// PIOS_RCVR +// See also pios_board.c +//------------------------ +#define PIOS_RCVR_MAX_DEVS 3 +#define PIOS_RCVR_MAX_CHANNELS 12 + +//------------------------- +// Receiver PPM input +//------------------------- +#define PIOS_PPM_MAX_DEVS 1 +#define PIOS_PPM_NUM_INPUTS 12 + +//------------------------- +// Receiver PWM input +//------------------------- +#define PIOS_PWM_MAX_DEVS 1 +#define PIOS_PWM_NUM_INPUTS 8 + +//------------------------- +// Receiver SPEKTRUM input +//------------------------- +#define PIOS_SPEKTRUM_MAX_DEVS 2 +#define PIOS_SPEKTRUM_NUM_INPUTS 12 + +//------------------------- +// Receiver S.Bus input +//------------------------- +#define PIOS_SBUS_MAX_DEVS 1 +#define PIOS_SBUS_NUM_INPUTS (16+2) + +//------------------------- +// Receiver DSM input +//------------------------- +#define PIOS_DSM_MAX_DEVS 2 +#define PIOS_DSM_NUM_INPUTS 12 + +//------------------------- +// Servo outputs +//------------------------- +#define PIOS_SERVO_UPDATE_HZ 50 +#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ + +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 6 + //------------------------- // ADC // None. //------------------------- - //------------------------- -// GPIO -// Not used, but pios_gpio.c expects something +// USB //------------------------- -#define PIOS_GPIO_1_PORT GPIOA -#define PIOS_GPIO_1_PIN GPIO_Pin_1 -#define PIOS_GPIO_1_GPIO_CLK RCC_APB2Periph_GPIOA - -#define PIOS_GPIO_PORTS { PIOS_GPIO_1_PORT } -#define PIOS_GPIO_PINS { PIOS_GPIO_1_PIN } -#define PIOS_GPIO_CLKS { PIOS_GPIO_1_GPIO_CLK } -#define PIOS_GPIO_NUM 1 - -#define PIOS_BMA_ENABLE PIOS_SPI_RC_PinSet(PIOS_SPI_ACCEL,0) -#define PIOS_BMA_DISABLE PIOS_SPI_RC_PinSet(PIOS_SPI_ACCEL,1) - -//------------------------ -// PIOS_HMC5883 -//------------------------ -#define PIOS_HMC5883_DRDY_GPIO_PORT GPIOB -#define PIOS_HMC5883_DRDY_GPIO_PIN GPIO_Pin_8 -#define PIOS_HMC5883_DRDY_PORT_SOURCE GPIO_PortSourceGPIOB -#define PIOS_HMC5883_DRDY_PIN_SOURCE GPIO_PinSource8 -#define PIOS_HMC5883_DRDY_CLK RCC_APB2Periph_GPIOB -#define PIOS_HMC5883_DRDY_EXTI_LINE EXTI_Line8 -#define PIOS_HMC5883_DRDY_IRQn EXTI9_5_IRQn -#define PIOS_HMC5883_DRDY_PRIO PIOS_IRQ_PRIO_LOW - -//------------------------ -// PIOS_IMU3000 -//------------------------ -#define PIOS_IMU3000_INT_GPIO_PORT GPIOB -#define PIOS_IMU3000_INT_GPIO_PIN GPIO_Pin_1 -#define PIOS_IMU3000_INT_PORT_SOURCE GPIO_PortSourceGPIOB -#define PIOS_IMU3000_INT_PIN_SOURCE GPIO_PinSource1 -#define PIOS_IMU3000_INT_CLK RCC_APB2Periph_GPIOB -#define PIOS_IMU3000_INT_EXTI_LINE EXTI_Line1 -#define PIOS_IMU3000_INT_IRQn EXTI1_IRQn -#define PIOS_IMU3000_INT_PRIO PIOS_IRQ_PRIO_HIGH - - - +#define PIOS_USB_MAX_DEVS 1 +#define PIOS_USB_ENABLED 1 /* Should remove all references to this */ +#define PIOS_USB_HID_MAX_DEVS 1 #endif /* STM3210E_INS_H_ */ /** diff --git a/flight/PiOS/Boards/pios_board.h b/flight/PiOS/Boards/pios_board.h index b352a7827..1b2588bc5 100644 --- a/flight/PiOS/Boards/pios_board.h +++ b/flight/PiOS/Boards/pios_board.h @@ -9,8 +9,10 @@ #include "STM32103CB_PIPXTREME_Rev1.h" #elif USE_STM32103CB_CC_Rev1 #include "STM32103CB_CC_Rev1.h" -#elif USE_STM3210E_INS -#include "STM3210E_INS.h" +#elif USE_STM32F2xx_INS +#include "STM32F2xx_INS.h" +#elif USE_STM32F4xx_OP +#include "STM32F4xx_Revolution.h" #else #error Board definition has not been provided. #endif diff --git a/flight/PiOS/Common/Libraries/CMSIS2/Include/arm_common_tables.h b/flight/PiOS/Common/Libraries/CMSIS2/Include/arm_common_tables.h new file mode 100644 index 000000000..7245c4f12 --- /dev/null +++ b/flight/PiOS/Common/Libraries/CMSIS2/Include/arm_common_tables.h @@ -0,0 +1,35 @@ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 11. November 2010 +* $Revision: V1.0.2 +* +* Project: CMSIS DSP Library +* Title: arm_common_tables.h +* +* Description: This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#ifndef _ARM_COMMON_TABLES_H +#define _ARM_COMMON_TABLES_H + +#include "arm_math.h" + +extern uint16_t armBitRevTable[256]; +extern q15_t armRecipTableQ15[64]; +extern q31_t armRecipTableQ31[64]; +extern const q31_t realCoefAQ31[1024]; +extern const q31_t realCoefBQ31[1024]; + +#endif /* ARM_COMMON_TABLES_H */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/Include/arm_math.h b/flight/PiOS/Common/Libraries/CMSIS2/Include/arm_math.h new file mode 100644 index 000000000..ffa03b6fd --- /dev/null +++ b/flight/PiOS/Common/Libraries/CMSIS2/Include/arm_math.h @@ -0,0 +1,7051 @@ +/* ---------------------------------------------------------------------- + * Copyright (C) 2010 ARM Limited. All rights reserved. + * + * $Date: 15. July 2011 + * $Revision: V1.0.10 + * + * Project: CMSIS DSP Library + * Title: arm_math.h + * + * Description: Public header file for CMSIS DSP Library + * + * Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 + * + * Version 1.0.10 2011/7/15 + * Big Endian support added and Merged M0 and M3/M4 Source code. + * + * Version 1.0.3 2010/11/29 + * Re-organized the CMSIS folders and updated documentation. + * + * Version 1.0.2 2010/11/11 + * Documentation updated. + * + * Version 1.0.1 2010/10/05 + * Production release and review comments incorporated. + * + * Version 1.0.0 2010/09/20 + * Production release and review comments incorporated. + * -------------------------------------------------------------------- */ + +/** + \mainpage CMSIS DSP Software Library + * + * Introduction + * + * This user manual describes the CMSIS DSP software library, + * a suite of common signal processing functions for use on Cortex-M processor based devices. + * + * The library is divided into a number of modules each covering a specific category: + * - Basic math functions + * - Fast math functions + * - Complex math functions + * - Filters + * - Matrix functions + * - Transforms + * - Motor control functions + * - Statistical functions + * - Support functions + * - Interpolation functions + * + * The library has separate functions for operating on 8-bit integers, 16-bit integers, + * 32-bit integer and 32-bit floating-point values. + * + * Processor Support + * + * The library is completely written in C and is fully CMSIS compliant. + * High performance is achieved through maximum use of Cortex-M4 intrinsics. + * + * The supplied library source code also builds and runs on the Cortex-M3 and Cortex-M0 processor, + * with the DSP intrinsics being emulated through software. + * + * + * Toolchain Support + * + * The library has been developed and tested with MDK-ARM version 4.21. + * The library is being tested in GCC and IAR toolchains and updates on this activity will be made available shortly. + * + * Using the Library + * + * The library installer contains prebuilt versions of the libraries in the Lib folder. + * - arm_cortexM4lf_math.lib (Little endian and Floating Point Unit on Cortex-M4) + * - arm_cortexM4bf_math.lib (Big endian and Floating Point Unit on Cortex-M4) + * - arm_cortexM4l_math.lib (Little endian on Cortex-M4) + * - arm_cortexM4b_math.lib (Big endian on Cortex-M4) + * - arm_cortexM3l_math.lib (Little endian on Cortex-M3) + * - arm_cortexM3b_math.lib (Big endian on Cortex-M3) + * - arm_cortexM0l_math.lib (Little endian on Cortex-M0) + * - arm_cortexM0b_math.lib (Big endian on Cortex-M3) + * + * The library functions are declared in the public file arm_math.h which is placed in the Include folder. + * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single + * public header file arm_math.h for Cortex-M4/M3/M0 with little endian and big endian. Same header file will be used for floating point unit(FPU) variants. + * Define the appropriate pre processor MACRO ARM_MATH_CM4 or ARM_MATH_CM3 or + * ARM_MATH_CM0 depending on the target processor in the application. + * + * Examples + * + * The library ships with a number of examples which demonstrate how to use the library functions. + * + * Building the Library + * + * The library installer contains project files to re build libraries on MDK Tool chain in the CMSIS\DSP_Lib\Source\ARM folder. + * - arm_cortexM0b_math.uvproj + * - arm_cortexM0l_math.uvproj + * - arm_cortexM3b_math.uvproj + * - arm_cortexM3l_math.uvproj + * - arm_cortexM4b_math.uvproj + * - arm_cortexM4l_math.uvproj + * - arm_cortexM4bf_math.uvproj + * - arm_cortexM4lf_math.uvproj + * + * Each library project have differant pre-processor macros. + * + * ARM_MATH_CMx: + * Define macro ARM_MATH_CM4 for building the library on Cortex-M4 target, ARM_MATH_CM3 for building library on Cortex-M3 target + * and ARM_MATH_CM0 for building library on cortex-M0 target. + * + * ARM_MATH_BIG_ENDIAN: + * Define macro ARM_MATH_BIG_ENDIAN to build the library for big endian targets. By default library builds for little endian targets. + * + * ARM_MATH_MATRIX_CHECK: + * Define macro for checking on the input and output sizes of matrices + * + * ARM_MATH_ROUNDING: + * Define macro for rounding on support functions + * + * __FPU_PRESENT: + * Initialize macro __FPU_PRESENT = 1 when building on FPU supported Targets. Enable this macro for M4bf and M4lf libraries + * + * + * The project can be built by opening the appropriate project in MDK-ARM 4.21 chain and defining the optional pre processor MACROs detailed above. + * + * Copyright Notice + * + * Copyright (C) 2010 ARM Limited. All rights reserved. + */ + + +/** + * @defgroup groupMath Basic Math Functions + */ + +/** + * @defgroup groupFastMath Fast Math Functions + * This set of functions provides a fast approximation to sine, cosine, and square root. + * As compared to most of the other functions in the CMSIS math library, the fast math functions + * operate on individual values and not arrays. + * There are separate functions for Q15, Q31, and floating-point data. + * + */ + +/** + * @defgroup groupCmplxMath Complex Math Functions + * This set of functions operates on complex data vectors. + * The data in the complex arrays is stored in an interleaved fashion + * (real, imag, real, imag, ...). + * In the API functions, the number of samples in a complex array refers + * to the number of complex values; the array contains twice this number of + * real values. + */ + +/** + * @defgroup groupFilters Filtering Functions + */ + +/** + * @defgroup groupMatrix Matrix Functions + * + * This set of functions provides basic matrix math operations. + * The functions operate on matrix data structures. For example, + * the type + * definition for the floating-point matrix structure is shown + * below: + *
+ *     typedef struct
+ *     {
+ *       uint16_t numRows;     // number of rows of the matrix.
+ *       uint16_t numCols;     // number of columns of the matrix.
+ *       float32_t *pData;     // points to the data of the matrix.
+ *     } arm_matrix_instance_f32;
+ * 
+ * There are similar definitions for Q15 and Q31 data types. + * + * The structure specifies the size of the matrix and then points to + * an array of data. The array is of size numRows X numCols + * and the values are arranged in row order. That is, the + * matrix element (i, j) is stored at: + *
+ *     pData[i*numCols + j]
+ * 
+ * + * \par Init Functions + * There is an associated initialization function for each type of matrix + * data structure. + * The initialization function sets the values of the internal structure fields. + * Refer to the function arm_mat_init_f32(), arm_mat_init_q31() + * and arm_mat_init_q15() for floating-point, Q31 and Q15 types, respectively. + * + * \par + * Use of the initialization function is optional. However, if initialization function is used + * then the instance structure cannot be placed into a const data section. + * To place the instance structure in a const data + * section, manually initialize the data structure. For example: + *
+ * arm_matrix_instance_f32 S = {nRows, nColumns, pData};
+ * arm_matrix_instance_q31 S = {nRows, nColumns, pData};
+ * arm_matrix_instance_q15 S = {nRows, nColumns, pData};
+ * 
+ * where nRows specifies the number of rows, nColumns + * specifies the number of columns, and pData points to the + * data array. + * + * \par Size Checking + * By default all of the matrix functions perform size checking on the input and + * output matrices. For example, the matrix addition function verifies that the + * two input matrices and the output matrix all have the same number of rows and + * columns. If the size check fails the functions return: + *
+ *     ARM_MATH_SIZE_MISMATCH
+ * 
+ * Otherwise the functions return + *
+ *     ARM_MATH_SUCCESS
+ * 
+ * There is some overhead associated with this matrix size checking. + * The matrix size checking is enabled via the #define + *
+ *     ARM_MATH_MATRIX_CHECK
+ * 
+ * within the library project settings. By default this macro is defined + * and size checking is enabled. By changing the project settings and + * undefining this macro size checking is eliminated and the functions + * run a bit faster. With size checking disabled the functions always + * return ARM_MATH_SUCCESS. + */ + +/** + * @defgroup groupTransforms Transform Functions + */ + +/** + * @defgroup groupController Controller Functions + */ + +/** + * @defgroup groupStats Statistics Functions + */ +/** + * @defgroup groupSupport Support Functions + */ + +/** + * @defgroup groupInterpolation Interpolation Functions + * These functions perform 1- and 2-dimensional interpolation of data. + * Linear interpolation is used for 1-dimensional data and + * bilinear interpolation is used for 2-dimensional data. + */ + +/** + * @defgroup groupExamples Examples + */ +#ifndef _ARM_MATH_H +#define _ARM_MATH_H + +#define __CMSIS_GENERIC /* disable NVIC and Systick functions */ + +#if defined (ARM_MATH_CM4) + #include "core_cm4.h" +#elif defined (ARM_MATH_CM3) + #include "core_cm3.h" +#elif defined (ARM_MATH_CM0) + #include "core_cm0.h" +#else +#include "ARMCM4.h" +#warning "Define either ARM_MATH_CM4 OR ARM_MATH_CM3...By Default building on ARM_MATH_CM4....." +#endif + +#undef __CMSIS_GENERIC /* enable NVIC and Systick functions */ +#include "string.h" + #include "math.h" +#ifdef __cplusplus +extern "C" +{ +#endif + + + /** + * @brief Macros required for reciprocal calculation in Normalized LMS + */ + +#define DELTA_Q31 (0x100) +#define DELTA_Q15 0x5 +#define INDEX_MASK 0x0000003F +#define PI 3.14159265358979f + + /** + * @brief Macros required for SINE and COSINE Fast math approximations + */ + +#define TABLE_SIZE 256 +#define TABLE_SPACING_Q31 0x800000 +#define TABLE_SPACING_Q15 0x80 + + /** + * @brief Macros required for SINE and COSINE Controller functions + */ + /* 1.31(q31) Fixed value of 2/360 */ + /* -1 to +1 is divided into 360 values so total spacing is (2/360) */ +#define INPUT_SPACING 0xB60B61 + + + /** + * @brief Error status returned by some functions in the library. + */ + + typedef enum + { + ARM_MATH_SUCCESS = 0, /**< No error */ + ARM_MATH_ARGUMENT_ERROR = -1, /**< One or more arguments are incorrect */ + ARM_MATH_LENGTH_ERROR = -2, /**< Length of data buffer is incorrect */ + ARM_MATH_SIZE_MISMATCH = -3, /**< Size of matrices is not compatible with the operation. */ + ARM_MATH_NANINF = -4, /**< Not-a-number (NaN) or infinity is generated */ + ARM_MATH_SINGULAR = -5, /**< Generated by matrix inversion if the input matrix is singular and cannot be inverted. */ + ARM_MATH_TEST_FAILURE = -6 /**< Test Failed */ + } arm_status; + + /** + * @brief 8-bit fractional data type in 1.7 format. + */ + typedef int8_t q7_t; + + /** + * @brief 16-bit fractional data type in 1.15 format. + */ + typedef int16_t q15_t; + + /** + * @brief 32-bit fractional data type in 1.31 format. + */ + typedef int32_t q31_t; + + /** + * @brief 64-bit fractional data type in 1.63 format. + */ + typedef int64_t q63_t; + + /** + * @brief 32-bit floating-point type definition. + */ + typedef float float32_t; + + /** + * @brief 64-bit floating-point type definition. + */ + typedef double float64_t; + + /** + * @brief definition to read/write two 16 bit values. + */ +#define __SIMD32(addr) (*(int32_t **) & (addr)) + +#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0) + /** + * @brief definition to pack two 16 bit values. + */ +#define __PKHBT(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0x0000FFFF) | \ + (((int32_t)(ARG2) << ARG3) & (int32_t)0xFFFF0000) ) + +#endif + + + /** + * @brief definition to pack four 8 bit values. + */ +#ifndef ARM_MATH_BIG_ENDIAN + +#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v0) << 0) & (int32_t)0x000000FF) | \ + (((int32_t)(v1) << 8) & (int32_t)0x0000FF00) | \ + (((int32_t)(v2) << 16) & (int32_t)0x00FF0000) | \ + (((int32_t)(v3) << 24) & (int32_t)0xFF000000) ) +#else + +#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v3) << 0) & (int32_t)0x000000FF) | \ + (((int32_t)(v2) << 8) & (int32_t)0x0000FF00) | \ + (((int32_t)(v1) << 16) & (int32_t)0x00FF0000) | \ + (((int32_t)(v0) << 24) & (int32_t)0xFF000000) ) + +#endif + + + /** + * @brief Clips Q63 to Q31 values. + */ + static __INLINE q31_t clip_q63_to_q31( + q63_t x) + { + return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? + ((0x7FFFFFFF ^ ((q31_t) (x >> 63)))) : (q31_t) x; + } + + /** + * @brief Clips Q63 to Q15 values. + */ + static __INLINE q15_t clip_q63_to_q15( + q63_t x) + { + return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? + ((0x7FFF ^ ((q15_t) (x >> 63)))) : (q15_t) (x >> 15); + } + + /** + * @brief Clips Q31 to Q7 values. + */ + static __INLINE q7_t clip_q31_to_q7( + q31_t x) + { + return ((q31_t) (x >> 24) != ((q31_t) x >> 23)) ? + ((0x7F ^ ((q7_t) (x >> 31)))) : (q7_t) x; + } + + /** + * @brief Clips Q31 to Q15 values. + */ + static __INLINE q15_t clip_q31_to_q15( + q31_t x) + { + return ((q31_t) (x >> 16) != ((q31_t) x >> 15)) ? + ((0x7FFF ^ ((q15_t) (x >> 31)))) : (q15_t) x; + } + + /** + * @brief Multiplies 32 X 64 and returns 32 bit result in 2.30 format. + */ + + static __INLINE q63_t mult32x64( + q63_t x, + q31_t y) + { + return ((((q63_t) (x & 0x00000000FFFFFFFF) * y) >> 32) + + (((q63_t) (x >> 32) * y))); + } + + +#if defined (ARM_MATH_CM0) && defined ( __CC_ARM ) +#define __CLZ __clz +#endif + +#if defined (ARM_MATH_CM0) && ((defined (__ICCARM__)) ||(defined (__GNUC__)) || defined (__TASKING__) ) + + static __INLINE uint32_t __CLZ(q31_t data); + + + static __INLINE uint32_t __CLZ(q31_t data) + { + uint32_t count = 0; + uint32_t mask = 0x80000000; + + while((data & mask) == 0) + { + count += 1u; + mask = mask >> 1u; + } + + return(count); + + } + +#endif + + /** + * @brief Function to Calculates 1/in(reciprocal) value of Q31 Data type. + */ + + static __INLINE uint32_t arm_recip_q31( + q31_t in, + q31_t * dst, + q31_t * pRecipTable) + { + + uint32_t out, tempVal; + uint32_t index, i; + uint32_t signBits; + + if(in > 0) + { + signBits = __CLZ(in) - 1; + } + else + { + signBits = __CLZ(-in) - 1; + } + + /* Convert input sample to 1.31 format */ + in = in << signBits; + + /* calculation of index for initial approximated Val */ + index = (uint32_t) (in >> 24u); + index = (index & INDEX_MASK); + + /* 1.31 with exp 1 */ + out = pRecipTable[index]; + + /* calculation of reciprocal value */ + /* running approximation for two iterations */ + for (i = 0u; i < 2u; i++) + { + tempVal = (q31_t) (((q63_t) in * out) >> 31u); + tempVal = 0x7FFFFFFF - tempVal; + /* 1.31 with exp 1 */ + //out = (q31_t) (((q63_t) out * tempVal) >> 30u); + out = (q31_t) clip_q63_to_q31(((q63_t) out * tempVal) >> 30u); + } + + /* write output */ + *dst = out; + + /* return num of signbits of out = 1/in value */ + return (signBits + 1u); + + } + + /** + * @brief Function to Calculates 1/in(reciprocal) value of Q15 Data type. + */ + static __INLINE uint32_t arm_recip_q15( + q15_t in, + q15_t * dst, + q15_t * pRecipTable) + { + + uint32_t out = 0, tempVal = 0; + uint32_t index = 0, i = 0; + uint32_t signBits = 0; + + if(in > 0) + { + signBits = __CLZ(in) - 17; + } + else + { + signBits = __CLZ(-in) - 17; + } + + /* Convert input sample to 1.15 format */ + in = in << signBits; + + /* calculation of index for initial approximated Val */ + index = in >> 8; + index = (index & INDEX_MASK); + + /* 1.15 with exp 1 */ + out = pRecipTable[index]; + + /* calculation of reciprocal value */ + /* running approximation for two iterations */ + for (i = 0; i < 2; i++) + { + tempVal = (q15_t) (((q31_t) in * out) >> 15); + tempVal = 0x7FFF - tempVal; + /* 1.15 with exp 1 */ + out = (q15_t) (((q31_t) out * tempVal) >> 14); + } + + /* write output */ + *dst = out; + + /* return num of signbits of out = 1/in value */ + return (signBits + 1); + + } + + + /* + * @brief C custom defined intrinisic function for only M0 processors + */ +#if defined(ARM_MATH_CM0) + + static __INLINE q31_t __SSAT( + q31_t x, + uint32_t y) + { + int32_t posMax, negMin; + uint32_t i; + + posMax = 1; + for (i = 0; i < (y - 1); i++) + { + posMax = posMax * 2; + } + + if(x > 0) + { + posMax = (posMax - 1); + + if(x > posMax) + { + x = posMax; + } + } + else + { + negMin = -posMax; + + if(x < negMin) + { + x = negMin; + } + } + return (x); + + + } + +#endif /* end of ARM_MATH_CM0 */ + + + + /* + * @brief C custom defined intrinsic function for M3 and M0 processors + */ +#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0) + + /* + * @brief C custom defined QADD8 for M3 and M0 processors + */ + static __INLINE q31_t __QADD8( + q31_t x, + q31_t y) + { + + q31_t sum; + q7_t r, s, t, u; + + r = (char) x; + s = (char) y; + + r = __SSAT((q31_t) (r + s), 8); + s = __SSAT(((q31_t) (((x << 16) >> 24) + ((y << 16) >> 24))), 8); + t = __SSAT(((q31_t) (((x << 8) >> 24) + ((y << 8) >> 24))), 8); + u = __SSAT(((q31_t) ((x >> 24) + (y >> 24))), 8); + + sum = (((q31_t) u << 24) & 0xFF000000) | (((q31_t) t << 16) & 0x00FF0000) | + (((q31_t) s << 8) & 0x0000FF00) | (r & 0x000000FF); + + return sum; + + } + + /* + * @brief C custom defined QSUB8 for M3 and M0 processors + */ + static __INLINE q31_t __QSUB8( + q31_t x, + q31_t y) + { + + q31_t sum; + q31_t r, s, t, u; + + r = (char) x; + s = (char) y; + + r = __SSAT((r - s), 8); + s = __SSAT(((q31_t) (((x << 16) >> 24) - ((y << 16) >> 24))), 8) << 8; + t = __SSAT(((q31_t) (((x << 8) >> 24) - ((y << 8) >> 24))), 8) << 16; + u = __SSAT(((q31_t) ((x >> 24) - (y >> 24))), 8) << 24; + + sum = + (u & 0xFF000000) | (t & 0x00FF0000) | (s & 0x0000FF00) | (r & 0x000000FF); + + return sum; + } + + /* + * @brief C custom defined QADD16 for M3 and M0 processors + */ + + /* + * @brief C custom defined QADD16 for M3 and M0 processors + */ + static __INLINE q31_t __QADD16( + q31_t x, + q31_t y) + { + + q31_t sum; + q31_t r, s; + + r = (short) x; + s = (short) y; + + r = __SSAT(r + s, 16); + s = __SSAT(((q31_t) ((x >> 16) + (y >> 16))), 16) << 16; + + sum = (s & 0xFFFF0000) | (r & 0x0000FFFF); + + return sum; + + } + + /* + * @brief C custom defined SHADD16 for M3 and M0 processors + */ + static __INLINE q31_t __SHADD16( + q31_t x, + q31_t y) + { + + q31_t sum; + q31_t r, s; + + r = (short) x; + s = (short) y; + + r = ((r >> 1) + (s >> 1)); + s = ((q31_t) ((x >> 17) + (y >> 17))) << 16; + + sum = (s & 0xFFFF0000) | (r & 0x0000FFFF); + + return sum; + + } + + /* + * @brief C custom defined QSUB16 for M3 and M0 processors + */ + static __INLINE q31_t __QSUB16( + q31_t x, + q31_t y) + { + + q31_t sum; + q31_t r, s; + + r = (short) x; + s = (short) y; + + r = __SSAT(r - s, 16); + s = __SSAT(((q31_t) ((x >> 16) - (y >> 16))), 16) << 16; + + sum = (s & 0xFFFF0000) | (r & 0x0000FFFF); + + return sum; + } + + /* + * @brief C custom defined SHSUB16 for M3 and M0 processors + */ + static __INLINE q31_t __SHSUB16( + q31_t x, + q31_t y) + { + + q31_t diff; + q31_t r, s; + + r = (short) x; + s = (short) y; + + r = ((r >> 1) - (s >> 1)); + s = (((x >> 17) - (y >> 17)) << 16); + + diff = (s & 0xFFFF0000) | (r & 0x0000FFFF); + + return diff; + } + + /* + * @brief C custom defined QASX for M3 and M0 processors + */ + static __INLINE q31_t __QASX( + q31_t x, + q31_t y) + { + + q31_t sum = 0; + + sum = ((sum + clip_q31_to_q15((q31_t) ((short) (x >> 16) + (short) y))) << 16) + + clip_q31_to_q15((q31_t) ((short) x - (short) (y >> 16))); + + return sum; + } + + /* + * @brief C custom defined SHASX for M3 and M0 processors + */ + static __INLINE q31_t __SHASX( + q31_t x, + q31_t y) + { + + q31_t sum; + q31_t r, s; + + r = (short) x; + s = (short) y; + + r = ((r >> 1) - (y >> 17)); + s = (((x >> 17) + (s >> 1)) << 16); + + sum = (s & 0xFFFF0000) | (r & 0x0000FFFF); + + return sum; + } + + + /* + * @brief C custom defined QSAX for M3 and M0 processors + */ + static __INLINE q31_t __QSAX( + q31_t x, + q31_t y) + { + + q31_t sum = 0; + + sum = ((sum + clip_q31_to_q15((q31_t) ((short) (x >> 16) - (short) y))) << 16) + + clip_q31_to_q15((q31_t) ((short) x + (short) (y >> 16))); + + return sum; + } + + /* + * @brief C custom defined SHSAX for M3 and M0 processors + */ + static __INLINE q31_t __SHSAX( + q31_t x, + q31_t y) + { + + q31_t sum; + q31_t r, s; + + r = (short) x; + s = (short) y; + + r = ((r >> 1) + (y >> 17)); + s = (((x >> 17) - (s >> 1)) << 16); + + sum = (s & 0xFFFF0000) | (r & 0x0000FFFF); + + return sum; + } + + /* + * @brief C custom defined SMUSDX for M3 and M0 processors + */ + static __INLINE q31_t __SMUSDX( + q31_t x, + q31_t y) + { + + return ((q31_t)(((short) x * (short) (y >> 16)) - + ((short) (x >> 16) * (short) y))); + } + + /* + * @brief C custom defined SMUADX for M3 and M0 processors + */ + static __INLINE q31_t __SMUADX( + q31_t x, + q31_t y) + { + + return ((q31_t)(((short) x * (short) (y >> 16)) + + ((short) (x >> 16) * (short) y))); + } + + /* + * @brief C custom defined QADD for M3 and M0 processors + */ + static __INLINE q31_t __QADD( + q31_t x, + q31_t y) + { + return clip_q63_to_q31((q63_t) x + y); + } + + /* + * @brief C custom defined QSUB for M3 and M0 processors + */ + static __INLINE q31_t __QSUB( + q31_t x, + q31_t y) + { + return clip_q63_to_q31((q63_t) x - y); + } + + /* + * @brief C custom defined SMLAD for M3 and M0 processors + */ + static __INLINE q31_t __SMLAD( + q31_t x, + q31_t y, + q31_t sum) + { + + return (sum + ((short) (x >> 16) * (short) (y >> 16)) + + ((short) x * (short) y)); + } + + /* + * @brief C custom defined SMLADX for M3 and M0 processors + */ + static __INLINE q31_t __SMLADX( + q31_t x, + q31_t y, + q31_t sum) + { + + return (sum + ((short) (x >> 16) * (short) (y)) + + ((short) x * (short) (y >> 16))); + } + + /* + * @brief C custom defined SMLSDX for M3 and M0 processors + */ + static __INLINE q31_t __SMLSDX( + q31_t x, + q31_t y, + q31_t sum) + { + + return (sum - ((short) (x >> 16) * (short) (y)) + + ((short) x * (short) (y >> 16))); + } + + /* + * @brief C custom defined SMLALD for M3 and M0 processors + */ + static __INLINE q63_t __SMLALD( + q31_t x, + q31_t y, + q63_t sum) + { + + return (sum + ((short) (x >> 16) * (short) (y >> 16)) + + ((short) x * (short) y)); + } + + /* + * @brief C custom defined SMLALDX for M3 and M0 processors + */ + static __INLINE q63_t __SMLALDX( + q31_t x, + q31_t y, + q63_t sum) + { + + return (sum + ((short) (x >> 16) * (short) y)) + + ((short) x * (short) (y >> 16)); + } + + /* + * @brief C custom defined SMUAD for M3 and M0 processors + */ + static __INLINE q31_t __SMUAD( + q31_t x, + q31_t y) + { + + return (((x >> 16) * (y >> 16)) + + (((x << 16) >> 16) * ((y << 16) >> 16))); + } + + /* + * @brief C custom defined SMUSD for M3 and M0 processors + */ + static __INLINE q31_t __SMUSD( + q31_t x, + q31_t y) + { + + return (-((x >> 16) * (y >> 16)) + + (((x << 16) >> 16) * ((y << 16) >> 16))); + } + + + + +#endif /* (ARM_MATH_CM3) || defined (ARM_MATH_CM0) */ + + + /** + * @brief Instance structure for the Q7 FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + q7_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + } arm_fir_instance_q7; + + /** + * @brief Instance structure for the Q15 FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + } arm_fir_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + } arm_fir_instance_q31; + + /** + * @brief Instance structure for the floating-point FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + } arm_fir_instance_f32; + + + /** + * @brief Processing function for the Q7 FIR filter. + * @param[in] *S points to an instance of the Q7 FIR filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + void arm_fir_q7( + const arm_fir_instance_q7 * S, + q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q7 FIR filter. + * @param[in,out] *S points to an instance of the Q7 FIR structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of samples that are processed. + * @return none + */ + void arm_fir_init_q7( + arm_fir_instance_q7 * S, + uint16_t numTaps, + q7_t * pCoeffs, + q7_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q15 FIR filter. + * @param[in] *S points to an instance of the Q15 FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + void arm_fir_q15( + const arm_fir_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the fast Q15 FIR filter for Cortex-M3 and Cortex-M4. + * @param[in] *S points to an instance of the Q15 FIR filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + void arm_fir_fast_q15( + const arm_fir_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q15 FIR filter. + * @param[in,out] *S points to an instance of the Q15 FIR filter structure. + * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of samples that are processed at a time. + * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_ARGUMENT_ERROR if + * numTaps is not a supported value. + */ + + arm_status arm_fir_init_q15( + arm_fir_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 FIR filter. + * @param[in] *S points to an instance of the Q31 FIR filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + void arm_fir_q31( + const arm_fir_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the fast Q31 FIR filter for Cortex-M3 and Cortex-M4. + * @param[in] *S points to an instance of the Q31 FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + void arm_fir_fast_q31( + const arm_fir_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q31 FIR filter. + * @param[in,out] *S points to an instance of the Q31 FIR structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of samples that are processed at a time. + * @return none. + */ + void arm_fir_init_q31( + arm_fir_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the floating-point FIR filter. + * @param[in] *S points to an instance of the floating-point FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + void arm_fir_f32( + const arm_fir_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point FIR filter. + * @param[in,out] *S points to an instance of the floating-point FIR filter structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of samples that are processed at a time. + * @return none. + */ + void arm_fir_init_f32( + arm_fir_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q15 Biquad cascade filter. + */ + typedef struct + { + int8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + q15_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ + q15_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ + int8_t postShift; /**< Additional shift, in bits, applied to each output sample. */ + + } arm_biquad_casd_df1_inst_q15; + + + /** + * @brief Instance structure for the Q31 Biquad cascade filter. + */ + typedef struct + { + uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + q31_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ + q31_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ + uint8_t postShift; /**< Additional shift, in bits, applied to each output sample. */ + + } arm_biquad_casd_df1_inst_q31; + + /** + * @brief Instance structure for the floating-point Biquad cascade filter. + */ + typedef struct + { + uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + float32_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ + float32_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ + + + } arm_biquad_casd_df1_inst_f32; + + + + /** + * @brief Processing function for the Q15 Biquad cascade filter. + * @param[in] *S points to an instance of the Q15 Biquad cascade structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_biquad_cascade_df1_q15( + const arm_biquad_casd_df1_inst_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q15 Biquad cascade filter. + * @param[in,out] *S points to an instance of the Q15 Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format + * @return none + */ + + void arm_biquad_cascade_df1_init_q15( + arm_biquad_casd_df1_inst_q15 * S, + uint8_t numStages, + q15_t * pCoeffs, + q15_t * pState, + int8_t postShift); + + + /** + * @brief Fast but less precise processing function for the Q15 Biquad cascade filter for Cortex-M3 and Cortex-M4. + * @param[in] *S points to an instance of the Q15 Biquad cascade structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_biquad_cascade_df1_fast_q15( + const arm_biquad_casd_df1_inst_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q31 Biquad cascade filter + * @param[in] *S points to an instance of the Q31 Biquad cascade structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_biquad_cascade_df1_q31( + const arm_biquad_casd_df1_inst_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Fast but less precise processing function for the Q31 Biquad cascade filter for Cortex-M3 and Cortex-M4. + * @param[in] *S points to an instance of the Q31 Biquad cascade structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_biquad_cascade_df1_fast_q31( + const arm_biquad_casd_df1_inst_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q31 Biquad cascade filter. + * @param[in,out] *S points to an instance of the Q31 Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format + * @return none + */ + + void arm_biquad_cascade_df1_init_q31( + arm_biquad_casd_df1_inst_q31 * S, + uint8_t numStages, + q31_t * pCoeffs, + q31_t * pState, + int8_t postShift); + + /** + * @brief Processing function for the floating-point Biquad cascade filter. + * @param[in] *S points to an instance of the floating-point Biquad cascade structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_biquad_cascade_df1_f32( + const arm_biquad_casd_df1_inst_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point Biquad cascade filter. + * @param[in,out] *S points to an instance of the floating-point Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @return none + */ + + void arm_biquad_cascade_df1_init_f32( + arm_biquad_casd_df1_inst_f32 * S, + uint8_t numStages, + float32_t * pCoeffs, + float32_t * pState); + + + /** + * @brief Instance structure for the floating-point matrix structure. + */ + + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + float32_t *pData; /**< points to the data of the matrix. */ + } arm_matrix_instance_f32; + + /** + * @brief Instance structure for the Q15 matrix structure. + */ + + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + q15_t *pData; /**< points to the data of the matrix. */ + + } arm_matrix_instance_q15; + + /** + * @brief Instance structure for the Q31 matrix structure. + */ + + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + q31_t *pData; /**< points to the data of the matrix. */ + + } arm_matrix_instance_q31; + + + + /** + * @brief Floating-point matrix addition. + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_add_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix addition. + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_add_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix addition. + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_add_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + + /** + * @brief Floating-point matrix transpose. + * @param[in] *pSrc points to the input matrix + * @param[out] *pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_trans_f32( + const arm_matrix_instance_f32 * pSrc, + arm_matrix_instance_f32 * pDst); + + + /** + * @brief Q15 matrix transpose. + * @param[in] *pSrc points to the input matrix + * @param[out] *pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_trans_q15( + const arm_matrix_instance_q15 * pSrc, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix transpose. + * @param[in] *pSrc points to the input matrix + * @param[out] *pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_trans_q31( + const arm_matrix_instance_q31 * pSrc, + arm_matrix_instance_q31 * pDst); + + + /** + * @brief Floating-point matrix multiplication + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_mult_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix multiplication + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_mult_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst, + q15_t * pState); + + /** + * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @param[in] *pState points to the array for storing intermediate results + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_mult_fast_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst, + q15_t * pState); + + /** + * @brief Q31 matrix multiplication + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_mult_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_mult_fast_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + + /** + * @brief Floating-point matrix subtraction + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_sub_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix subtraction + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_sub_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix subtraction + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_sub_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point matrix scaling. + * @param[in] *pSrc points to the input matrix + * @param[in] scale scale factor + * @param[out] *pDst points to the output matrix + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_scale_f32( + const arm_matrix_instance_f32 * pSrc, + float32_t scale, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix scaling. + * @param[in] *pSrc points to input matrix + * @param[in] scaleFract fractional portion of the scale factor + * @param[in] shift number of bits to shift the result by + * @param[out] *pDst points to output matrix + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_scale_q15( + const arm_matrix_instance_q15 * pSrc, + q15_t scaleFract, + int32_t shift, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix scaling. + * @param[in] *pSrc points to input matrix + * @param[in] scaleFract fractional portion of the scale factor + * @param[in] shift number of bits to shift the result by + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + arm_status arm_mat_scale_q31( + const arm_matrix_instance_q31 * pSrc, + q31_t scaleFract, + int32_t shift, + arm_matrix_instance_q31 * pDst); + + + /** + * @brief Q31 matrix initialization. + * @param[in,out] *S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] *pData points to the matrix data array. + * @return none + */ + + void arm_mat_init_q31( + arm_matrix_instance_q31 * S, + uint16_t nRows, + uint16_t nColumns, + q31_t *pData); + + /** + * @brief Q15 matrix initialization. + * @param[in,out] *S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] *pData points to the matrix data array. + * @return none + */ + + void arm_mat_init_q15( + arm_matrix_instance_q15 * S, + uint16_t nRows, + uint16_t nColumns, + q15_t *pData); + + /** + * @brief Floating-point matrix initialization. + * @param[in,out] *S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] *pData points to the matrix data array. + * @return none + */ + + void arm_mat_init_f32( + arm_matrix_instance_f32 * S, + uint16_t nRows, + uint16_t nColumns, + float32_t *pData); + + + + /** + * @brief Instance structure for the Q15 PID Control. + */ + typedef struct + { + q15_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ + #ifdef ARM_MATH_CM0 + q15_t A1; + q15_t A2; + #else + q31_t A1; /**< The derived gain A1 = -Kp - 2Kd | Kd.*/ + #endif + q15_t state[3]; /**< The state array of length 3. */ + q15_t Kp; /**< The proportional gain. */ + q15_t Ki; /**< The integral gain. */ + q15_t Kd; /**< The derivative gain. */ + } arm_pid_instance_q15; + + /** + * @brief Instance structure for the Q31 PID Control. + */ + typedef struct + { + q31_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ + q31_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */ + q31_t A2; /**< The derived gain, A2 = Kd . */ + q31_t state[3]; /**< The state array of length 3. */ + q31_t Kp; /**< The proportional gain. */ + q31_t Ki; /**< The integral gain. */ + q31_t Kd; /**< The derivative gain. */ + + } arm_pid_instance_q31; + + /** + * @brief Instance structure for the floating-point PID Control. + */ + typedef struct + { + float32_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ + float32_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */ + float32_t A2; /**< The derived gain, A2 = Kd . */ + float32_t state[3]; /**< The state array of length 3. */ + float32_t Kp; /**< The proportional gain. */ + float32_t Ki; /**< The integral gain. */ + float32_t Kd; /**< The derivative gain. */ + } arm_pid_instance_f32; + + + + /** + * @brief Initialization function for the floating-point PID Control. + * @param[in,out] *S points to an instance of the PID structure. + * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. + * @return none. + */ + void arm_pid_init_f32( + arm_pid_instance_f32 * S, + int32_t resetStateFlag); + + /** + * @brief Reset function for the floating-point PID Control. + * @param[in,out] *S is an instance of the floating-point PID Control structure + * @return none + */ + void arm_pid_reset_f32( + arm_pid_instance_f32 * S); + + + /** + * @brief Initialization function for the Q31 PID Control. + * @param[in,out] *S points to an instance of the Q15 PID structure. + * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. + * @return none. + */ + void arm_pid_init_q31( + arm_pid_instance_q31 * S, + int32_t resetStateFlag); + + + /** + * @brief Reset function for the Q31 PID Control. + * @param[in,out] *S points to an instance of the Q31 PID Control structure + * @return none + */ + + void arm_pid_reset_q31( + arm_pid_instance_q31 * S); + + /** + * @brief Initialization function for the Q15 PID Control. + * @param[in,out] *S points to an instance of the Q15 PID structure. + * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. + * @return none. + */ + void arm_pid_init_q15( + arm_pid_instance_q15 * S, + int32_t resetStateFlag); + + /** + * @brief Reset function for the Q15 PID Control. + * @param[in,out] *S points to an instance of the q15 PID Control structure + * @return none + */ + void arm_pid_reset_q15( + arm_pid_instance_q15 * S); + + + /** + * @brief Instance structure for the floating-point Linear Interpolate function. + */ + typedef struct + { + uint32_t nValues; + float32_t x1; + float32_t xSpacing; + float32_t *pYData; /**< pointer to the table of Y values */ + } arm_linear_interp_instance_f32; + + /** + * @brief Instance structure for the floating-point bilinear interpolation function. + */ + + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + float32_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_f32; + + /** + * @brief Instance structure for the Q31 bilinear interpolation function. + */ + + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + q31_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_q31; + + /** + * @brief Instance structure for the Q15 bilinear interpolation function. + */ + + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + q15_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_q15; + + /** + * @brief Instance structure for the Q15 bilinear interpolation function. + */ + + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + q7_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_q7; + + + /** + * @brief Q7 vector multiplication. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_mult_q7( + q7_t * pSrcA, + q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Q15 vector multiplication. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_mult_q15( + q15_t * pSrcA, + q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Q31 vector multiplication. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_mult_q31( + q31_t * pSrcA, + q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Floating-point vector multiplication. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_mult_f32( + float32_t * pSrcA, + float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q15 CFFT/CIFFT function. + */ + + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + q15_t *pTwiddle; /**< points to the twiddle factor table. */ + uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix4_instance_q15; + + /** + * @brief Instance structure for the Q31 CFFT/CIFFT function. + */ + + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + q31_t *pTwiddle; /**< points to the twiddle factor table. */ + uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix4_instance_q31; + + /** + * @brief Instance structure for the floating-point CFFT/CIFFT function. + */ + + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + float32_t *pTwiddle; /**< points to the twiddle factor table. */ + uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + float32_t onebyfftLen; /**< value of 1/fftLen. */ + } arm_cfft_radix4_instance_f32; + + /** + * @brief Processing function for the Q15 CFFT/CIFFT. + * @param[in] *S points to an instance of the Q15 CFFT/CIFFT structure. + * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. + * @return none. + */ + + void arm_cfft_radix4_q15( + const arm_cfft_radix4_instance_q15 * S, + q15_t * pSrc); + + /** + * @brief Initialization function for the Q15 CFFT/CIFFT. + * @param[in,out] *S points to an instance of the Q15 CFFT/CIFFT structure. + * @param[in] fftLen length of the FFT. + * @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. + * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. + */ + + arm_status arm_cfft_radix4_init_q15( + arm_cfft_radix4_instance_q15 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + /** + * @brief Processing function for the Q31 CFFT/CIFFT. + * @param[in] *S points to an instance of the Q31 CFFT/CIFFT structure. + * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. + * @return none. + */ + + void arm_cfft_radix4_q31( + const arm_cfft_radix4_instance_q31 * S, + q31_t * pSrc); + + /** + * @brief Initialization function for the Q31 CFFT/CIFFT. + * @param[in,out] *S points to an instance of the Q31 CFFT/CIFFT structure. + * @param[in] fftLen length of the FFT. + * @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. + * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. + */ + + arm_status arm_cfft_radix4_init_q31( + arm_cfft_radix4_instance_q31 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + /** + * @brief Processing function for the floating-point CFFT/CIFFT. + * @param[in] *S points to an instance of the floating-point CFFT/CIFFT structure. + * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. + * @return none. + */ + + void arm_cfft_radix4_f32( + const arm_cfft_radix4_instance_f32 * S, + float32_t * pSrc); + + /** + * @brief Initialization function for the floating-point CFFT/CIFFT. + * @param[in,out] *S points to an instance of the floating-point CFFT/CIFFT structure. + * @param[in] fftLen length of the FFT. + * @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. + * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. + */ + + arm_status arm_cfft_radix4_init_f32( + arm_cfft_radix4_instance_f32 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + + + /*---------------------------------------------------------------------- + * Internal functions prototypes FFT function + ----------------------------------------------------------------------*/ + + /** + * @brief Core function for the floating-point CFFT butterfly process. + * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef points to the twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + + void arm_radix4_butterfly_f32( + float32_t * pSrc, + uint16_t fftLen, + float32_t * pCoef, + uint16_t twidCoefModifier); + + /** + * @brief Core function for the floating-point CIFFT butterfly process. + * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef points to twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @param[in] onebyfftLen value of 1/fftLen. + * @return none. + */ + + void arm_radix4_butterfly_inverse_f32( + float32_t * pSrc, + uint16_t fftLen, + float32_t * pCoef, + uint16_t twidCoefModifier, + float32_t onebyfftLen); + + /** + * @brief In-place bit reversal function. + * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. + * @param[in] fftSize length of the FFT. + * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table. + * @param[in] *pBitRevTab points to the bit reversal table. + * @return none. + */ + + void arm_bitreversal_f32( + float32_t *pSrc, + uint16_t fftSize, + uint16_t bitRevFactor, + uint16_t *pBitRevTab); + + /** + * @brief Core function for the Q31 CFFT butterfly process. + * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef points to twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + + void arm_radix4_butterfly_q31( + q31_t *pSrc, + uint32_t fftLen, + q31_t *pCoef, + uint32_t twidCoefModifier); + + /** + * @brief Core function for the Q31 CIFFT butterfly process. + * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef points to twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + + void arm_radix4_butterfly_inverse_q31( + q31_t * pSrc, + uint32_t fftLen, + q31_t * pCoef, + uint32_t twidCoefModifier); + + /** + * @brief In-place bit reversal function. + * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. + * @param[in] fftLen length of the FFT. + * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table + * @param[in] *pBitRevTab points to bit reversal table. + * @return none. + */ + + void arm_bitreversal_q31( + q31_t * pSrc, + uint32_t fftLen, + uint16_t bitRevFactor, + uint16_t *pBitRevTab); + + /** + * @brief Core function for the Q15 CFFT butterfly process. + * @param[in, out] *pSrc16 points to the in-place buffer of Q15 data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef16 points to twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + + void arm_radix4_butterfly_q15( + q15_t *pSrc16, + uint32_t fftLen, + q15_t *pCoef16, + uint32_t twidCoefModifier); + + /** + * @brief Core function for the Q15 CIFFT butterfly process. + * @param[in, out] *pSrc16 points to the in-place buffer of Q15 data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef16 points to twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + + void arm_radix4_butterfly_inverse_q15( + q15_t *pSrc16, + uint32_t fftLen, + q15_t *pCoef16, + uint32_t twidCoefModifier); + + /** + * @brief In-place bit reversal function. + * @param[in, out] *pSrc points to the in-place buffer of Q15 data type. + * @param[in] fftLen length of the FFT. + * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table + * @param[in] *pBitRevTab points to bit reversal table. + * @return none. + */ + + void arm_bitreversal_q15( + q15_t * pSrc, + uint32_t fftLen, + uint16_t bitRevFactor, + uint16_t *pBitRevTab); + + /** + * @brief Instance structure for the Q15 RFFT/RIFFT function. + */ + + typedef struct + { + uint32_t fftLenReal; /**< length of the real FFT. */ + uint32_t fftLenBy2; /**< length of the complex FFT. */ + uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ + uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ + uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + q15_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ + q15_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ + arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */ + } arm_rfft_instance_q15; + + /** + * @brief Instance structure for the Q31 RFFT/RIFFT function. + */ + + typedef struct + { + uint32_t fftLenReal; /**< length of the real FFT. */ + uint32_t fftLenBy2; /**< length of the complex FFT. */ + uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ + uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ + uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + q31_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ + q31_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ + arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */ + } arm_rfft_instance_q31; + + /** + * @brief Instance structure for the floating-point RFFT/RIFFT function. + */ + + typedef struct + { + uint32_t fftLenReal; /**< length of the real FFT. */ + uint16_t fftLenBy2; /**< length of the complex FFT. */ + uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ + uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ + uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + float32_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ + float32_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ + arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ + } arm_rfft_instance_f32; + + /** + * @brief Processing function for the Q15 RFFT/RIFFT. + * @param[in] *S points to an instance of the Q15 RFFT/RIFFT structure. + * @param[in] *pSrc points to the input buffer. + * @param[out] *pDst points to the output buffer. + * @return none. + */ + + void arm_rfft_q15( + const arm_rfft_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst); + + /** + * @brief Initialization function for the Q15 RFFT/RIFFT. + * @param[in, out] *S points to an instance of the Q15 RFFT/RIFFT structure. + * @param[in] *S_CFFT points to an instance of the Q15 CFFT/CIFFT structure. + * @param[in] fftLenReal length of the FFT. + * @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. + * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. + */ + + arm_status arm_rfft_init_q15( + arm_rfft_instance_q15 * S, + arm_cfft_radix4_instance_q15 * S_CFFT, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + /** + * @brief Processing function for the Q31 RFFT/RIFFT. + * @param[in] *S points to an instance of the Q31 RFFT/RIFFT structure. + * @param[in] *pSrc points to the input buffer. + * @param[out] *pDst points to the output buffer. + * @return none. + */ + + void arm_rfft_q31( + const arm_rfft_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst); + + /** + * @brief Initialization function for the Q31 RFFT/RIFFT. + * @param[in, out] *S points to an instance of the Q31 RFFT/RIFFT structure. + * @param[in, out] *S_CFFT points to an instance of the Q31 CFFT/CIFFT structure. + * @param[in] fftLenReal length of the FFT. + * @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. + * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. + */ + + arm_status arm_rfft_init_q31( + arm_rfft_instance_q31 * S, + arm_cfft_radix4_instance_q31 * S_CFFT, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + /** + * @brief Initialization function for the floating-point RFFT/RIFFT. + * @param[in,out] *S points to an instance of the floating-point RFFT/RIFFT structure. + * @param[in,out] *S_CFFT points to an instance of the floating-point CFFT/CIFFT structure. + * @param[in] fftLenReal length of the FFT. + * @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. + * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. + */ + + arm_status arm_rfft_init_f32( + arm_rfft_instance_f32 * S, + arm_cfft_radix4_instance_f32 * S_CFFT, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + /** + * @brief Processing function for the floating-point RFFT/RIFFT. + * @param[in] *S points to an instance of the floating-point RFFT/RIFFT structure. + * @param[in] *pSrc points to the input buffer. + * @param[out] *pDst points to the output buffer. + * @return none. + */ + + void arm_rfft_f32( + const arm_rfft_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst); + + /** + * @brief Instance structure for the floating-point DCT4/IDCT4 function. + */ + + typedef struct + { + uint16_t N; /**< length of the DCT4. */ + uint16_t Nby2; /**< half of the length of the DCT4. */ + float32_t normalize; /**< normalizing factor. */ + float32_t *pTwiddle; /**< points to the twiddle factor table. */ + float32_t *pCosFactor; /**< points to the cosFactor table. */ + arm_rfft_instance_f32 *pRfft; /**< points to the real FFT instance. */ + arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ + } arm_dct4_instance_f32; + + /** + * @brief Initialization function for the floating-point DCT4/IDCT4. + * @param[in,out] *S points to an instance of floating-point DCT4/IDCT4 structure. + * @param[in] *S_RFFT points to an instance of floating-point RFFT/RIFFT structure. + * @param[in] *S_CFFT points to an instance of floating-point CFFT/CIFFT structure. + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported transform length. + */ + + arm_status arm_dct4_init_f32( + arm_dct4_instance_f32 * S, + arm_rfft_instance_f32 * S_RFFT, + arm_cfft_radix4_instance_f32 * S_CFFT, + uint16_t N, + uint16_t Nby2, + float32_t normalize); + + /** + * @brief Processing function for the floating-point DCT4/IDCT4. + * @param[in] *S points to an instance of the floating-point DCT4/IDCT4 structure. + * @param[in] *pState points to state buffer. + * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. + * @return none. + */ + + void arm_dct4_f32( + const arm_dct4_instance_f32 * S, + float32_t * pState, + float32_t * pInlineBuffer); + + /** + * @brief Instance structure for the Q31 DCT4/IDCT4 function. + */ + + typedef struct + { + uint16_t N; /**< length of the DCT4. */ + uint16_t Nby2; /**< half of the length of the DCT4. */ + q31_t normalize; /**< normalizing factor. */ + q31_t *pTwiddle; /**< points to the twiddle factor table. */ + q31_t *pCosFactor; /**< points to the cosFactor table. */ + arm_rfft_instance_q31 *pRfft; /**< points to the real FFT instance. */ + arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */ + } arm_dct4_instance_q31; + + /** + * @brief Initialization function for the Q31 DCT4/IDCT4. + * @param[in,out] *S points to an instance of Q31 DCT4/IDCT4 structure. + * @param[in] *S_RFFT points to an instance of Q31 RFFT/RIFFT structure + * @param[in] *S_CFFT points to an instance of Q31 CFFT/CIFFT structure + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. + */ + + arm_status arm_dct4_init_q31( + arm_dct4_instance_q31 * S, + arm_rfft_instance_q31 * S_RFFT, + arm_cfft_radix4_instance_q31 * S_CFFT, + uint16_t N, + uint16_t Nby2, + q31_t normalize); + + /** + * @brief Processing function for the Q31 DCT4/IDCT4. + * @param[in] *S points to an instance of the Q31 DCT4 structure. + * @param[in] *pState points to state buffer. + * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. + * @return none. + */ + + void arm_dct4_q31( + const arm_dct4_instance_q31 * S, + q31_t * pState, + q31_t * pInlineBuffer); + + /** + * @brief Instance structure for the Q15 DCT4/IDCT4 function. + */ + + typedef struct + { + uint16_t N; /**< length of the DCT4. */ + uint16_t Nby2; /**< half of the length of the DCT4. */ + q15_t normalize; /**< normalizing factor. */ + q15_t *pTwiddle; /**< points to the twiddle factor table. */ + q15_t *pCosFactor; /**< points to the cosFactor table. */ + arm_rfft_instance_q15 *pRfft; /**< points to the real FFT instance. */ + arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */ + } arm_dct4_instance_q15; + + /** + * @brief Initialization function for the Q15 DCT4/IDCT4. + * @param[in,out] *S points to an instance of Q15 DCT4/IDCT4 structure. + * @param[in] *S_RFFT points to an instance of Q15 RFFT/RIFFT structure. + * @param[in] *S_CFFT points to an instance of Q15 CFFT/CIFFT structure. + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. + */ + + arm_status arm_dct4_init_q15( + arm_dct4_instance_q15 * S, + arm_rfft_instance_q15 * S_RFFT, + arm_cfft_radix4_instance_q15 * S_CFFT, + uint16_t N, + uint16_t Nby2, + q15_t normalize); + + /** + * @brief Processing function for the Q15 DCT4/IDCT4. + * @param[in] *S points to an instance of the Q15 DCT4 structure. + * @param[in] *pState points to state buffer. + * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. + * @return none. + */ + + void arm_dct4_q15( + const arm_dct4_instance_q15 * S, + q15_t * pState, + q15_t * pInlineBuffer); + + /** + * @brief Floating-point vector addition. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_add_f32( + float32_t * pSrcA, + float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Q7 vector addition. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_add_q7( + q7_t * pSrcA, + q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Q15 vector addition. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_add_q15( + q15_t * pSrcA, + q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Q31 vector addition. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_add_q31( + q31_t * pSrcA, + q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Floating-point vector subtraction. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_sub_f32( + float32_t * pSrcA, + float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Q7 vector subtraction. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_sub_q7( + q7_t * pSrcA, + q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Q15 vector subtraction. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_sub_q15( + q15_t * pSrcA, + q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Q31 vector subtraction. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_sub_q31( + q31_t * pSrcA, + q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Multiplies a floating-point vector by a scalar. + * @param[in] *pSrc points to the input vector + * @param[in] scale scale factor to be applied + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_scale_f32( + float32_t * pSrc, + float32_t scale, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Multiplies a Q7 vector by a scalar. + * @param[in] *pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_scale_q7( + q7_t * pSrc, + q7_t scaleFract, + int8_t shift, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Multiplies a Q15 vector by a scalar. + * @param[in] *pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_scale_q15( + q15_t * pSrc, + q15_t scaleFract, + int8_t shift, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Multiplies a Q31 vector by a scalar. + * @param[in] *pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_scale_q31( + q31_t * pSrc, + q31_t scaleFract, + int8_t shift, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Q7 vector absolute value. + * @param[in] *pSrc points to the input buffer + * @param[out] *pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_abs_q7( + q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Floating-point vector absolute value. + * @param[in] *pSrc points to the input buffer + * @param[out] *pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_abs_f32( + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Q15 vector absolute value. + * @param[in] *pSrc points to the input buffer + * @param[out] *pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_abs_q15( + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Q31 vector absolute value. + * @param[in] *pSrc points to the input buffer + * @param[out] *pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + * @return none. + */ + + void arm_abs_q31( + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Dot product of floating-point vectors. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] *result output result returned here + * @return none. + */ + + void arm_dot_prod_f32( + float32_t * pSrcA, + float32_t * pSrcB, + uint32_t blockSize, + float32_t * result); + + /** + * @brief Dot product of Q7 vectors. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] *result output result returned here + * @return none. + */ + + void arm_dot_prod_q7( + q7_t * pSrcA, + q7_t * pSrcB, + uint32_t blockSize, + q31_t * result); + + /** + * @brief Dot product of Q15 vectors. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] *result output result returned here + * @return none. + */ + + void arm_dot_prod_q15( + q15_t * pSrcA, + q15_t * pSrcB, + uint32_t blockSize, + q63_t * result); + + /** + * @brief Dot product of Q31 vectors. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] *result output result returned here + * @return none. + */ + + void arm_dot_prod_q31( + q31_t * pSrcA, + q31_t * pSrcB, + uint32_t blockSize, + q63_t * result); + + /** + * @brief Shifts the elements of a Q7 vector a specified number of bits. + * @param[in] *pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_shift_q7( + q7_t * pSrc, + int8_t shiftBits, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Shifts the elements of a Q15 vector a specified number of bits. + * @param[in] *pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_shift_q15( + q15_t * pSrc, + int8_t shiftBits, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Shifts the elements of a Q31 vector a specified number of bits. + * @param[in] *pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_shift_q31( + q31_t * pSrc, + int8_t shiftBits, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Adds a constant offset to a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_offset_f32( + float32_t * pSrc, + float32_t offset, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Adds a constant offset to a Q7 vector. + * @param[in] *pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_offset_q7( + q7_t * pSrc, + q7_t offset, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Adds a constant offset to a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_offset_q15( + q15_t * pSrc, + q15_t offset, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Adds a constant offset to a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_offset_q31( + q31_t * pSrc, + q31_t offset, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Negates the elements of a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_negate_f32( + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Negates the elements of a Q7 vector. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_negate_q7( + q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Negates the elements of a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_negate_q15( + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Negates the elements of a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + void arm_negate_q31( + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + /** + * @brief Copies the elements of a floating-point vector. + * @param[in] *pSrc input pointer + * @param[out] *pDst output pointer + * @param[in] blockSize number of samples to process + * @return none. + */ + void arm_copy_f32( + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Copies the elements of a Q7 vector. + * @param[in] *pSrc input pointer + * @param[out] *pDst output pointer + * @param[in] blockSize number of samples to process + * @return none. + */ + void arm_copy_q7( + q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Copies the elements of a Q15 vector. + * @param[in] *pSrc input pointer + * @param[out] *pDst output pointer + * @param[in] blockSize number of samples to process + * @return none. + */ + void arm_copy_q15( + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Copies the elements of a Q31 vector. + * @param[in] *pSrc input pointer + * @param[out] *pDst output pointer + * @param[in] blockSize number of samples to process + * @return none. + */ + void arm_copy_q31( + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + /** + * @brief Fills a constant value into a floating-point vector. + * @param[in] value input value to be filled + * @param[out] *pDst output pointer + * @param[in] blockSize number of samples to process + * @return none. + */ + void arm_fill_f32( + float32_t value, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Fills a constant value into a Q7 vector. + * @param[in] value input value to be filled + * @param[out] *pDst output pointer + * @param[in] blockSize number of samples to process + * @return none. + */ + void arm_fill_q7( + q7_t value, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Fills a constant value into a Q15 vector. + * @param[in] value input value to be filled + * @param[out] *pDst output pointer + * @param[in] blockSize number of samples to process + * @return none. + */ + void arm_fill_q15( + q15_t value, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Fills a constant value into a Q31 vector. + * @param[in] value input value to be filled + * @param[out] *pDst output pointer + * @param[in] blockSize number of samples to process + * @return none. + */ + void arm_fill_q31( + q31_t value, + q31_t * pDst, + uint32_t blockSize); + +/** + * @brief Convolution of floating-point sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + * @return none. + */ + + void arm_conv_f32( + float32_t * pSrcA, + uint32_t srcALen, + float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst); + +/** + * @brief Convolution of Q15 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + * @return none. + */ + + void arm_conv_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + /** + * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1. + * @return none. + */ + + void arm_conv_fast_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + /** + * @brief Convolution of Q31 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1. + * @return none. + */ + + void arm_conv_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + /** + * @brief Convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1. + * @return none. + */ + + void arm_conv_fast_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + /** + * @brief Convolution of Q7 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1. + * @return none. + */ + + void arm_conv_q7( + q7_t * pSrcA, + uint32_t srcALen, + q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst); + + /** + * @brief Partial convolution of floating-point sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + + arm_status arm_conv_partial_f32( + float32_t * pSrcA, + uint32_t srcALen, + float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + /** + * @brief Partial convolution of Q15 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + + arm_status arm_conv_partial_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + /** + * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + + arm_status arm_conv_partial_fast_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + /** + * @brief Partial convolution of Q31 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + + arm_status arm_conv_partial_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + + arm_status arm_conv_partial_fast_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + /** + * @brief Partial convolution of Q7 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + + arm_status arm_conv_partial_q7( + q7_t * pSrcA, + uint32_t srcALen, + q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Instance structure for the Q15 FIR decimator. + */ + + typedef struct + { + uint8_t M; /**< decimation factor. */ + uint16_t numTaps; /**< number of coefficients in the filter. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + } arm_fir_decimate_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR decimator. + */ + + typedef struct + { + uint8_t M; /**< decimation factor. */ + uint16_t numTaps; /**< number of coefficients in the filter. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + + } arm_fir_decimate_instance_q31; + + /** + * @brief Instance structure for the floating-point FIR decimator. + */ + + typedef struct + { + uint8_t M; /**< decimation factor. */ + uint16_t numTaps; /**< number of coefficients in the filter. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + + } arm_fir_decimate_instance_f32; + + + + /** + * @brief Processing function for the floating-point FIR decimator. + * @param[in] *S points to an instance of the floating-point FIR decimator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + * @return none + */ + + void arm_fir_decimate_f32( + const arm_fir_decimate_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the floating-point FIR decimator. + * @param[in,out] *S points to an instance of the floating-point FIR decimator structure. + * @param[in] numTaps number of coefficients in the filter. + * @param[in] M decimation factor. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * blockSize is not a multiple of M. + */ + + arm_status arm_fir_decimate_init_f32( + arm_fir_decimate_instance_f32 * S, + uint16_t numTaps, + uint8_t M, + float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the Q15 FIR decimator. + * @param[in] *S points to an instance of the Q15 FIR decimator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + * @return none + */ + + void arm_fir_decimate_q15( + const arm_fir_decimate_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. + * @param[in] *S points to an instance of the Q15 FIR decimator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + * @return none + */ + + void arm_fir_decimate_fast_q15( + const arm_fir_decimate_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + + /** + * @brief Initialization function for the Q15 FIR decimator. + * @param[in,out] *S points to an instance of the Q15 FIR decimator structure. + * @param[in] numTaps number of coefficients in the filter. + * @param[in] M decimation factor. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * blockSize is not a multiple of M. + */ + + arm_status arm_fir_decimate_init_q15( + arm_fir_decimate_instance_q15 * S, + uint16_t numTaps, + uint8_t M, + q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 FIR decimator. + * @param[in] *S points to an instance of the Q31 FIR decimator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + * @return none + */ + + void arm_fir_decimate_q31( + const arm_fir_decimate_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. + * @param[in] *S points to an instance of the Q31 FIR decimator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + * @return none + */ + + void arm_fir_decimate_fast_q31( + arm_fir_decimate_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 FIR decimator. + * @param[in,out] *S points to an instance of the Q31 FIR decimator structure. + * @param[in] numTaps number of coefficients in the filter. + * @param[in] M decimation factor. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * blockSize is not a multiple of M. + */ + + arm_status arm_fir_decimate_init_q31( + arm_fir_decimate_instance_q31 * S, + uint16_t numTaps, + uint8_t M, + q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize); + + + + /** + * @brief Instance structure for the Q15 FIR interpolator. + */ + + typedef struct + { + uint8_t L; /**< upsample factor. */ + uint16_t phaseLength; /**< length of each polyphase filter component. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ + q15_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */ + } arm_fir_interpolate_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR interpolator. + */ + + typedef struct + { + uint8_t L; /**< upsample factor. */ + uint16_t phaseLength; /**< length of each polyphase filter component. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ + q31_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */ + } arm_fir_interpolate_instance_q31; + + /** + * @brief Instance structure for the floating-point FIR interpolator. + */ + + typedef struct + { + uint8_t L; /**< upsample factor. */ + uint16_t phaseLength; /**< length of each polyphase filter component. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ + float32_t *pState; /**< points to the state variable array. The array is of length phaseLength+numTaps-1. */ + } arm_fir_interpolate_instance_f32; + + + /** + * @brief Processing function for the Q15 FIR interpolator. + * @param[in] *S points to an instance of the Q15 FIR interpolator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + * @return none. + */ + + void arm_fir_interpolate_q15( + const arm_fir_interpolate_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q15 FIR interpolator. + * @param[in,out] *S points to an instance of the Q15 FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficient buffer. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + */ + + arm_status arm_fir_interpolate_init_q15( + arm_fir_interpolate_instance_q15 * S, + uint8_t L, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 FIR interpolator. + * @param[in] *S points to an instance of the Q15 FIR interpolator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + * @return none. + */ + + void arm_fir_interpolate_q31( + const arm_fir_interpolate_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q31 FIR interpolator. + * @param[in,out] *S points to an instance of the Q31 FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficient buffer. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + */ + + arm_status arm_fir_interpolate_init_q31( + arm_fir_interpolate_instance_q31 * S, + uint8_t L, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the floating-point FIR interpolator. + * @param[in] *S points to an instance of the floating-point FIR interpolator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + * @return none. + */ + + void arm_fir_interpolate_f32( + const arm_fir_interpolate_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point FIR interpolator. + * @param[in,out] *S points to an instance of the floating-point FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficient buffer. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + */ + + arm_status arm_fir_interpolate_init_f32( + arm_fir_interpolate_instance_f32 * S, + uint8_t L, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize); + + /** + * @brief Instance structure for the high precision Q31 Biquad cascade filter. + */ + + typedef struct + { + uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + q63_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */ + q31_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ + uint8_t postShift; /**< additional shift, in bits, applied to each output sample. */ + + } arm_biquad_cas_df1_32x64_ins_q31; + + + /** + * @param[in] *S points to an instance of the high precision Q31 Biquad cascade filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_biquad_cas_df1_32x64_q31( + const arm_biquad_cas_df1_32x64_ins_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @param[in,out] *S points to an instance of the high precision Q31 Biquad cascade filter structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] postShift shift to be applied to the output. Varies according to the coefficients format + * @return none + */ + + void arm_biquad_cas_df1_32x64_init_q31( + arm_biquad_cas_df1_32x64_ins_q31 * S, + uint8_t numStages, + q31_t * pCoeffs, + q63_t * pState, + uint8_t postShift); + + + + /** + * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. + */ + + typedef struct + { + uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + float32_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */ + float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ + } arm_biquad_cascade_df2T_instance_f32; + + + /** + * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in] *S points to an instance of the filter data structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_biquad_cascade_df2T_f32( + const arm_biquad_cascade_df2T_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in,out] *S points to an instance of the filter data structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @return none + */ + + void arm_biquad_cascade_df2T_init_f32( + arm_biquad_cascade_df2T_instance_f32 * S, + uint8_t numStages, + float32_t * pCoeffs, + float32_t * pState); + + + + /** + * @brief Instance structure for the Q15 FIR lattice filter. + */ + + typedef struct + { + uint16_t numStages; /**< number of filter stages. */ + q15_t *pState; /**< points to the state variable array. The array is of length numStages. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ + } arm_fir_lattice_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR lattice filter. + */ + + typedef struct + { + uint16_t numStages; /**< number of filter stages. */ + q31_t *pState; /**< points to the state variable array. The array is of length numStages. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ + } arm_fir_lattice_instance_q31; + + /** + * @brief Instance structure for the floating-point FIR lattice filter. + */ + + typedef struct + { + uint16_t numStages; /**< number of filter stages. */ + float32_t *pState; /**< points to the state variable array. The array is of length numStages. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ + } arm_fir_lattice_instance_f32; + + /** + * @brief Initialization function for the Q15 FIR lattice filter. + * @param[in] *S points to an instance of the Q15 FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] *pState points to the state buffer. The array is of length numStages. + * @return none. + */ + + void arm_fir_lattice_init_q15( + arm_fir_lattice_instance_q15 * S, + uint16_t numStages, + q15_t * pCoeffs, + q15_t * pState); + + + /** + * @brief Processing function for the Q15 FIR lattice filter. + * @param[in] *S points to an instance of the Q15 FIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + void arm_fir_lattice_q15( + const arm_fir_lattice_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q31 FIR lattice filter. + * @param[in] *S points to an instance of the Q31 FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] *pState points to the state buffer. The array is of length numStages. + * @return none. + */ + + void arm_fir_lattice_init_q31( + arm_fir_lattice_instance_q31 * S, + uint16_t numStages, + q31_t * pCoeffs, + q31_t * pState); + + + /** + * @brief Processing function for the Q31 FIR lattice filter. + * @param[in] *S points to an instance of the Q31 FIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_fir_lattice_q31( + const arm_fir_lattice_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + +/** + * @brief Initialization function for the floating-point FIR lattice filter. + * @param[in] *S points to an instance of the floating-point FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] *pState points to the state buffer. The array is of length numStages. + * @return none. + */ + + void arm_fir_lattice_init_f32( + arm_fir_lattice_instance_f32 * S, + uint16_t numStages, + float32_t * pCoeffs, + float32_t * pState); + + /** + * @brief Processing function for the floating-point FIR lattice filter. + * @param[in] *S points to an instance of the floating-point FIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_fir_lattice_f32( + const arm_fir_lattice_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Instance structure for the Q15 IIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of stages in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ + q15_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ + q15_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ + } arm_iir_lattice_instance_q15; + + /** + * @brief Instance structure for the Q31 IIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of stages in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ + q31_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ + q31_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ + } arm_iir_lattice_instance_q31; + + /** + * @brief Instance structure for the floating-point IIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of stages in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ + float32_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ + float32_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ + } arm_iir_lattice_instance_f32; + + /** + * @brief Processing function for the floating-point IIR lattice filter. + * @param[in] *S points to an instance of the floating-point IIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_iir_lattice_f32( + const arm_iir_lattice_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point IIR lattice filter. + * @param[in] *S points to an instance of the floating-point IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. + * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. + * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize-1. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_iir_lattice_init_f32( + arm_iir_lattice_instance_f32 * S, + uint16_t numStages, + float32_t *pkCoeffs, + float32_t *pvCoeffs, + float32_t *pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q31 IIR lattice filter. + * @param[in] *S points to an instance of the Q31 IIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_iir_lattice_q31( + const arm_iir_lattice_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 IIR lattice filter. + * @param[in] *S points to an instance of the Q31 IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. + * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. + * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_iir_lattice_init_q31( + arm_iir_lattice_instance_q31 * S, + uint16_t numStages, + q31_t *pkCoeffs, + q31_t *pvCoeffs, + q31_t *pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q15 IIR lattice filter. + * @param[in] *S points to an instance of the Q15 IIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_iir_lattice_q15( + const arm_iir_lattice_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + +/** + * @brief Initialization function for the Q15 IIR lattice filter. + * @param[in] *S points to an instance of the fixed-point Q15 IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] *pkCoeffs points to reflection coefficient buffer. The array is of length numStages. + * @param[in] *pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1. + * @param[in] *pState points to state buffer. The array is of length numStages+blockSize. + * @param[in] blockSize number of samples to process per call. + * @return none. + */ + + void arm_iir_lattice_init_q15( + arm_iir_lattice_instance_q15 * S, + uint16_t numStages, + q15_t *pkCoeffs, + q15_t *pvCoeffs, + q15_t *pState, + uint32_t blockSize); + + /** + * @brief Instance structure for the floating-point LMS filter. + */ + + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + float32_t mu; /**< step size that controls filter coefficient updates. */ + } arm_lms_instance_f32; + + /** + * @brief Processing function for floating-point LMS filter. + * @param[in] *S points to an instance of the floating-point LMS filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[in] *pRef points to the block of reference data. + * @param[out] *pOut points to the block of output data. + * @param[out] *pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_lms_f32( + const arm_lms_instance_f32 * S, + float32_t * pSrc, + float32_t * pRef, + float32_t * pOut, + float32_t * pErr, + uint32_t blockSize); + + /** + * @brief Initialization function for floating-point LMS filter. + * @param[in] *S points to an instance of the floating-point LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to the coefficient buffer. + * @param[in] *pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_lms_init_f32( + arm_lms_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + float32_t mu, + uint32_t blockSize); + + /** + * @brief Instance structure for the Q15 LMS filter. + */ + + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q15_t mu; /**< step size that controls filter coefficient updates. */ + uint32_t postShift; /**< bit shift applied to coefficients. */ + } arm_lms_instance_q15; + + + /** + * @brief Initialization function for the Q15 LMS filter. + * @param[in] *S points to an instance of the Q15 LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to the coefficient buffer. + * @param[in] *pState points to the state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + * @return none. + */ + + void arm_lms_init_q15( + arm_lms_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + q15_t mu, + uint32_t blockSize, + uint32_t postShift); + + /** + * @brief Processing function for Q15 LMS filter. + * @param[in] *S points to an instance of the Q15 LMS filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[in] *pRef points to the block of reference data. + * @param[out] *pOut points to the block of output data. + * @param[out] *pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_lms_q15( + const arm_lms_instance_q15 * S, + q15_t * pSrc, + q15_t * pRef, + q15_t * pOut, + q15_t * pErr, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q31 LMS filter. + */ + + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q31_t mu; /**< step size that controls filter coefficient updates. */ + uint32_t postShift; /**< bit shift applied to coefficients. */ + + } arm_lms_instance_q31; + + /** + * @brief Processing function for Q31 LMS filter. + * @param[in] *S points to an instance of the Q15 LMS filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[in] *pRef points to the block of reference data. + * @param[out] *pOut points to the block of output data. + * @param[out] *pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_lms_q31( + const arm_lms_instance_q31 * S, + q31_t * pSrc, + q31_t * pRef, + q31_t * pOut, + q31_t * pErr, + uint32_t blockSize); + + /** + * @brief Initialization function for Q31 LMS filter. + * @param[in] *S points to an instance of the Q31 LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to coefficient buffer. + * @param[in] *pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + * @return none. + */ + + void arm_lms_init_q31( + arm_lms_instance_q31 * S, + uint16_t numTaps, + q31_t *pCoeffs, + q31_t *pState, + q31_t mu, + uint32_t blockSize, + uint32_t postShift); + + /** + * @brief Instance structure for the floating-point normalized LMS filter. + */ + + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + float32_t mu; /**< step size that control filter coefficient updates. */ + float32_t energy; /**< saves previous frame energy. */ + float32_t x0; /**< saves previous input sample. */ + } arm_lms_norm_instance_f32; + + /** + * @brief Processing function for floating-point normalized LMS filter. + * @param[in] *S points to an instance of the floating-point normalized LMS filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[in] *pRef points to the block of reference data. + * @param[out] *pOut points to the block of output data. + * @param[out] *pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_lms_norm_f32( + arm_lms_norm_instance_f32 * S, + float32_t * pSrc, + float32_t * pRef, + float32_t * pOut, + float32_t * pErr, + uint32_t blockSize); + + /** + * @brief Initialization function for floating-point normalized LMS filter. + * @param[in] *S points to an instance of the floating-point LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to coefficient buffer. + * @param[in] *pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_lms_norm_init_f32( + arm_lms_norm_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + float32_t mu, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q31 normalized LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q31_t mu; /**< step size that controls filter coefficient updates. */ + uint8_t postShift; /**< bit shift applied to coefficients. */ + q31_t *recipTable; /**< points to the reciprocal initial value table. */ + q31_t energy; /**< saves previous frame energy. */ + q31_t x0; /**< saves previous input sample. */ + } arm_lms_norm_instance_q31; + + /** + * @brief Processing function for Q31 normalized LMS filter. + * @param[in] *S points to an instance of the Q31 normalized LMS filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[in] *pRef points to the block of reference data. + * @param[out] *pOut points to the block of output data. + * @param[out] *pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_lms_norm_q31( + arm_lms_norm_instance_q31 * S, + q31_t * pSrc, + q31_t * pRef, + q31_t * pOut, + q31_t * pErr, + uint32_t blockSize); + + /** + * @brief Initialization function for Q31 normalized LMS filter. + * @param[in] *S points to an instance of the Q31 normalized LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to coefficient buffer. + * @param[in] *pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + * @return none. + */ + + void arm_lms_norm_init_q31( + arm_lms_norm_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + q31_t mu, + uint32_t blockSize, + uint8_t postShift); + + /** + * @brief Instance structure for the Q15 normalized LMS filter. + */ + + typedef struct + { + uint16_t numTaps; /**< Number of coefficients in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q15_t mu; /**< step size that controls filter coefficient updates. */ + uint8_t postShift; /**< bit shift applied to coefficients. */ + q15_t *recipTable; /**< Points to the reciprocal initial value table. */ + q15_t energy; /**< saves previous frame energy. */ + q15_t x0; /**< saves previous input sample. */ + } arm_lms_norm_instance_q15; + + /** + * @brief Processing function for Q15 normalized LMS filter. + * @param[in] *S points to an instance of the Q15 normalized LMS filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[in] *pRef points to the block of reference data. + * @param[out] *pOut points to the block of output data. + * @param[out] *pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + + void arm_lms_norm_q15( + arm_lms_norm_instance_q15 * S, + q15_t * pSrc, + q15_t * pRef, + q15_t * pOut, + q15_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for Q15 normalized LMS filter. + * @param[in] *S points to an instance of the Q15 normalized LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to coefficient buffer. + * @param[in] *pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + * @return none. + */ + + void arm_lms_norm_init_q15( + arm_lms_norm_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + q15_t mu, + uint32_t blockSize, + uint8_t postShift); + + /** + * @brief Correlation of floating-point sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + */ + + void arm_correlate_f32( + float32_t * pSrcA, + uint32_t srcALen, + float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst); + + /** + * @brief Correlation of Q15 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + */ + + void arm_correlate_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + /** + * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + */ + + void arm_correlate_fast_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + /** + * @brief Correlation of Q31 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + */ + + void arm_correlate_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + /** + * @brief Correlation of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + */ + + void arm_correlate_fast_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + /** + * @brief Correlation of Q7 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + */ + + void arm_correlate_q7( + q7_t * pSrcA, + uint32_t srcALen, + q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst); + + /** + * @brief Instance structure for the floating-point sparse FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + float32_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_f32; + + /** + * @brief Instance structure for the Q31 sparse FIR filter. + */ + + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + q31_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_q31; + + /** + * @brief Instance structure for the Q15 sparse FIR filter. + */ + + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + q15_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_q15; + + /** + * @brief Instance structure for the Q7 sparse FIR filter. + */ + + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + q7_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_q7; + + /** + * @brief Processing function for the floating-point sparse FIR filter. + * @param[in] *S points to an instance of the floating-point sparse FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] *pScratchIn points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + * @return none. + */ + + void arm_fir_sparse_f32( + arm_fir_sparse_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + float32_t * pScratchIn, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point sparse FIR filter. + * @param[in,out] *S points to an instance of the floating-point sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] *pCoeffs points to the array of filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] *pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + * @return none + */ + + void arm_fir_sparse_init_f32( + arm_fir_sparse_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 sparse FIR filter. + * @param[in] *S points to an instance of the Q31 sparse FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] *pScratchIn points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + * @return none. + */ + + void arm_fir_sparse_q31( + arm_fir_sparse_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + q31_t * pScratchIn, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q31 sparse FIR filter. + * @param[in,out] *S points to an instance of the Q31 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] *pCoeffs points to the array of filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] *pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + * @return none + */ + + void arm_fir_sparse_init_q31( + arm_fir_sparse_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + /** + * @brief Processing function for the Q15 sparse FIR filter. + * @param[in] *S points to an instance of the Q15 sparse FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] *pScratchIn points to a temporary buffer of size blockSize. + * @param[in] *pScratchOut points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + * @return none. + */ + + void arm_fir_sparse_q15( + arm_fir_sparse_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + q15_t * pScratchIn, + q31_t * pScratchOut, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q15 sparse FIR filter. + * @param[in,out] *S points to an instance of the Q15 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] *pCoeffs points to the array of filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] *pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + * @return none + */ + + void arm_fir_sparse_init_q15( + arm_fir_sparse_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + /** + * @brief Processing function for the Q7 sparse FIR filter. + * @param[in] *S points to an instance of the Q7 sparse FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] *pScratchIn points to a temporary buffer of size blockSize. + * @param[in] *pScratchOut points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + * @return none. + */ + + void arm_fir_sparse_q7( + arm_fir_sparse_instance_q7 * S, + q7_t * pSrc, + q7_t * pDst, + q7_t * pScratchIn, + q31_t * pScratchOut, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q7 sparse FIR filter. + * @param[in,out] *S points to an instance of the Q7 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] *pCoeffs points to the array of filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] *pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + * @return none + */ + + void arm_fir_sparse_init_q7( + arm_fir_sparse_instance_q7 * S, + uint16_t numTaps, + q7_t * pCoeffs, + q7_t * pState, + int32_t *pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + + /* + * @brief Floating-point sin_cos function. + * @param[in] theta input value in degrees + * @param[out] *pSinVal points to the processed sine output. + * @param[out] *pCosVal points to the processed cos output. + * @return none. + */ + + void arm_sin_cos_f32( + float32_t theta, + float32_t *pSinVal, + float32_t *pCcosVal); + + /* + * @brief Q31 sin_cos function. + * @param[in] theta scaled input value in degrees + * @param[out] *pSinVal points to the processed sine output. + * @param[out] *pCosVal points to the processed cosine output. + * @return none. + */ + + void arm_sin_cos_q31( + q31_t theta, + q31_t *pSinVal, + q31_t *pCosVal); + + + /** + * @brief Floating-point complex conjugate. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + * @return none. + */ + + void arm_cmplx_conj_f32( + float32_t * pSrc, + float32_t * pDst, + uint32_t numSamples); + + /** + * @brief Q31 complex conjugate. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + * @return none. + */ + + void arm_cmplx_conj_q31( + q31_t * pSrc, + q31_t * pDst, + uint32_t numSamples); + + /** + * @brief Q15 complex conjugate. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + * @return none. + */ + + void arm_cmplx_conj_q15( + q15_t * pSrc, + q15_t * pDst, + uint32_t numSamples); + + + + /** + * @brief Floating-point complex magnitude squared + * @param[in] *pSrc points to the complex input vector + * @param[out] *pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + * @return none. + */ + + void arm_cmplx_mag_squared_f32( + float32_t * pSrc, + float32_t * pDst, + uint32_t numSamples); + + /** + * @brief Q31 complex magnitude squared + * @param[in] *pSrc points to the complex input vector + * @param[out] *pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + * @return none. + */ + + void arm_cmplx_mag_squared_q31( + q31_t * pSrc, + q31_t * pDst, + uint32_t numSamples); + + /** + * @brief Q15 complex magnitude squared + * @param[in] *pSrc points to the complex input vector + * @param[out] *pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + * @return none. + */ + + void arm_cmplx_mag_squared_q15( + q15_t * pSrc, + q15_t * pDst, + uint32_t numSamples); + + + /** + * @ingroup groupController + */ + + /** + * @defgroup PID PID Motor Control + * + * A Proportional Integral Derivative (PID) controller is a generic feedback control + * loop mechanism widely used in industrial control systems. + * A PID controller is the most commonly used type of feedback controller. + * + * This set of functions implements (PID) controllers + * for Q15, Q31, and floating-point data types. The functions operate on a single sample + * of data and each call to the function returns a single processed value. + * S points to an instance of the PID control data structure. in + * is the input sample value. The functions return the output value. + * + * \par Algorithm: + *
+   *    y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2]
+   *    A0 = Kp + Ki + Kd
+   *    A1 = (-Kp ) - (2 * Kd )
+   *    A2 = Kd  
+ * + * \par + * where \c Kp is proportional constant, \c Ki is Integral constant and \c Kd is Derivative constant + * + * \par + * \image html PID.gif "Proportional Integral Derivative Controller" + * + * \par + * The PID controller calculates an "error" value as the difference between + * the measured output and the reference input. + * The controller attempts to minimize the error by adjusting the process control inputs. + * The proportional value determines the reaction to the current error, + * the integral value determines the reaction based on the sum of recent errors, + * and the derivative value determines the reaction based on the rate at which the error has been changing. + * + * \par Instance Structure + * The Gains A0, A1, A2 and state variables for a PID controller are stored together in an instance data structure. + * A separate instance structure must be defined for each PID Controller. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Reset Functions + * There is also an associated reset function for each data type which clears the state array. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Initializes the Gains A0, A1, A2 from Kp,Ki, Kd gains. + * - Zeros out the values in the state buffer. + * + * \par + * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function. + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the PID Controller functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup PID + * @{ + */ + + /** + * @brief Process function for the floating-point PID Control. + * @param[in,out] *S is an instance of the floating-point PID Control structure + * @param[in] in input sample to process + * @return out processed output sample. + */ + + + static __INLINE float32_t arm_pid_f32( + arm_pid_instance_f32 * S, + float32_t in) + { + float32_t out; + + /* y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2] */ + out = (S->A0 * in) + + (S->A1 * S->state[0]) + (S->A2 * S->state[1]) + (S->state[2]); + + /* Update state */ + S->state[1] = S->state[0]; + S->state[0] = in; + S->state[2] = out; + + /* return to application */ + return (out); + + } + + /** + * @brief Process function for the Q31 PID Control. + * @param[in,out] *S points to an instance of the Q31 PID Control structure + * @param[in] in input sample to process + * @return out processed output sample. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around rather than clip. + * In order to avoid overflows completely the input signal must be scaled down by 2 bits as there are four additions. + * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. + */ + + static __INLINE q31_t arm_pid_q31( + arm_pid_instance_q31 * S, + q31_t in) + { + q63_t acc; + q31_t out; + + /* acc = A0 * x[n] */ + acc = (q63_t) S->A0 * in; + + /* acc += A1 * x[n-1] */ + acc += (q63_t) S->A1 * S->state[0]; + + /* acc += A2 * x[n-2] */ + acc += (q63_t) S->A2 * S->state[1]; + + /* convert output to 1.31 format to add y[n-1] */ + out = (q31_t) (acc >> 31u); + + /* out += y[n-1] */ + out += S->state[2]; + + /* Update state */ + S->state[1] = S->state[0]; + S->state[0] = in; + S->state[2] = out; + + /* return to application */ + return (out); + + } + + /** + * @brief Process function for the Q15 PID Control. + * @param[in,out] *S points to an instance of the Q15 PID Control structure + * @param[in] in input sample to process + * @return out processed output sample. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 64-bit internal accumulator. + * Both Gains and state variables are represented in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. + * Lastly, the accumulator is saturated to yield a result in 1.15 format. + */ + + static __INLINE q15_t arm_pid_q15( + arm_pid_instance_q15 * S, + q15_t in) + { + q63_t acc; + q15_t out; + + /* Implementation of PID controller */ + + #ifdef ARM_MATH_CM0 + + /* acc = A0 * x[n] */ + acc = ((q31_t) S->A0 )* in ; + + #else + + /* acc = A0 * x[n] */ + acc = (q31_t) __SMUAD(S->A0, in); + + #endif + + #ifdef ARM_MATH_CM0 + + /* acc += A1 * x[n-1] + A2 * x[n-2] */ + acc += (q31_t) S->A1 * S->state[0] ; + acc += (q31_t) S->A2 * S->state[1] ; + + #else + + /* acc += A1 * x[n-1] + A2 * x[n-2] */ + acc = __SMLALD(S->A1, (q31_t)__SIMD32(S->state), acc); + + #endif + + /* acc += y[n-1] */ + acc += (q31_t) S->state[2] << 15; + + /* saturate the output */ + out = (q15_t) (__SSAT((acc >> 15), 16)); + + /* Update state */ + S->state[1] = S->state[0]; + S->state[0] = in; + S->state[2] = out; + + /* return to application */ + return (out); + + } + + /** + * @} end of PID group + */ + + + /** + * @brief Floating-point matrix inverse. + * @param[in] *src points to the instance of the input floating-point matrix structure. + * @param[out] *dst points to the instance of the output floating-point matrix structure. + * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match. + * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR. + */ + + arm_status arm_mat_inverse_f32( + const arm_matrix_instance_f32 * src, + arm_matrix_instance_f32 * dst); + + + + /** + * @ingroup groupController + */ + + + /** + * @defgroup clarke Vector Clarke Transform + * Forward Clarke transform converts the instantaneous stator phases into a two-coordinate time invariant vector. + * Generally the Clarke transform uses three-phase currents Ia, Ib and Ic to calculate currents + * in the two-phase orthogonal stator axis Ialpha and Ibeta. + * When Ialpha is superposed with Ia as shown in the figure below + * \image html clarke.gif Stator current space vector and its components in (a,b). + * and Ia + Ib + Ic = 0, in this condition Ialpha and Ibeta + * can be calculated using only Ia and Ib. + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html clarkeFormula.gif + * where Ia and Ib are the instantaneous stator phases and + * pIalpha and pIbeta are the two coordinates of time invariant vector. + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Clarke transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup clarke + * @{ + */ + + /** + * + * @brief Floating-point Clarke transform + * @param[in] Ia input three-phase coordinate a + * @param[in] Ib input three-phase coordinate b + * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha + * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta + * @return none. + */ + + static __INLINE void arm_clarke_f32( + float32_t Ia, + float32_t Ib, + float32_t * pIalpha, + float32_t * pIbeta) + { + /* Calculate pIalpha using the equation, pIalpha = Ia */ + *pIalpha = Ia; + + /* Calculate pIbeta using the equation, pIbeta = (1/sqrt(3)) * Ia + (2/sqrt(3)) * Ib */ + *pIbeta = ((float32_t) 0.57735026919 * Ia + (float32_t) 1.15470053838 * Ib); + + } + + /** + * @brief Clarke transform for Q31 version + * @param[in] Ia input three-phase coordinate a + * @param[in] Ib input three-phase coordinate b + * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha + * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 32-bit accumulator. + * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + * There is saturation on the addition, hence there is no risk of overflow. + */ + + static __INLINE void arm_clarke_q31( + q31_t Ia, + q31_t Ib, + q31_t * pIalpha, + q31_t * pIbeta) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + + /* Calculating pIalpha from Ia by equation pIalpha = Ia */ + *pIalpha = Ia; + + /* Intermediate product is calculated by (1/(sqrt(3)) * Ia) */ + product1 = (q31_t) (((q63_t) Ia * 0x24F34E8B) >> 30); + + /* Intermediate product is calculated by (2/sqrt(3) * Ib) */ + product2 = (q31_t) (((q63_t) Ib * 0x49E69D16) >> 30); + + /* pIbeta is calculated by adding the intermediate products */ + *pIbeta = __QADD(product1, product2); + } + + /** + * @} end of clarke group + */ + + /** + * @brief Converts the elements of the Q7 vector to Q31 vector. + * @param[in] *pSrc input pointer + * @param[out] *pDst output pointer + * @param[in] blockSize number of samples to process + * @return none. + */ + void arm_q7_to_q31( + q7_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + + + /** + * @ingroup groupController + */ + + /** + * @defgroup inv_clarke Vector Inverse Clarke Transform + * Inverse Clarke transform converts the two-coordinate time invariant vector into instantaneous stator phases. + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html clarkeInvFormula.gif + * where pIa and pIb are the instantaneous stator phases and + * Ialpha and Ibeta are the two coordinates of time invariant vector. + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Clarke transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup inv_clarke + * @{ + */ + + /** + * @brief Floating-point Inverse Clarke transform + * @param[in] Ialpha input two-phase orthogonal vector axis alpha + * @param[in] Ibeta input two-phase orthogonal vector axis beta + * @param[out] *pIa points to output three-phase coordinate a + * @param[out] *pIb points to output three-phase coordinate b + * @return none. + */ + + + static __INLINE void arm_inv_clarke_f32( + float32_t Ialpha, + float32_t Ibeta, + float32_t * pIa, + float32_t * pIb) + { + /* Calculating pIa from Ialpha by equation pIa = Ialpha */ + *pIa = Ialpha; + + /* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */ + *pIb = -0.5 * Ialpha + (float32_t) 0.8660254039 *Ibeta; + + } + + /** + * @brief Inverse Clarke transform for Q31 version + * @param[in] Ialpha input two-phase orthogonal vector axis alpha + * @param[in] Ibeta input two-phase orthogonal vector axis beta + * @param[out] *pIa points to output three-phase coordinate a + * @param[out] *pIb points to output three-phase coordinate b + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 32-bit accumulator. + * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + * There is saturation on the subtraction, hence there is no risk of overflow. + */ + + static __INLINE void arm_inv_clarke_q31( + q31_t Ialpha, + q31_t Ibeta, + q31_t * pIa, + q31_t * pIb) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + + /* Calculating pIa from Ialpha by equation pIa = Ialpha */ + *pIa = Ialpha; + + /* Intermediate product is calculated by (1/(2*sqrt(3)) * Ia) */ + product1 = (q31_t) (((q63_t) (Ialpha) * (0x40000000)) >> 31); + + /* Intermediate product is calculated by (1/sqrt(3) * pIb) */ + product2 = (q31_t) (((q63_t) (Ibeta) * (0x6ED9EBA1)) >> 31); + + /* pIb is calculated by subtracting the products */ + *pIb = __QSUB(product2, product1); + + } + + /** + * @} end of inv_clarke group + */ + + /** + * @brief Converts the elements of the Q7 vector to Q15 vector. + * @param[in] *pSrc input pointer + * @param[out] *pDst output pointer + * @param[in] blockSize number of samples to process + * @return none. + */ + void arm_q7_to_q15( + q7_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + + /** + * @ingroup groupController + */ + + /** + * @defgroup park Vector Park Transform + * + * Forward Park transform converts the input two-coordinate vector to flux and torque components. + * The Park transform can be used to realize the transformation of the Ialpha and the Ibeta currents + * from the stationary to the moving reference frame and control the spatial relationship between + * the stator vector current and rotor flux vector. + * If we consider the d axis aligned with the rotor flux, the diagram below shows the + * current vector and the relationship from the two reference frames: + * \image html park.gif "Stator current space vector and its component in (a,b) and in the d,q rotating reference frame" + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html parkFormula.gif + * where Ialpha and Ibeta are the stator vector components, + * pId and pIq are rotor vector components and cosVal and sinVal are the + * cosine and sine values of theta (rotor flux position). + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Park transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup park + * @{ + */ + + /** + * @brief Floating-point Park transform + * @param[in] Ialpha input two-phase vector coordinate alpha + * @param[in] Ibeta input two-phase vector coordinate beta + * @param[out] *pId points to output rotor reference frame d + * @param[out] *pIq points to output rotor reference frame q + * @param[in] sinVal sine value of rotation angle theta + * @param[in] cosVal cosine value of rotation angle theta + * @return none. + * + * The function implements the forward Park transform. + * + */ + + static __INLINE void arm_park_f32( + float32_t Ialpha, + float32_t Ibeta, + float32_t * pId, + float32_t * pIq, + float32_t sinVal, + float32_t cosVal) + { + /* Calculate pId using the equation, pId = Ialpha * cosVal + Ibeta * sinVal */ + *pId = Ialpha * cosVal + Ibeta * sinVal; + + /* Calculate pIq using the equation, pIq = - Ialpha * sinVal + Ibeta * cosVal */ + *pIq = -Ialpha * sinVal + Ibeta * cosVal; + + } + + /** + * @brief Park transform for Q31 version + * @param[in] Ialpha input two-phase vector coordinate alpha + * @param[in] Ibeta input two-phase vector coordinate beta + * @param[out] *pId points to output rotor reference frame d + * @param[out] *pIq points to output rotor reference frame q + * @param[in] sinVal sine value of rotation angle theta + * @param[in] cosVal cosine value of rotation angle theta + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 32-bit accumulator. + * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + * There is saturation on the addition and subtraction, hence there is no risk of overflow. + */ + + + static __INLINE void arm_park_q31( + q31_t Ialpha, + q31_t Ibeta, + q31_t * pId, + q31_t * pIq, + q31_t sinVal, + q31_t cosVal) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + q31_t product3, product4; /* Temporary variables used to store intermediate results */ + + /* Intermediate product is calculated by (Ialpha * cosVal) */ + product1 = (q31_t) (((q63_t) (Ialpha) * (cosVal)) >> 31); + + /* Intermediate product is calculated by (Ibeta * sinVal) */ + product2 = (q31_t) (((q63_t) (Ibeta) * (sinVal)) >> 31); + + + /* Intermediate product is calculated by (Ialpha * sinVal) */ + product3 = (q31_t) (((q63_t) (Ialpha) * (sinVal)) >> 31); + + /* Intermediate product is calculated by (Ibeta * cosVal) */ + product4 = (q31_t) (((q63_t) (Ibeta) * (cosVal)) >> 31); + + /* Calculate pId by adding the two intermediate products 1 and 2 */ + *pId = __QADD(product1, product2); + + /* Calculate pIq by subtracting the two intermediate products 3 from 4 */ + *pIq = __QSUB(product4, product3); + } + + /** + * @} end of park group + */ + + /** + * @brief Converts the elements of the Q7 vector to floating-point vector. + * @param[in] *pSrc is input pointer + * @param[out] *pDst is output pointer + * @param[in] blockSize is the number of samples to process + * @return none. + */ + void arm_q7_to_float( + q7_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @ingroup groupController + */ + + /** + * @defgroup inv_park Vector Inverse Park transform + * Inverse Park transform converts the input flux and torque components to two-coordinate vector. + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html parkInvFormula.gif + * where pIalpha and pIbeta are the stator vector components, + * Id and Iq are rotor vector components and cosVal and sinVal are the + * cosine and sine values of theta (rotor flux position). + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Park transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup inv_park + * @{ + */ + + /** + * @brief Floating-point Inverse Park transform + * @param[in] Id input coordinate of rotor reference frame d + * @param[in] Iq input coordinate of rotor reference frame q + * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha + * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta + * @param[in] sinVal sine value of rotation angle theta + * @param[in] cosVal cosine value of rotation angle theta + * @return none. + */ + + static __INLINE void arm_inv_park_f32( + float32_t Id, + float32_t Iq, + float32_t * pIalpha, + float32_t * pIbeta, + float32_t sinVal, + float32_t cosVal) + { + /* Calculate pIalpha using the equation, pIalpha = Id * cosVal - Iq * sinVal */ + *pIalpha = Id * cosVal - Iq * sinVal; + + /* Calculate pIbeta using the equation, pIbeta = Id * sinVal + Iq * cosVal */ + *pIbeta = Id * sinVal + Iq * cosVal; + + } + + + /** + * @brief Inverse Park transform for Q31 version + * @param[in] Id input coordinate of rotor reference frame d + * @param[in] Iq input coordinate of rotor reference frame q + * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha + * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta + * @param[in] sinVal sine value of rotation angle theta + * @param[in] cosVal cosine value of rotation angle theta + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 32-bit accumulator. + * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + * There is saturation on the addition, hence there is no risk of overflow. + */ + + + static __INLINE void arm_inv_park_q31( + q31_t Id, + q31_t Iq, + q31_t * pIalpha, + q31_t * pIbeta, + q31_t sinVal, + q31_t cosVal) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + q31_t product3, product4; /* Temporary variables used to store intermediate results */ + + /* Intermediate product is calculated by (Id * cosVal) */ + product1 = (q31_t) (((q63_t) (Id) * (cosVal)) >> 31); + + /* Intermediate product is calculated by (Iq * sinVal) */ + product2 = (q31_t) (((q63_t) (Iq) * (sinVal)) >> 31); + + + /* Intermediate product is calculated by (Id * sinVal) */ + product3 = (q31_t) (((q63_t) (Id) * (sinVal)) >> 31); + + /* Intermediate product is calculated by (Iq * cosVal) */ + product4 = (q31_t) (((q63_t) (Iq) * (cosVal)) >> 31); + + /* Calculate pIalpha by using the two intermediate products 1 and 2 */ + *pIalpha = __QSUB(product1, product2); + + /* Calculate pIbeta by using the two intermediate products 3 and 4 */ + *pIbeta = __QADD(product4, product3); + + } + + /** + * @} end of Inverse park group + */ + + + /** + * @brief Converts the elements of the Q31 vector to floating-point vector. + * @param[in] *pSrc is input pointer + * @param[out] *pDst is output pointer + * @param[in] blockSize is the number of samples to process + * @return none. + */ + void arm_q31_to_float( + q31_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @ingroup groupInterpolation + */ + + /** + * @defgroup LinearInterpolate Linear Interpolation + * + * Linear interpolation is a method of curve fitting using linear polynomials. + * Linear interpolation works by effectively drawing a straight line between two neighboring samples and returning the appropriate point along that line + * + * \par + * \image html LinearInterp.gif "Linear interpolation" + * + * \par + * A Linear Interpolate function calculates an output value(y), for the input(x) + * using linear interpolation of the input values x0, x1( nearest input values) and the output values y0 and y1(nearest output values) + * + * \par Algorithm: + *
+   *       y = y0 + (x - x0) * ((y1 - y0)/(x1-x0))
+   *       where x0, x1 are nearest values of input x
+   *             y0, y1 are nearest values to output y
+   * 
+ * + * \par + * This set of functions implements Linear interpolation process + * for Q7, Q15, Q31, and floating-point data types. The functions operate on a single + * sample of data and each call to the function returns a single processed value. + * S points to an instance of the Linear Interpolate function data structure. + * x is the input sample value. The functions returns the output value. + * + * \par + * if x is outside of the table boundary, Linear interpolation returns first value of the table + * if x is below input range and returns last value of table if x is above range. + */ + + /** + * @addtogroup LinearInterpolate + * @{ + */ + + /** + * @brief Process function for the floating-point Linear Interpolation Function. + * @param[in,out] *S is an instance of the floating-point Linear Interpolation structure + * @param[in] x input sample to process + * @return y processed output sample. + * + */ + + static __INLINE float32_t arm_linear_interp_f32( + arm_linear_interp_instance_f32 * S, + float32_t x) + { + + float32_t y; + float32_t x0, x1; /* Nearest input values */ + float32_t y0, y1; /* Nearest output values */ + float32_t xSpacing = S->xSpacing; /* spacing between input values */ + int32_t i; /* Index variable */ + float32_t *pYData = S->pYData; /* pointer to output table */ + + /* Calculation of index */ + i = (x - S->x1) / xSpacing; + + if(i < 0) + { + /* Iniatilize output for below specified range as least output value of table */ + y = pYData[0]; + } + else if(i >= S->nValues) + { + /* Iniatilize output for above specified range as last output value of table */ + y = pYData[S->nValues-1]; + } + else + { + /* Calculation of nearest input values */ + x0 = S->x1 + i * xSpacing; + x1 = S->x1 + (i +1) * xSpacing; + + /* Read of nearest output values */ + y0 = pYData[i]; + y1 = pYData[i + 1]; + + /* Calculation of output */ + y = y0 + (x - x0) * ((y1 - y0)/(x1-x0)); + + } + + /* returns output value */ + return (y); + } + + /** + * + * @brief Process function for the Q31 Linear Interpolation Function. + * @param[in] *pYData pointer to Q31 Linear Interpolation table + * @param[in] x input sample to process + * @param[in] nValues number of table values + * @return y processed output sample. + * + * \par + * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. + * This function can support maximum of table size 2^12. + * + */ + + + static __INLINE q31_t arm_linear_interp_q31(q31_t *pYData, + q31_t x, uint32_t nValues) + { + q31_t y; /* output */ + q31_t y0, y1; /* Nearest output values */ + q31_t fract; /* fractional part */ + int32_t index; /* Index to read nearest output values */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + index = ((x & 0xFFF00000) >> 20); + + if(index >= (nValues - 1)) + { + return(pYData[nValues - 1]); + } + else if(index < 0) + { + return(pYData[0]); + } + else + { + + /* 20 bits for the fractional part */ + /* shift left by 11 to keep fract in 1.31 format */ + fract = (x & 0x000FFFFF) << 11; + + /* Read two nearest output values from the index in 1.31(q31) format */ + y0 = pYData[index]; + y1 = pYData[index + 1u]; + + /* Calculation of y0 * (1-fract) and y is in 2.30 format */ + y = ((q31_t) ((q63_t) y0 * (0x7FFFFFFF - fract) >> 32)); + + /* Calculation of y0 * (1-fract) + y1 *fract and y is in 2.30 format */ + y += ((q31_t) (((q63_t) y1 * fract) >> 32)); + + /* Convert y to 1.31 format */ + return (y << 1u); + + } + + } + + /** + * + * @brief Process function for the Q15 Linear Interpolation Function. + * @param[in] *pYData pointer to Q15 Linear Interpolation table + * @param[in] x input sample to process + * @param[in] nValues number of table values + * @return y processed output sample. + * + * \par + * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. + * This function can support maximum of table size 2^12. + * + */ + + + static __INLINE q15_t arm_linear_interp_q15(q15_t *pYData, q31_t x, uint32_t nValues) + { + q63_t y; /* output */ + q15_t y0, y1; /* Nearest output values */ + q31_t fract; /* fractional part */ + int32_t index; /* Index to read nearest output values */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + index = ((x & 0xFFF00000) >> 20u); + + if(index >= (nValues - 1)) + { + return(pYData[nValues - 1]); + } + else if(index < 0) + { + return(pYData[0]); + } + else + { + /* 20 bits for the fractional part */ + /* fract is in 12.20 format */ + fract = (x & 0x000FFFFF); + + /* Read two nearest output values from the index */ + y0 = pYData[index]; + y1 = pYData[index + 1u]; + + /* Calculation of y0 * (1-fract) and y is in 13.35 format */ + y = ((q63_t) y0 * (0xFFFFF - fract)); + + /* Calculation of (y0 * (1-fract) + y1 * fract) and y is in 13.35 format */ + y += ((q63_t) y1 * (fract)); + + /* convert y to 1.15 format */ + return (y >> 20); + } + + + } + + /** + * + * @brief Process function for the Q7 Linear Interpolation Function. + * @param[in] *pYData pointer to Q7 Linear Interpolation table + * @param[in] x input sample to process + * @param[in] nValues number of table values + * @return y processed output sample. + * + * \par + * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. + * This function can support maximum of table size 2^12. + */ + + + static __INLINE q7_t arm_linear_interp_q7(q7_t *pYData, q31_t x, uint32_t nValues) + { + q31_t y; /* output */ + q7_t y0, y1; /* Nearest output values */ + q31_t fract; /* fractional part */ + int32_t index; /* Index to read nearest output values */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + index = ((x & 0xFFF00000) >> 20u); + + + if(index >= (nValues - 1)) + { + return(pYData[nValues - 1]); + } + else if(index < 0) + { + return(pYData[0]); + } + else + { + + /* 20 bits for the fractional part */ + /* fract is in 12.20 format */ + fract = (x & 0x000FFFFF); + + /* Read two nearest output values from the index and are in 1.7(q7) format */ + y0 = pYData[index]; + y1 = pYData[index + 1u]; + + /* Calculation of y0 * (1-fract ) and y is in 13.27(q27) format */ + y = ((y0 * (0xFFFFF - fract))); + + /* Calculation of y1 * fract + y0 * (1-fract) and y is in 13.27(q27) format */ + y += (y1 * fract); + + /* convert y to 1.7(q7) format */ + return (y >> 20u); + + } + + } + /** + * @} end of LinearInterpolate group + */ + + /** + * @brief Fast approximation to the trigonometric sine function for floating-point data. + * @param[in] x input value in radians. + * @return sin(x). + */ + + float32_t arm_sin_f32( + float32_t x); + + /** + * @brief Fast approximation to the trigonometric sine function for Q31 data. + * @param[in] x Scaled input value in radians. + * @return sin(x). + */ + + q31_t arm_sin_q31( + q31_t x); + + /** + * @brief Fast approximation to the trigonometric sine function for Q15 data. + * @param[in] x Scaled input value in radians. + * @return sin(x). + */ + + q15_t arm_sin_q15( + q15_t x); + + /** + * @brief Fast approximation to the trigonometric cosine function for floating-point data. + * @param[in] x input value in radians. + * @return cos(x). + */ + + float32_t arm_cos_f32( + float32_t x); + + /** + * @brief Fast approximation to the trigonometric cosine function for Q31 data. + * @param[in] x Scaled input value in radians. + * @return cos(x). + */ + + q31_t arm_cos_q31( + q31_t x); + + /** + * @brief Fast approximation to the trigonometric cosine function for Q15 data. + * @param[in] x Scaled input value in radians. + * @return cos(x). + */ + + q15_t arm_cos_q15( + q15_t x); + + + /** + * @ingroup groupFastMath + */ + + + /** + * @defgroup SQRT Square Root + * + * Computes the square root of a number. + * There are separate functions for Q15, Q31, and floating-point data types. + * The square root function is computed using the Newton-Raphson algorithm. + * This is an iterative algorithm of the form: + *
+   *      x1 = x0 - f(x0)/f'(x0)
+   * 
+ * where x1 is the current estimate, + * x0 is the previous estimate and + * f'(x0) is the derivative of f() evaluated at x0. + * For the square root function, the algorithm reduces to: + *
+   *     x0 = in/2                         [initial guess]
+   *     x1 = 1/2 * ( x0 + in / x0)        [each iteration]
+   * 
+ */ + + + /** + * @addtogroup SQRT + * @{ + */ + + /** + * @brief Floating-point square root function. + * @param[in] in input value. + * @param[out] *pOut square root of input value. + * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if + * in is negative value and returns zero output for negative values. + */ + + static __INLINE arm_status arm_sqrt_f32( + float32_t in, float32_t *pOut) + { + if(in > 0) + { + +// #if __FPU_USED + #if (__FPU_USED == 1) && defined ( __CC_ARM ) + *pOut = __sqrtf(in); + #else + *pOut = sqrtf(in); + #endif + + return (ARM_MATH_SUCCESS); + } + else + { + *pOut = 0.0f; + return (ARM_MATH_ARGUMENT_ERROR); + } + + } + + + /** + * @brief Q31 square root function. + * @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF. + * @param[out] *pOut square root of input value. + * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if + * in is negative value and returns zero output for negative values. + */ + arm_status arm_sqrt_q31( + q31_t in, q31_t *pOut); + + /** + * @brief Q15 square root function. + * @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF. + * @param[out] *pOut square root of input value. + * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if + * in is negative value and returns zero output for negative values. + */ + arm_status arm_sqrt_q15( + q15_t in, q15_t *pOut); + + /** + * @} end of SQRT group + */ + + + + + + + /** + * @brief floating-point Circular write function. + */ + + static __INLINE void arm_circularWrite_f32( + int32_t * circBuffer, + int32_t L, + uint16_t * writeOffset, + int32_t bufferInc, + const int32_t * src, + int32_t srcInc, + uint32_t blockSize) + { + uint32_t i = 0u; + int32_t wOffset; + + /* Copy the value of Index pointer that points + * to the current location where the input samples to be copied */ + wOffset = *writeOffset; + + /* Loop over the blockSize */ + i = blockSize; + + while(i > 0u) + { + /* copy the input sample to the circular buffer */ + circBuffer[wOffset] = *src; + + /* Update the input pointer */ + src += srcInc; + + /* Circularly update wOffset. Watch out for positive and negative value */ + wOffset += bufferInc; + if(wOffset >= L) + wOffset -= L; + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *writeOffset = wOffset; + } + + + + /** + * @brief floating-point Circular Read function. + */ + static __INLINE void arm_circularRead_f32( + int32_t * circBuffer, + int32_t L, + int32_t * readOffset, + int32_t bufferInc, + int32_t * dst, + int32_t * dst_base, + int32_t dst_length, + int32_t dstInc, + uint32_t blockSize) + { + uint32_t i = 0u; + int32_t rOffset, dst_end; + + /* Copy the value of Index pointer that points + * to the current location from where the input samples to be read */ + rOffset = *readOffset; + dst_end = (int32_t) (dst_base + dst_length); + + /* Loop over the blockSize */ + i = blockSize; + + while(i > 0u) + { + /* copy the sample from the circular buffer to the destination buffer */ + *dst = circBuffer[rOffset]; + + /* Update the input pointer */ + dst += dstInc; + + if(dst == (int32_t *) dst_end) + { + dst = dst_base; + } + + /* Circularly update rOffset. Watch out for positive and negative value */ + rOffset += bufferInc; + + if(rOffset >= L) + { + rOffset -= L; + } + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *readOffset = rOffset; + } + + /** + * @brief Q15 Circular write function. + */ + + static __INLINE void arm_circularWrite_q15( + q15_t * circBuffer, + int32_t L, + uint16_t * writeOffset, + int32_t bufferInc, + const q15_t * src, + int32_t srcInc, + uint32_t blockSize) + { + uint32_t i = 0u; + int32_t wOffset; + + /* Copy the value of Index pointer that points + * to the current location where the input samples to be copied */ + wOffset = *writeOffset; + + /* Loop over the blockSize */ + i = blockSize; + + while(i > 0u) + { + /* copy the input sample to the circular buffer */ + circBuffer[wOffset] = *src; + + /* Update the input pointer */ + src += srcInc; + + /* Circularly update wOffset. Watch out for positive and negative value */ + wOffset += bufferInc; + if(wOffset >= L) + wOffset -= L; + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *writeOffset = wOffset; + } + + + + /** + * @brief Q15 Circular Read function. + */ + static __INLINE void arm_circularRead_q15( + q15_t * circBuffer, + int32_t L, + int32_t * readOffset, + int32_t bufferInc, + q15_t * dst, + q15_t * dst_base, + int32_t dst_length, + int32_t dstInc, + uint32_t blockSize) + { + uint32_t i = 0; + int32_t rOffset, dst_end; + + /* Copy the value of Index pointer that points + * to the current location from where the input samples to be read */ + rOffset = *readOffset; + + dst_end = (int32_t) (dst_base + dst_length); + + /* Loop over the blockSize */ + i = blockSize; + + while(i > 0u) + { + /* copy the sample from the circular buffer to the destination buffer */ + *dst = circBuffer[rOffset]; + + /* Update the input pointer */ + dst += dstInc; + + if(dst == (q15_t *) dst_end) + { + dst = dst_base; + } + + /* Circularly update wOffset. Watch out for positive and negative value */ + rOffset += bufferInc; + + if(rOffset >= L) + { + rOffset -= L; + } + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *readOffset = rOffset; + } + + + /** + * @brief Q7 Circular write function. + */ + + static __INLINE void arm_circularWrite_q7( + q7_t * circBuffer, + int32_t L, + uint16_t * writeOffset, + int32_t bufferInc, + const q7_t * src, + int32_t srcInc, + uint32_t blockSize) + { + uint32_t i = 0u; + int32_t wOffset; + + /* Copy the value of Index pointer that points + * to the current location where the input samples to be copied */ + wOffset = *writeOffset; + + /* Loop over the blockSize */ + i = blockSize; + + while(i > 0u) + { + /* copy the input sample to the circular buffer */ + circBuffer[wOffset] = *src; + + /* Update the input pointer */ + src += srcInc; + + /* Circularly update wOffset. Watch out for positive and negative value */ + wOffset += bufferInc; + if(wOffset >= L) + wOffset -= L; + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *writeOffset = wOffset; + } + + + + /** + * @brief Q7 Circular Read function. + */ + static __INLINE void arm_circularRead_q7( + q7_t * circBuffer, + int32_t L, + int32_t * readOffset, + int32_t bufferInc, + q7_t * dst, + q7_t * dst_base, + int32_t dst_length, + int32_t dstInc, + uint32_t blockSize) + { + uint32_t i = 0; + int32_t rOffset, dst_end; + + /* Copy the value of Index pointer that points + * to the current location from where the input samples to be read */ + rOffset = *readOffset; + + dst_end = (int32_t) (dst_base + dst_length); + + /* Loop over the blockSize */ + i = blockSize; + + while(i > 0u) + { + /* copy the sample from the circular buffer to the destination buffer */ + *dst = circBuffer[rOffset]; + + /* Update the input pointer */ + dst += dstInc; + + if(dst == (q7_t *) dst_end) + { + dst = dst_base; + } + + /* Circularly update rOffset. Watch out for positive and negative value */ + rOffset += bufferInc; + + if(rOffset >= L) + { + rOffset -= L; + } + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *readOffset = rOffset; + } + + + /** + * @brief Sum of the squares of the elements of a Q31 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_power_q31( + q31_t * pSrc, + uint32_t blockSize, + q63_t * pResult); + + /** + * @brief Sum of the squares of the elements of a floating-point vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_power_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + /** + * @brief Sum of the squares of the elements of a Q15 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_power_q15( + q15_t * pSrc, + uint32_t blockSize, + q63_t * pResult); + + /** + * @brief Sum of the squares of the elements of a Q7 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_power_q7( + q7_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + /** + * @brief Mean value of a Q7 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_mean_q7( + q7_t * pSrc, + uint32_t blockSize, + q7_t * pResult); + + /** + * @brief Mean value of a Q15 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + void arm_mean_q15( + q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + /** + * @brief Mean value of a Q31 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + void arm_mean_q31( + q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + /** + * @brief Mean value of a floating-point vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + void arm_mean_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + /** + * @brief Variance of the elements of a floating-point vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_var_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + /** + * @brief Variance of the elements of a Q31 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_var_q31( + q31_t * pSrc, + uint32_t blockSize, + q63_t * pResult); + + /** + * @brief Variance of the elements of a Q15 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_var_q15( + q15_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + /** + * @brief Root Mean Square of the elements of a floating-point vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_rms_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + /** + * @brief Root Mean Square of the elements of a Q31 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_rms_q31( + q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + /** + * @brief Root Mean Square of the elements of a Q15 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_rms_q15( + q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + /** + * @brief Standard deviation of the elements of a floating-point vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_std_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + /** + * @brief Standard deviation of the elements of a Q31 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_std_q31( + q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + /** + * @brief Standard deviation of the elements of a Q15 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output value. + * @return none. + */ + + void arm_std_q15( + q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + /** + * @brief Floating-point complex magnitude + * @param[in] *pSrc points to the complex input vector + * @param[out] *pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + * @return none. + */ + + void arm_cmplx_mag_f32( + float32_t * pSrc, + float32_t * pDst, + uint32_t numSamples); + + /** + * @brief Q31 complex magnitude + * @param[in] *pSrc points to the complex input vector + * @param[out] *pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + * @return none. + */ + + void arm_cmplx_mag_q31( + q31_t * pSrc, + q31_t * pDst, + uint32_t numSamples); + + /** + * @brief Q15 complex magnitude + * @param[in] *pSrc points to the complex input vector + * @param[out] *pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + * @return none. + */ + + void arm_cmplx_mag_q15( + q15_t * pSrc, + q15_t * pDst, + uint32_t numSamples); + + /** + * @brief Q15 complex dot product + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] numSamples number of complex samples in each vector + * @param[out] *realResult real part of the result returned here + * @param[out] *imagResult imaginary part of the result returned here + * @return none. + */ + + void arm_cmplx_dot_prod_q15( + q15_t * pSrcA, + q15_t * pSrcB, + uint32_t numSamples, + q31_t * realResult, + q31_t * imagResult); + + /** + * @brief Q31 complex dot product + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] numSamples number of complex samples in each vector + * @param[out] *realResult real part of the result returned here + * @param[out] *imagResult imaginary part of the result returned here + * @return none. + */ + + void arm_cmplx_dot_prod_q31( + q31_t * pSrcA, + q31_t * pSrcB, + uint32_t numSamples, + q63_t * realResult, + q63_t * imagResult); + + /** + * @brief Floating-point complex dot product + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] numSamples number of complex samples in each vector + * @param[out] *realResult real part of the result returned here + * @param[out] *imagResult imaginary part of the result returned here + * @return none. + */ + + void arm_cmplx_dot_prod_f32( + float32_t * pSrcA, + float32_t * pSrcB, + uint32_t numSamples, + float32_t * realResult, + float32_t * imagResult); + + /** + * @brief Q15 complex-by-real multiplication + * @param[in] *pSrcCmplx points to the complex input vector + * @param[in] *pSrcReal points to the real input vector + * @param[out] *pCmplxDst points to the complex output vector + * @param[in] numSamples number of samples in each vector + * @return none. + */ + + void arm_cmplx_mult_real_q15( + q15_t * pSrcCmplx, + q15_t * pSrcReal, + q15_t * pCmplxDst, + uint32_t numSamples); + + /** + * @brief Q31 complex-by-real multiplication + * @param[in] *pSrcCmplx points to the complex input vector + * @param[in] *pSrcReal points to the real input vector + * @param[out] *pCmplxDst points to the complex output vector + * @param[in] numSamples number of samples in each vector + * @return none. + */ + + void arm_cmplx_mult_real_q31( + q31_t * pSrcCmplx, + q31_t * pSrcReal, + q31_t * pCmplxDst, + uint32_t numSamples); + + /** + * @brief Floating-point complex-by-real multiplication + * @param[in] *pSrcCmplx points to the complex input vector + * @param[in] *pSrcReal points to the real input vector + * @param[out] *pCmplxDst points to the complex output vector + * @param[in] numSamples number of samples in each vector + * @return none. + */ + + void arm_cmplx_mult_real_f32( + float32_t * pSrcCmplx, + float32_t * pSrcReal, + float32_t * pCmplxDst, + uint32_t numSamples); + + /** + * @brief Minimum value of a Q7 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *result is output pointer + * @param[in] index is the array index of the minimum value in the input buffer. + * @return none. + */ + + void arm_min_q7( + q7_t * pSrc, + uint32_t blockSize, + q7_t * result, + uint32_t * index); + + /** + * @brief Minimum value of a Q15 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output pointer + * @param[in] *pIndex is the array index of the minimum value in the input buffer. + * @return none. + */ + + void arm_min_q15( + q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult, + uint32_t * pIndex); + + /** + * @brief Minimum value of a Q31 vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output pointer + * @param[out] *pIndex is the array index of the minimum value in the input buffer. + * @return none. + */ + void arm_min_q31( + q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult, + uint32_t * pIndex); + + /** + * @brief Minimum value of a floating-point vector. + * @param[in] *pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] *pResult is output pointer + * @param[out] *pIndex is the array index of the minimum value in the input buffer. + * @return none. + */ + + void arm_min_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult, + uint32_t * pIndex); + +/** + * @brief Maximum value of a Q7 vector. + * @param[in] *pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] *pResult maximum value returned here + * @param[out] *pIndex index of maximum value returned here + * @return none. + */ + + void arm_max_q7( + q7_t * pSrc, + uint32_t blockSize, + q7_t * pResult, + uint32_t * pIndex); + +/** + * @brief Maximum value of a Q15 vector. + * @param[in] *pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] *pResult maximum value returned here + * @param[out] *pIndex index of maximum value returned here + * @return none. + */ + + void arm_max_q15( + q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult, + uint32_t * pIndex); + +/** + * @brief Maximum value of a Q31 vector. + * @param[in] *pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] *pResult maximum value returned here + * @param[out] *pIndex index of maximum value returned here + * @return none. + */ + + void arm_max_q31( + q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult, + uint32_t * pIndex); + +/** + * @brief Maximum value of a floating-point vector. + * @param[in] *pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] *pResult maximum value returned here + * @param[out] *pIndex index of maximum value returned here + * @return none. + */ + + void arm_max_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult, + uint32_t * pIndex); + + /** + * @brief Q15 complex-by-complex multiplication + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + * @return none. + */ + + void arm_cmplx_mult_cmplx_q15( + q15_t * pSrcA, + q15_t * pSrcB, + q15_t * pDst, + uint32_t numSamples); + + /** + * @brief Q31 complex-by-complex multiplication + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + * @return none. + */ + + void arm_cmplx_mult_cmplx_q31( + q31_t * pSrcA, + q31_t * pSrcB, + q31_t * pDst, + uint32_t numSamples); + + /** + * @brief Floating-point complex-by-complex multiplication + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + * @return none. + */ + + void arm_cmplx_mult_cmplx_f32( + float32_t * pSrcA, + float32_t * pSrcB, + float32_t * pDst, + uint32_t numSamples); + + /** + * @brief Converts the elements of the floating-point vector to Q31 vector. + * @param[in] *pSrc points to the floating-point input vector + * @param[out] *pDst points to the Q31 output vector + * @param[in] blockSize length of the input vector + * @return none. + */ + void arm_float_to_q31( + float32_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Converts the elements of the floating-point vector to Q15 vector. + * @param[in] *pSrc points to the floating-point input vector + * @param[out] *pDst points to the Q15 output vector + * @param[in] blockSize length of the input vector + * @return none + */ + void arm_float_to_q15( + float32_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Converts the elements of the floating-point vector to Q7 vector. + * @param[in] *pSrc points to the floating-point input vector + * @param[out] *pDst points to the Q7 output vector + * @param[in] blockSize length of the input vector + * @return none + */ + void arm_float_to_q7( + float32_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q31 vector to Q15 vector. + * @param[in] *pSrc is input pointer + * @param[out] *pDst is output pointer + * @param[in] blockSize is the number of samples to process + * @return none. + */ + void arm_q31_to_q15( + q31_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Converts the elements of the Q31 vector to Q7 vector. + * @param[in] *pSrc is input pointer + * @param[out] *pDst is output pointer + * @param[in] blockSize is the number of samples to process + * @return none. + */ + void arm_q31_to_q7( + q31_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Converts the elements of the Q15 vector to floating-point vector. + * @param[in] *pSrc is input pointer + * @param[out] *pDst is output pointer + * @param[in] blockSize is the number of samples to process + * @return none. + */ + void arm_q15_to_float( + q15_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q15 vector to Q31 vector. + * @param[in] *pSrc is input pointer + * @param[out] *pDst is output pointer + * @param[in] blockSize is the number of samples to process + * @return none. + */ + void arm_q15_to_q31( + q15_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q15 vector to Q7 vector. + * @param[in] *pSrc is input pointer + * @param[out] *pDst is output pointer + * @param[in] blockSize is the number of samples to process + * @return none. + */ + void arm_q15_to_q7( + q15_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @ingroup groupInterpolation + */ + + /** + * @defgroup BilinearInterpolate Bilinear Interpolation + * + * Bilinear interpolation is an extension of linear interpolation applied to a two dimensional grid. + * The underlying function f(x, y) is sampled on a regular grid and the interpolation process + * determines values between the grid points. + * Bilinear interpolation is equivalent to two step linear interpolation, first in the x-dimension and then in the y-dimension. + * Bilinear interpolation is often used in image processing to rescale images. + * The CMSIS DSP library provides bilinear interpolation functions for Q7, Q15, Q31, and floating-point data types. + * + * Algorithm + * \par + * The instance structure used by the bilinear interpolation functions describes a two dimensional data table. + * For floating-point, the instance structure is defined as: + *
+   *   typedef struct
+   *   {
+   *     uint16_t numRows;
+   *     uint16_t numCols;
+   *     float32_t *pData;
+   * } arm_bilinear_interp_instance_f32;
+   * 
+ * + * \par + * where numRows specifies the number of rows in the table; + * numCols specifies the number of columns in the table; + * and pData points to an array of size numRows*numCols values. + * The data table pTable is organized in row order and the supplied data values fall on integer indexes. + * That is, table element (x,y) is located at pTable[x + y*numCols] where x and y are integers. + * + * \par + * Let (x, y) specify the desired interpolation point. Then define: + *
+   *     XF = floor(x)
+   *     YF = floor(y)
+   * 
+ * \par + * The interpolated output point is computed as: + *
+   *  f(x, y) = f(XF, YF) * (1-(x-XF)) * (1-(y-YF))
+   *           + f(XF+1, YF) * (x-XF)*(1-(y-YF))
+   *           + f(XF, YF+1) * (1-(x-XF))*(y-YF)
+   *           + f(XF+1, YF+1) * (x-XF)*(y-YF)
+   * 
+ * Note that the coordinates (x, y) contain integer and fractional components. + * The integer components specify which portion of the table to use while the + * fractional components control the interpolation processor. + * + * \par + * if (x,y) are outside of the table boundary, Bilinear interpolation returns zero output. + */ + + /** + * @addtogroup BilinearInterpolate + * @{ + */ + + /** + * + * @brief Floating-point bilinear interpolation. + * @param[in,out] *S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate. + * @param[in] Y interpolation coordinate. + * @return out interpolated value. + */ + + + static __INLINE float32_t arm_bilinear_interp_f32( + const arm_bilinear_interp_instance_f32 * S, + float32_t X, + float32_t Y) + { + float32_t out; + float32_t f00, f01, f10, f11; + float32_t *pData = S->pData; + int32_t xIndex, yIndex, index; + float32_t xdiff, ydiff; + float32_t b1, b2, b3, b4; + + xIndex = (int32_t) X; + yIndex = (int32_t) Y; + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if(xIndex < 0 || xIndex > (S->numRows-1) || yIndex < 0 || yIndex > ( S->numCols-1)) + { + return(0); + } + + /* Calculation of index for two nearest points in X-direction */ + index = (xIndex - 1) + (yIndex-1) * S->numCols ; + + + /* Read two nearest points in X-direction */ + f00 = pData[index]; + f01 = pData[index + 1]; + + /* Calculation of index for two nearest points in Y-direction */ + index = (xIndex-1) + (yIndex) * S->numCols; + + + /* Read two nearest points in Y-direction */ + f10 = pData[index]; + f11 = pData[index + 1]; + + /* Calculation of intermediate values */ + b1 = f00; + b2 = f01 - f00; + b3 = f10 - f00; + b4 = f00 - f01 - f10 + f11; + + /* Calculation of fractional part in X */ + xdiff = X - xIndex; + + /* Calculation of fractional part in Y */ + ydiff = Y - yIndex; + + /* Calculation of bi-linear interpolated output */ + out = b1 + b2 * xdiff + b3 * ydiff + b4 * xdiff * ydiff; + + /* return to application */ + return (out); + + } + + /** + * + * @brief Q31 bilinear interpolation. + * @param[in,out] *S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate in 12.20 format. + * @param[in] Y interpolation coordinate in 12.20 format. + * @return out interpolated value. + */ + + static __INLINE q31_t arm_bilinear_interp_q31( + arm_bilinear_interp_instance_q31 * S, + q31_t X, + q31_t Y) + { + q31_t out; /* Temporary output */ + q31_t acc = 0; /* output */ + q31_t xfract, yfract; /* X, Y fractional parts */ + q31_t x1, x2, y1, y2; /* Nearest output values */ + int32_t rI, cI; /* Row and column indices */ + q31_t *pYData = S->pData; /* pointer to output table values */ + uint32_t nCols = S->numCols; /* num of rows */ + + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + rI = ((X & 0xFFF00000) >> 20u); + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + cI = ((Y & 0xFFF00000) >> 20u); + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if(rI < 0 || rI > (S->numRows-1) || cI < 0 || cI > ( S->numCols-1)) + { + return(0); + } + + /* 20 bits for the fractional part */ + /* shift left xfract by 11 to keep 1.31 format */ + xfract = (X & 0x000FFFFF) << 11u; + + /* Read two nearest output values from the index */ + x1 = pYData[(rI) + nCols * (cI)]; + x2 = pYData[(rI) + nCols * (cI) + 1u]; + + /* 20 bits for the fractional part */ + /* shift left yfract by 11 to keep 1.31 format */ + yfract = (Y & 0x000FFFFF) << 11u; + + /* Read two nearest output values from the index */ + y1 = pYData[(rI) + nCols * (cI + 1)]; + y2 = pYData[(rI) + nCols * (cI + 1) + 1u]; + + /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 3.29(q29) format */ + out = ((q31_t) (((q63_t) x1 * (0x7FFFFFFF - xfract)) >> 32)); + acc = ((q31_t) (((q63_t) out * (0x7FFFFFFF - yfract)) >> 32)); + + /* x2 * (xfract) * (1-yfract) in 3.29(q29) and adding to acc */ + out = ((q31_t) ((q63_t) x2 * (0x7FFFFFFF - yfract) >> 32)); + acc += ((q31_t) ((q63_t) out * (xfract) >> 32)); + + /* y1 * (1 - xfract) * (yfract) in 3.29(q29) and adding to acc */ + out = ((q31_t) ((q63_t) y1 * (0x7FFFFFFF - xfract) >> 32)); + acc += ((q31_t) ((q63_t) out * (yfract) >> 32)); + + /* y2 * (xfract) * (yfract) in 3.29(q29) and adding to acc */ + out = ((q31_t) ((q63_t) y2 * (xfract) >> 32)); + acc += ((q31_t) ((q63_t) out * (yfract) >> 32)); + + /* Convert acc to 1.31(q31) format */ + return (acc << 2u); + + } + + /** + * @brief Q15 bilinear interpolation. + * @param[in,out] *S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate in 12.20 format. + * @param[in] Y interpolation coordinate in 12.20 format. + * @return out interpolated value. + */ + + static __INLINE q15_t arm_bilinear_interp_q15( + arm_bilinear_interp_instance_q15 * S, + q31_t X, + q31_t Y) + { + q63_t acc = 0; /* output */ + q31_t out; /* Temporary output */ + q15_t x1, x2, y1, y2; /* Nearest output values */ + q31_t xfract, yfract; /* X, Y fractional parts */ + int32_t rI, cI; /* Row and column indices */ + q15_t *pYData = S->pData; /* pointer to output table values */ + uint32_t nCols = S->numCols; /* num of rows */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + rI = ((X & 0xFFF00000) >> 20); + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + cI = ((Y & 0xFFF00000) >> 20); + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if(rI < 0 || rI > (S->numRows-1) || cI < 0 || cI > ( S->numCols-1)) + { + return(0); + } + + /* 20 bits for the fractional part */ + /* xfract should be in 12.20 format */ + xfract = (X & 0x000FFFFF); + + /* Read two nearest output values from the index */ + x1 = pYData[(rI) + nCols * (cI)]; + x2 = pYData[(rI) + nCols * (cI) + 1u]; + + + /* 20 bits for the fractional part */ + /* yfract should be in 12.20 format */ + yfract = (Y & 0x000FFFFF); + + /* Read two nearest output values from the index */ + y1 = pYData[(rI) + nCols * (cI + 1)]; + y2 = pYData[(rI) + nCols * (cI + 1) + 1u]; + + /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 13.51 format */ + + /* x1 is in 1.15(q15), xfract in 12.20 format and out is in 13.35 format */ + /* convert 13.35 to 13.31 by right shifting and out is in 1.31 */ + out = (q31_t) (((q63_t) x1 * (0xFFFFF - xfract)) >> 4u); + acc = ((q63_t) out * (0xFFFFF - yfract)); + + /* x2 * (xfract) * (1-yfract) in 1.51 and adding to acc */ + out = (q31_t) (((q63_t) x2 * (0xFFFFF - yfract)) >> 4u); + acc += ((q63_t) out * (xfract)); + + /* y1 * (1 - xfract) * (yfract) in 1.51 and adding to acc */ + out = (q31_t) (((q63_t) y1 * (0xFFFFF - xfract)) >> 4u); + acc += ((q63_t) out * (yfract)); + + /* y2 * (xfract) * (yfract) in 1.51 and adding to acc */ + out = (q31_t) (((q63_t) y2 * (xfract)) >> 4u); + acc += ((q63_t) out * (yfract)); + + /* acc is in 13.51 format and down shift acc by 36 times */ + /* Convert out to 1.15 format */ + return (acc >> 36); + + } + + /** + * @brief Q7 bilinear interpolation. + * @param[in,out] *S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate in 12.20 format. + * @param[in] Y interpolation coordinate in 12.20 format. + * @return out interpolated value. + */ + + static __INLINE q7_t arm_bilinear_interp_q7( + arm_bilinear_interp_instance_q7 * S, + q31_t X, + q31_t Y) + { + q63_t acc = 0; /* output */ + q31_t out; /* Temporary output */ + q31_t xfract, yfract; /* X, Y fractional parts */ + q7_t x1, x2, y1, y2; /* Nearest output values */ + int32_t rI, cI; /* Row and column indices */ + q7_t *pYData = S->pData; /* pointer to output table values */ + uint32_t nCols = S->numCols; /* num of rows */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + rI = ((X & 0xFFF00000) >> 20); + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + cI = ((Y & 0xFFF00000) >> 20); + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if(rI < 0 || rI > (S->numRows-1) || cI < 0 || cI > ( S->numCols-1)) + { + return(0); + } + + /* 20 bits for the fractional part */ + /* xfract should be in 12.20 format */ + xfract = (X & 0x000FFFFF); + + /* Read two nearest output values from the index */ + x1 = pYData[(rI) + nCols * (cI)]; + x2 = pYData[(rI) + nCols * (cI) + 1u]; + + + /* 20 bits for the fractional part */ + /* yfract should be in 12.20 format */ + yfract = (Y & 0x000FFFFF); + + /* Read two nearest output values from the index */ + y1 = pYData[(rI) + nCols * (cI + 1)]; + y2 = pYData[(rI) + nCols * (cI + 1) + 1u]; + + /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 16.47 format */ + out = ((x1 * (0xFFFFF - xfract))); + acc = (((q63_t) out * (0xFFFFF - yfract))); + + /* x2 * (xfract) * (1-yfract) in 2.22 and adding to acc */ + out = ((x2 * (0xFFFFF - yfract))); + acc += (((q63_t) out * (xfract))); + + /* y1 * (1 - xfract) * (yfract) in 2.22 and adding to acc */ + out = ((y1 * (0xFFFFF - xfract))); + acc += (((q63_t) out * (yfract))); + + /* y2 * (xfract) * (yfract) in 2.22 and adding to acc */ + out = ((y2 * (yfract))); + acc += (((q63_t) out * (xfract))); + + /* acc in 16.47 format and down shift by 40 to convert to 1.7 format */ + return (acc >> 40); + + } + + /** + * @} end of BilinearInterpolate group + */ + + + + + + +#ifdef __cplusplus +} +#endif + + +#endif /* _ARM_MATH_H */ + + +/** + * + * End of file. + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm0.h b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm0.h new file mode 100644 index 000000000..9d7a19f9a --- /dev/null +++ b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm0.h @@ -0,0 +1,665 @@ +/**************************************************************************//** + * @file core_cm0.h + * @brief CMSIS Cortex-M0 Core Peripheral Access Layer Header File + * @version V2.10 + * @date 19. July 2011 + * + * @note + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#endif + +#ifdef __cplusplus + extern "C" { +#endif + +#ifndef __CORE_CM0_H_GENERIC +#define __CORE_CM0_H_GENERIC + + +/** \mainpage CMSIS Cortex-M0 + + This documentation describes the CMSIS Cortex-M Core Peripheral Access Layer. + It consists of: + + - Cortex-M Core Register Definitions + - Cortex-M functions + - Cortex-M instructions + + The CMSIS Cortex-M0 Core Peripheral Access Layer contains C and assembly functions that ease + access to the Cortex-M Core + */ + +/** \defgroup CMSIS_MISRA_Exceptions CMSIS MISRA-C:2004 Compliance Exceptions + CMSIS violates following MISRA-C2004 Rules: + + - Violates MISRA 2004 Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + - Violates MISRA 2004 Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + - Violates MISRA 2004 Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** \defgroup CMSIS_core_definitions CMSIS Core Definitions + This file defines all structures and symbols for CMSIS core: + - CMSIS version number + - Cortex-M core + - Cortex-M core Revision Number + @{ + */ + +/* CMSIS CM0 definitions */ +#define __CM0_CMSIS_VERSION_MAIN (0x02) /*!< [31:16] CMSIS HAL main version */ +#define __CM0_CMSIS_VERSION_SUB (0x10) /*!< [15:0] CMSIS HAL sub version */ +#define __CM0_CMSIS_VERSION ((__CM0_CMSIS_VERSION_MAIN << 16) | __CM0_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x00) /*!< Cortex core */ + + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */ + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + +#endif + +/*!< __FPU_USED to be checked prior to making use of FPU specific registers and functions */ +#define __FPU_USED 0 + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + /* add preprocessor checks */ +#endif + +#include /*!< standard types definitions */ +#include "core_cmInstr.h" /*!< Core Instruction Access */ +#include "core_cmFunc.h" /*!< Core Function Access */ + +#endif /* __CORE_CM0_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM0_H_DEPENDANT +#define __CORE_CM0_H_DEPENDANT + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM0_REV + #define __CM0_REV 0x0000 + #warning "__CM0_REV not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 2 + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0 + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +#ifdef __cplusplus + #define __I volatile /*!< defines 'read only' permissions */ +#else + #define __I volatile const /*!< defines 'read only' permissions */ +#endif +#define __O volatile /*!< defines 'write only' permissions */ +#define __IO volatile /*!< defines 'read / write' permissions */ + +/*@} end of group CMSIS_core_definitions */ + + + +/******************************************************************************* + * Register Abstraction + ******************************************************************************/ +/** \defgroup CMSIS_core_register CMSIS Core Register + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register +*/ + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CORE CMSIS Core + Type definitions for the Cortex-M Core Registers + @{ + */ + +/** \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ +#else + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ +#endif + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + + +/** \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + + +/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ +#else + uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ +#endif + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + + +/** \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ + uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/*@} end of group CMSIS_CORE */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC CMSIS NVIC + Type definitions for the Cortex-M NVIC Registers + @{ + */ + +/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IO uint32_t ISER[1]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[31]; + __IO uint32_t ICER[1]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[31]; + __IO uint32_t ISPR[1]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[31]; + __IO uint32_t ICPR[1]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[31]; + uint32_t RESERVED4[64]; + __IO uint32_t IP[8]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ +} NVIC_Type; + +/*@} end of group CMSIS_NVIC */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCB CMSIS SCB + Type definitions for the Cortex-M System Control Block Registers + @{ + */ + +/** \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + uint32_t RESERVED0; + __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + uint32_t RESERVED1; + __IO uint32_t SHP[2]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ + __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick CMSIS SysTick + Type definitions for the Cortex-M System Timer Registers + @{ + */ + +/** \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug CMSIS Core Debug + Cortex-M0 Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP + and not via processor. Therefore they are not covered by the Cortex-M0 header file. + @{ + */ +/*@} end of group CMSIS_CoreDebug */ + + +/** \ingroup CMSIS_core_register + @{ + */ + +/* Memory mapping of Cortex-M0 Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ + + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + ******************************************************************************/ +/** \defgroup CMSIS_Core_FunctionInterface CMSIS Core Function Interface + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Register Access Functions +*/ + + + +/* ########################## NVIC functions #################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions CMSIS Core NVIC Functions + @{ + */ + +/* Interrupt Priorities are WORD accessible only under ARMv6M */ +/* The following MACROS handle generation of the register offset and byte masks */ +#define _BIT_SHIFT(IRQn) ( (((uint32_t)(IRQn) ) & 0x03) * 8 ) +#define _SHP_IDX(IRQn) ( ((((uint32_t)(IRQn) & 0x0F)-8) >> 2) ) +#define _IP_IDX(IRQn) ( ((uint32_t)(IRQn) >> 2) ) + + +/** \brief Enable External Interrupt + + This function enables a device specific interrupt in the NVIC interrupt controller. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the external interrupt to enable + */ +static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + NVIC->ISER[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); +} + + +/** \brief Disable External Interrupt + + This function disables a device specific interrupt in the NVIC interrupt controller. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the external interrupt to disable + */ +static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); +} + + +/** \brief Get Pending Interrupt + + This function reads the pending register in the NVIC and returns the pending bit + for the specified interrupt. + + \param [in] IRQn Number of the interrupt for get pending + \return 0 Interrupt status is not pending + \return 1 Interrupt status is pending + */ +static __INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t) ((NVIC->ISPR[0] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); +} + + +/** \brief Set Pending Interrupt + + This function sets the pending bit for the specified interrupt. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the interrupt for set pending + */ +static __INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); +} + + +/** \brief Clear Pending Interrupt + + This function clears the pending bit for the specified interrupt. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the interrupt for clear pending + */ +static __INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[0] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ +} + + +/** \brief Set Interrupt Priority + + This function sets the priority for the specified interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + Note: The priority cannot be set for every core interrupt. + + \param [in] IRQn Number of the interrupt for set priority + \param [in] priority Priority to set + */ +static __INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if(IRQn < 0) { + SCB->SHP[_SHP_IDX(IRQn)] = (SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFF << _BIT_SHIFT(IRQn))) | + (((priority << (8 - __NVIC_PRIO_BITS)) & 0xFF) << _BIT_SHIFT(IRQn)); } + else { + NVIC->IP[_IP_IDX(IRQn)] = (NVIC->IP[_IP_IDX(IRQn)] & ~(0xFF << _BIT_SHIFT(IRQn))) | + (((priority << (8 - __NVIC_PRIO_BITS)) & 0xFF) << _BIT_SHIFT(IRQn)); } +} + + +/** \brief Get Interrupt Priority + + This function reads the priority for the specified interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + The returned priority value is automatically aligned to the implemented + priority bits of the microcontroller. + + \param [in] IRQn Number of the interrupt for get priority + \return Interrupt Priority + */ +static __INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if(IRQn < 0) { + return((uint32_t)((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M0 system interrupts */ + else { + return((uint32_t)((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ +} + + +/** \brief System Reset + + This function initiate a system reset request to reset the MCU. + */ +static __INLINE void NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + SCB_AIRCR_SYSRESETREQ_Msk); + __DSB(); /* Ensure completion of memory access */ + while(1); /* wait until reset */ +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions CMSIS Core SysTick Functions + @{ + */ + +#if (__Vendor_SysTickConfig == 0) + +/** \brief System Tick Configuration + + This function initialises the system tick timer and its interrupt and start the system tick timer. + Counter is in free running mode to generate periodical interrupts. + + \param [in] ticks Number of ticks between two interrupts + \return 0 Function succeeded + \return 1 Function failed + */ +static __INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + + SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Cortex-M0 System Interrupts */ + SysTick->VAL = 0; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + + +#endif /* __CORE_CM0_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ + +#ifdef __cplusplus +} +#endif diff --git a/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm3.h b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm3.h new file mode 100644 index 000000000..1c688181a --- /dev/null +++ b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm3.h @@ -0,0 +1,1236 @@ +/**************************************************************************//** + * @file core_cm3.h + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File + * @version V2.10 + * @date 19. July 2011 + * + * @note + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#endif + +#ifdef __cplusplus + extern "C" { +#endif + +#ifndef __CORE_CM3_H_GENERIC +#define __CORE_CM3_H_GENERIC + + +/** \mainpage CMSIS Cortex-M3 + + This documentation describes the CMSIS Cortex-M Core Peripheral Access Layer. + It consists of: + + - Cortex-M Core Register Definitions + - Cortex-M functions + - Cortex-M instructions + + The CMSIS Cortex-M3 Core Peripheral Access Layer contains C and assembly functions that ease + access to the Cortex-M Core + */ + +/** \defgroup CMSIS_MISRA_Exceptions CMSIS MISRA-C:2004 Compliance Exceptions + CMSIS violates following MISRA-C2004 Rules: + + - Violates MISRA 2004 Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + - Violates MISRA 2004 Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + - Violates MISRA 2004 Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** \defgroup CMSIS_core_definitions CMSIS Core Definitions + This file defines all structures and symbols for CMSIS core: + - CMSIS version number + - Cortex-M core + - Cortex-M core Revision Number + @{ + */ + +/* CMSIS CM3 definitions */ +#define __CM3_CMSIS_VERSION_MAIN (0x02) /*!< [31:16] CMSIS HAL main version */ +#define __CM3_CMSIS_VERSION_SUB (0x10) /*!< [15:0] CMSIS HAL sub version */ +#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | __CM3_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x03) /*!< Cortex core */ + + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */ + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + +#endif + +/*!< __FPU_USED to be checked prior to making use of FPU specific registers and functions */ +#define __FPU_USED 0 + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + /* add preprocessor checks */ +#endif + +#include /*!< standard types definitions */ +#include "core_cmInstr.h" /*!< Core Instruction Access */ +#include "core_cmFunc.h" /*!< Core Function Access */ + +#endif /* __CORE_CM3_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM3_H_DEPENDANT +#define __CORE_CM3_H_DEPENDANT + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM3_REV + #define __CM3_REV 0x0200 + #warning "__CM3_REV not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0 + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 4 + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0 + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +#ifdef __cplusplus + #define __I volatile /*!< defines 'read only' permissions */ +#else + #define __I volatile const /*!< defines 'read only' permissions */ +#endif +#define __O volatile /*!< defines 'write only' permissions */ +#define __IO volatile /*!< defines 'read / write' permissions */ + +/*@} end of group CMSIS_core_definitions */ + + + +/******************************************************************************* + * Register Abstraction + ******************************************************************************/ +/** \defgroup CMSIS_core_register CMSIS Core Register + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register +*/ + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CORE CMSIS Core + Type definitions for the Cortex-M Core Registers + @{ + */ + +/** \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ +#else + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ +#endif + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + + +/** \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + + +/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ +#else + uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ +#endif + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + + +/** \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ + uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/*@} end of group CMSIS_CORE */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC CMSIS NVIC + Type definitions for the Cortex-M NVIC Registers + @{ + */ + +/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24]; + __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24]; + __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24]; + __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24]; + __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56]; + __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644]; + __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCB CMSIS SCB + Type definitions for the Cortex-M System Control Block Registers + @{ + */ + +/** \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5]; + __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Registers Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* SCB Hard Fault Status Registers Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB CMSIS System Control and ID Register not in the SCB + Type definitions for the Cortex-M System Control and ID Register not in the SCB + @{ + */ + +/** \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1]; + __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ +#if ((defined __CM3_REV) && (__CM3_REV >= 0x200)) + __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +#else + uint32_t RESERVED1[1]; +#endif +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick CMSIS SysTick + Type definitions for the Cortex-M System Timer Registers + @{ + */ + +/** \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_ITM CMSIS ITM + Type definitions for the Cortex-M Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __O union + { + __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864]; + __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15]; + __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15]; + __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_TXENA_Pos 3 /*!< ITM TCR: TXENA Position */ +#define ITM_TCR_TXENA_Msk (1UL << ITM_TCR_TXENA_Pos) /*!< ITM TCR: TXENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +#if (__MPU_PRESENT == 1) +/** \ingroup CMSIS_core_register + \defgroup CMSIS_MPU CMSIS MPU + Type definitions for the Cortex-M Memory Protection Unit (MPU) + @{ + */ + +/** \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register */ +#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register */ +#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register */ +#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register */ +#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register */ +#define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug CMSIS Core Debug + Type definitions for the Cortex-M Core Debug Registers + @{ + */ + +/** \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register */ +#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register */ +#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** \ingroup CMSIS_core_register + @{ + */ + +/* Memory mapping of Cortex-M3 Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if (__MPU_PRESENT == 1) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + ******************************************************************************/ +/** \defgroup CMSIS_Core_FunctionInterface CMSIS Core Function Interface + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions +*/ + + + +/* ########################## NVIC functions #################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions CMSIS Core NVIC Functions + @{ + */ + +/** \brief Set Priority Grouping + + This function sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + + \param [in] PriorityGroup Priority grouping field + */ +static __INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + + +/** \brief Get Priority Grouping + + This function gets the priority grouping from NVIC Interrupt Controller. + Priority grouping is SCB->AIRCR [10:8] PRIGROUP field. + + \return Priority grouping field + */ +static __INLINE uint32_t NVIC_GetPriorityGrouping(void) +{ + return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ +} + + +/** \brief Enable External Interrupt + + This function enables a device specific interrupt in the NVIC interrupt controller. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the external interrupt to enable + */ +static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */ +} + + +/** \brief Disable External Interrupt + + This function disables a device specific interrupt in the NVIC interrupt controller. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the external interrupt to disable + */ +static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ +} + + +/** \brief Get Pending Interrupt + + This function reads the pending register in the NVIC and returns the pending bit + for the specified interrupt. + + \param [in] IRQn Number of the interrupt for get pending + \return 0 Interrupt status is not pending + \return 1 Interrupt status is pending + */ +static __INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ +} + + +/** \brief Set Pending Interrupt + + This function sets the pending bit for the specified interrupt. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the interrupt for set pending + */ +static __INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ +} + + +/** \brief Clear Pending Interrupt + + This function clears the pending bit for the specified interrupt. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the interrupt for clear pending + */ +static __INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ +} + + +/** \brief Get Active Interrupt + + This function reads the active register in NVIC and returns the active bit. + \param [in] IRQn Number of the interrupt for get active + \return 0 Interrupt status is not active + \return 1 Interrupt status is active + */ +static __INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) +{ + return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ +} + + +/** \brief Set Interrupt Priority + + This function sets the priority for the specified interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + Note: The priority cannot be set for every core interrupt. + + \param [in] IRQn Number of the interrupt for set priority + \param [in] priority Priority to set + */ +static __INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if(IRQn < 0) { + SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */ + else { + NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ +} + + +/** \brief Get Interrupt Priority + + This function reads the priority for the specified interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + The returned priority value is automatically aligned to the implemented + priority bits of the microcontroller. + + \param [in] IRQn Number of the interrupt for get priority + \return Interrupt Priority + */ +static __INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if(IRQn < 0) { + return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */ + else { + return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ +} + + +/** \brief Encode Priority + + This function encodes the priority for an interrupt with the given priority group, + preemptive priority value and sub priority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + + The returned priority value can be used for NVIC_SetPriority(...) function + + \param [in] PriorityGroup Used priority group + \param [in] PreemptPriority Preemptive priority value (starting from 0) + \param [in] SubPriority Sub priority value (starting from 0) + \return Encoded priority for the interrupt + */ +static __INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + return ( + ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | + ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ); +} + + +/** \brief Decode Priority + + This function decodes an interrupt priority value with the given priority group to + preemptive priority value and sub priority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + + The priority value can be retrieved with NVIC_GetPriority(...) function + + \param [in] Priority Priority value + \param [in] PriorityGroup Used priority group + \param [out] pPreemptPriority Preemptive priority value (starting from 0) + \param [out] pSubPriority Sub priority value (starting from 0) + */ +static __INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1); + *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); +} + + +/** \brief System Reset + + This function initiate a system reset request to reset the MCU. + */ +static __INLINE void NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + while(1); /* wait until reset */ +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions CMSIS Core SysTick Functions + @{ + */ + +#if (__Vendor_SysTickConfig == 0) + +/** \brief System Tick Configuration + + This function initialises the system tick timer and its interrupt and start the system tick timer. + Counter is in free running mode to generate periodical interrupts. + + \param [in] ticks Number of ticks between two interrupts + \return 0 Function succeeded + \return 1 Function failed + */ +static __INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + + SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Cortex-M0 System Interrupts */ + SysTick->VAL = 0; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions CMSIS Core Debug Functions + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< external variable to receive characters */ +#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< value identifying ITM_RxBuffer is ready for next character */ + + +/** \brief ITM Send Character + + This function transmits a character via the ITM channel 0. + It just returns when no debugger is connected that has booked the output. + It is blocking when a debugger is connected, but the previous character send is not transmitted. + + \param [in] ch Character to transmit + \return Character to transmit + */ +static __INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if ((CoreDebug->DEMCR & CoreDebug_DEMCR_TRCENA_Msk) && /* Trace enabled */ + (ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ + (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0].u32 == 0); + ITM->PORT[0].u8 = (uint8_t) ch; + } + return (ch); +} + + +/** \brief ITM Receive Character + + This function inputs a character via external variable ITM_RxBuffer. + It just returns when no debugger is connected that has booked the output. + It is blocking when a debugger is connected, but the previous character send is not transmitted. + + \return Received character + \return -1 No character received + */ +static __INLINE int32_t ITM_ReceiveChar (void) { + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** \brief ITM Check Character + + This function checks external variable ITM_RxBuffer whether a character is available or not. + It returns '1' if a character is available and '0' if no character is available. + + \return 0 No character available + \return 1 Character available + */ +static __INLINE int32_t ITM_CheckChar (void) { + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) { + return (0); /* no character available */ + } else { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + +#endif /* __CORE_CM3_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ + +#ifdef __cplusplus +} +#endif diff --git a/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm4.h b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm4.h new file mode 100644 index 000000000..bf022ba67 --- /dev/null +++ b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm4.h @@ -0,0 +1,1378 @@ +/**************************************************************************//** + * @file core_cm4.h + * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File + * @version V2.10 + * @date 19. July 2011 + * + * @note + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#endif + +#ifdef __cplusplus + extern "C" { +#endif + +#ifndef __CORE_CM4_H_GENERIC +#define __CORE_CM4_H_GENERIC + + +/** \mainpage CMSIS Cortex-M4 + + This documentation describes the CMSIS Cortex-M Core Peripheral Access Layer. + It consists of: + + - Cortex-M Core Register Definitions + - Cortex-M functions + - Cortex-M instructions + - Cortex-M SIMD instructions + + The CMSIS Cortex-M4 Core Peripheral Access Layer contains C and assembly functions that ease + access to the Cortex-M Core + */ + +/** \defgroup CMSIS_MISRA_Exceptions CMSIS MISRA-C:2004 Compliance Exceptions + CMSIS violates following MISRA-C2004 Rules: + + - Violates MISRA 2004 Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + - Violates MISRA 2004 Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + - Violates MISRA 2004 Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** \defgroup CMSIS_core_definitions CMSIS Core Definitions + This file defines all structures and symbols for CMSIS core: + - CMSIS version number + - Cortex-M core + - Cortex-M core Revision Number + @{ + */ + +/* CMSIS CM4 definitions */ +#define __CM4_CMSIS_VERSION_MAIN (0x02) /*!< [31:16] CMSIS HAL main version */ +#define __CM4_CMSIS_VERSION_SUB (0x10) /*!< [15:0] CMSIS HAL sub version */ +#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16) | __CM4_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x04) /*!< Cortex core */ + + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */ + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + +#endif + +/*!< __FPU_USED to be checked prior to making use of FPU specific registers and functions */ +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #if (__FPU_PRESENT == 1) + #define __FPU_USED 1 + #else + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0 + #endif + #else + #define __FPU_USED 0 + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #if (__FPU_PRESENT == 1) + #define __FPU_USED 1 + #else + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0 + #endif + #else + #define __FPU_USED 0 + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #if (__FPU_PRESENT == 1) + #define __FPU_USED 1 + #else + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0 + #endif + #else + #define __FPU_USED 0 + #endif + +#elif defined ( __TASKING__ ) + /* add preprocessor checks to define __FPU_USED */ + #define __FPU_USED 0 +#endif + +#include /*!< standard types definitions */ +#include /*!< Core Instruction Access */ +#include /*!< Core Function Access */ +#include /*!< Compiler specific SIMD Intrinsics */ + +#endif /* __CORE_CM4_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM4_H_DEPENDANT +#define __CORE_CM4_H_DEPENDANT + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM4_REV + #define __CM4_REV 0x0000 + #warning "__CM4_REV not defined in device header file; using default!" + #endif + + #ifndef __FPU_PRESENT + #define __FPU_PRESENT 0 + #warning "__FPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0 + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 4 + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0 + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +#ifdef __cplusplus + #define __I volatile /*!< defines 'read only' permissions */ +#else + #define __I volatile const /*!< defines 'read only' permissions */ +#endif +#define __O volatile /*!< defines 'write only' permissions */ +#define __IO volatile /*!< defines 'read / write' permissions */ + +/*@} end of group CMSIS_core_definitions */ + + + +/******************************************************************************* + * Register Abstraction + ******************************************************************************/ +/** \defgroup CMSIS_core_register CMSIS Core Register + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + - Core FPU Register +*/ + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CORE CMSIS Core + Type definitions for the Cortex-M Core Registers + @{ + */ + +/** \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ +#else + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ +#endif + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + + +/** \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + + +/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ +#else + uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ +#endif + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + + +/** \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ + uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/*@} end of group CMSIS_CORE */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC CMSIS NVIC + Type definitions for the Cortex-M NVIC Registers + @{ + */ + +/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24]; + __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24]; + __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24]; + __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24]; + __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56]; + __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644]; + __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCB CMSIS SCB + Type definitions for the Cortex-M System Control Block Registers + @{ + */ + +/** \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5]; + __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Registers Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* SCB Hard Fault Status Registers Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB CMSIS System Control and ID Register not in the SCB + Type definitions for the Cortex-M System Control and ID Register not in the SCB + @{ + */ + +/** \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1]; + __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ + __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ +#define SCnSCB_ACTLR_DISOOFP_Pos 9 /*!< ACTLR: DISOOFP Position */ +#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ + +#define SCnSCB_ACTLR_DISFPCA_Pos 8 /*!< ACTLR: DISFPCA Position */ +#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick CMSIS SysTick + Type definitions for the Cortex-M System Timer Registers + @{ + */ + +/** \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_ITM CMSIS ITM + Type definitions for the Cortex-M Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __O union + { + __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864]; + __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15]; + __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15]; + __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_TXENA_Pos 3 /*!< ITM TCR: TXENA Position */ +#define ITM_TCR_TXENA_Msk (1UL << ITM_TCR_TXENA_Pos) /*!< ITM TCR: TXENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +#if (__MPU_PRESENT == 1) +/** \ingroup CMSIS_core_register + \defgroup CMSIS_MPU CMSIS MPU + Type definitions for the Cortex-M Memory Protection Unit (MPU) + @{ + */ + +/** \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register */ +#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register */ +#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register */ +#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register */ +#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register */ +#define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +#if (__FPU_PRESENT == 1) +/** \ingroup CMSIS_core_register + \defgroup CMSIS_FPU CMSIS FPU + Type definitions for the Cortex-M Floating Point Unit (FPU) + @{ + */ + +/** \brief Structure type to access the Floating Point Unit (FPU). + */ +typedef struct +{ + uint32_t RESERVED0[1]; + __IO uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ + __IO uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ + __IO uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ + __I uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ + __I uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ +} FPU_Type; + +/* Floating-Point Context Control Register */ +#define FPU_FPCCR_ASPEN_Pos 31 /*!< FPCCR: ASPEN bit Position */ +#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ + +#define FPU_FPCCR_LSPEN_Pos 30 /*!< FPCCR: LSPEN Position */ +#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ + +#define FPU_FPCCR_MONRDY_Pos 8 /*!< FPCCR: MONRDY Position */ +#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ + +#define FPU_FPCCR_BFRDY_Pos 6 /*!< FPCCR: BFRDY Position */ +#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ + +#define FPU_FPCCR_MMRDY_Pos 5 /*!< FPCCR: MMRDY Position */ +#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ + +#define FPU_FPCCR_HFRDY_Pos 4 /*!< FPCCR: HFRDY Position */ +#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ + +#define FPU_FPCCR_THREAD_Pos 3 /*!< FPCCR: processor mode bit Position */ +#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ + +#define FPU_FPCCR_USER_Pos 1 /*!< FPCCR: privilege level bit Position */ +#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ + +#define FPU_FPCCR_LSPACT_Pos 0 /*!< FPCCR: Lazy state preservation active bit Position */ +#define FPU_FPCCR_LSPACT_Msk (1UL << FPU_FPCCR_LSPACT_Pos) /*!< FPCCR: Lazy state preservation active bit Mask */ + +/* Floating-Point Context Address Register */ +#define FPU_FPCAR_ADDRESS_Pos 3 /*!< FPCAR: ADDRESS bit Position */ +#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ + +/* Floating-Point Default Status Control Register */ +#define FPU_FPDSCR_AHP_Pos 26 /*!< FPDSCR: AHP bit Position */ +#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ + +#define FPU_FPDSCR_DN_Pos 25 /*!< FPDSCR: DN bit Position */ +#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ + +#define FPU_FPDSCR_FZ_Pos 24 /*!< FPDSCR: FZ bit Position */ +#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ + +#define FPU_FPDSCR_RMode_Pos 22 /*!< FPDSCR: RMode bit Position */ +#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ + +/* Media and FP Feature Register 0 */ +#define FPU_MVFR0_FP_rounding_modes_Pos 28 /*!< MVFR0: FP rounding modes bits Position */ +#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ + +#define FPU_MVFR0_Short_vectors_Pos 24 /*!< MVFR0: Short vectors bits Position */ +#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ + +#define FPU_MVFR0_Square_root_Pos 20 /*!< MVFR0: Square root bits Position */ +#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ + +#define FPU_MVFR0_Divide_Pos 16 /*!< MVFR0: Divide bits Position */ +#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ + +#define FPU_MVFR0_FP_excep_trapping_Pos 12 /*!< MVFR0: FP exception trapping bits Position */ +#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ + +#define FPU_MVFR0_Double_precision_Pos 8 /*!< MVFR0: Double-precision bits Position */ +#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ + +#define FPU_MVFR0_Single_precision_Pos 4 /*!< MVFR0: Single-precision bits Position */ +#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ + +#define FPU_MVFR0_A_SIMD_registers_Pos 0 /*!< MVFR0: A_SIMD registers bits Position */ +#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL << FPU_MVFR0_A_SIMD_registers_Pos) /*!< MVFR0: A_SIMD registers bits Mask */ + +/* Media and FP Feature Register 1 */ +#define FPU_MVFR1_FP_fused_MAC_Pos 28 /*!< MVFR1: FP fused MAC bits Position */ +#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ + +#define FPU_MVFR1_FP_HPFP_Pos 24 /*!< MVFR1: FP HPFP bits Position */ +#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ + +#define FPU_MVFR1_D_NaN_mode_Pos 4 /*!< MVFR1: D_NaN mode bits Position */ +#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ + +#define FPU_MVFR1_FtZ_mode_Pos 0 /*!< MVFR1: FtZ mode bits Position */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL << FPU_MVFR1_FtZ_mode_Pos) /*!< MVFR1: FtZ mode bits Mask */ + +/*@} end of group CMSIS_FPU */ +#endif + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug CMSIS Core Debug + Type definitions for the Cortex-M Core Debug Registers + @{ + */ + +/** \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register */ +#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register */ +#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** \ingroup CMSIS_core_register + @{ + */ + +/* Memory mapping of Cortex-M4 Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if (__MPU_PRESENT == 1) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +#if (__FPU_PRESENT == 1) + #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ + #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + ******************************************************************************/ +/** \defgroup CMSIS_Core_FunctionInterface CMSIS Core Function Interface + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions +*/ + + + +/* ########################## NVIC functions #################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions CMSIS Core NVIC Functions + @{ + */ + +/** \brief Set Priority Grouping + + This function sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + + \param [in] PriorityGroup Priority grouping field + */ +static __INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + + +/** \brief Get Priority Grouping + + This function gets the priority grouping from NVIC Interrupt Controller. + Priority grouping is SCB->AIRCR [10:8] PRIGROUP field. + + \return Priority grouping field + */ +static __INLINE uint32_t NVIC_GetPriorityGrouping(void) +{ + return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ +} + + +/** \brief Enable External Interrupt + + This function enables a device specific interrupt in the NVIC interrupt controller. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the external interrupt to enable + */ +static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ +/* NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); enable interrupt */ + NVIC->ISER[(uint32_t)((int32_t)IRQn) >> 5] = (uint32_t)(1 << ((uint32_t)((int32_t)IRQn) & (uint32_t)0x1F)); /* enable interrupt */ +} + + +/** \brief Disable External Interrupt + + This function disables a device specific interrupt in the NVIC interrupt controller. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the external interrupt to disable + */ +static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ +} + + +/** \brief Get Pending Interrupt + + This function reads the pending register in the NVIC and returns the pending bit + for the specified interrupt. + + \param [in] IRQn Number of the interrupt for get pending + \return 0 Interrupt status is not pending + \return 1 Interrupt status is pending + */ +static __INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ +} + + +/** \brief Set Pending Interrupt + + This function sets the pending bit for the specified interrupt. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the interrupt for set pending + */ +static __INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ +} + + +/** \brief Clear Pending Interrupt + + This function clears the pending bit for the specified interrupt. + The interrupt number cannot be a negative value. + + \param [in] IRQn Number of the interrupt for clear pending + */ +static __INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ +} + + +/** \brief Get Active Interrupt + + This function reads the active register in NVIC and returns the active bit. + \param [in] IRQn Number of the interrupt for get active + \return 0 Interrupt status is not active + \return 1 Interrupt status is active + */ +static __INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) +{ + return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ +} + + +/** \brief Set Interrupt Priority + + This function sets the priority for the specified interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + Note: The priority cannot be set for every core interrupt. + + \param [in] IRQn Number of the interrupt for set priority + \param [in] priority Priority to set + */ +static __INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if(IRQn < 0) { + SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */ + else { + NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ +} + + +/** \brief Get Interrupt Priority + + This function reads the priority for the specified interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + The returned priority value is automatically aligned to the implemented + priority bits of the microcontroller. + + \param [in] IRQn Number of the interrupt for get priority + \return Interrupt Priority + */ +static __INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if(IRQn < 0) { + return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */ + else { + return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ +} + + +/** \brief Encode Priority + + This function encodes the priority for an interrupt with the given priority group, + preemptive priority value and sub priority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + + The returned priority value can be used for NVIC_SetPriority(...) function + + \param [in] PriorityGroup Used priority group + \param [in] PreemptPriority Preemptive priority value (starting from 0) + \param [in] SubPriority Sub priority value (starting from 0) + \return Encoded priority for the interrupt + */ +static __INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + return ( + ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | + ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ); +} + + +/** \brief Decode Priority + + This function decodes an interrupt priority value with the given priority group to + preemptive priority value and sub priority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + + The priority value can be retrieved with NVIC_GetPriority(...) function + + \param [in] Priority Priority value + \param [in] PriorityGroup Used priority group + \param [out] pPreemptPriority Preemptive priority value (starting from 0) + \param [out] pSubPriority Sub priority value (starting from 0) + */ +static __INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1); + *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); +} + + +/** \brief System Reset + + This function initiate a system reset request to reset the MCU. + */ +static __INLINE void NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + while(1); /* wait until reset */ +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions CMSIS Core SysTick Functions + @{ + */ + +#if (__Vendor_SysTickConfig == 0) + +/** \brief System Tick Configuration + + This function initialises the system tick timer and its interrupt and start the system tick timer. + Counter is in free running mode to generate periodical interrupts. + + \param [in] ticks Number of ticks between two interrupts + \return 0 Function succeeded + \return 1 Function failed + */ +static __INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + + SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Cortex-M0 System Interrupts */ + SysTick->VAL = 0; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions CMSIS Core Debug Functions + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< external variable to receive characters */ +#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< value identifying ITM_RxBuffer is ready for next character */ + + +/** \brief ITM Send Character + + This function transmits a character via the ITM channel 0. + It just returns when no debugger is connected that has booked the output. + It is blocking when a debugger is connected, but the previous character send is not transmitted. + + \param [in] ch Character to transmit + \return Character to transmit + */ +static __INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if ((CoreDebug->DEMCR & CoreDebug_DEMCR_TRCENA_Msk) && /* Trace enabled */ + (ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ + (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0].u32 == 0); + ITM->PORT[0].u8 = (uint8_t) ch; + } + return (ch); +} + + +/** \brief ITM Receive Character + + This function inputs a character via external variable ITM_RxBuffer. + It just returns when no debugger is connected that has booked the output. + It is blocking when a debugger is connected, but the previous character send is not transmitted. + + \return Received character + \return -1 No character received + */ +static __INLINE int32_t ITM_ReceiveChar (void) { + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** \brief ITM Check Character + + This function checks external variable ITM_RxBuffer whether a character is available or not. + It returns '1' if a character is available and '0' if no character is available. + + \return 0 No character available + \return 1 Character available + */ +static __INLINE int32_t ITM_CheckChar (void) { + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) { + return (0); /* no character available */ + } else { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + +#endif /* __CORE_CM4_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ + +#ifdef __cplusplus +} +#endif diff --git a/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm4_simd.h b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm4_simd.h new file mode 100644 index 000000000..e7b676522 --- /dev/null +++ b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cm4_simd.h @@ -0,0 +1,701 @@ +/**************************************************************************//** + * @file core_cm4_simd.h + * @brief CMSIS Cortex-M4 SIMD Header File + * @version V2.10 + * @date 19. July 2011 + * + * @note + * Copyright (C) 2010-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifdef __cplusplus + extern "C" { +#endif + +#ifndef __CORE_CM4_SIMD_H +#define __CORE_CM4_SIMD_H + + +/******************************************************************************* + * Hardware Abstraction Layer + ******************************************************************************/ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +/*------ CM4 SOMD Intrinsics -----------------------------------------------------*/ +#define __SADD8 __sadd8 +#define __QADD8 __qadd8 +#define __SHADD8 __shadd8 +#define __UADD8 __uadd8 +#define __UQADD8 __uqadd8 +#define __UHADD8 __uhadd8 +#define __SSUB8 __ssub8 +#define __QSUB8 __qsub8 +#define __SHSUB8 __shsub8 +#define __USUB8 __usub8 +#define __UQSUB8 __uqsub8 +#define __UHSUB8 __uhsub8 +#define __SADD16 __sadd16 +#define __QADD16 __qadd16 +#define __SHADD16 __shadd16 +#define __UADD16 __uadd16 +#define __UQADD16 __uqadd16 +#define __UHADD16 __uhadd16 +#define __SSUB16 __ssub16 +#define __QSUB16 __qsub16 +#define __SHSUB16 __shsub16 +#define __USUB16 __usub16 +#define __UQSUB16 __uqsub16 +#define __UHSUB16 __uhsub16 +#define __SASX __sasx +#define __QASX __qasx +#define __SHASX __shasx +#define __UASX __uasx +#define __UQASX __uqasx +#define __UHASX __uhasx +#define __SSAX __ssax +#define __QSAX __qsax +#define __SHSAX __shsax +#define __USAX __usax +#define __UQSAX __uqsax +#define __UHSAX __uhsax +#define __USAD8 __usad8 +#define __USADA8 __usada8 +#define __SSAT16 __ssat16 +#define __USAT16 __usat16 +#define __UXTB16 __uxtb16 +#define __UXTAB16 __uxtab16 +#define __SXTB16 __sxtb16 +#define __SXTAB16 __sxtab16 +#define __SMUAD __smuad +#define __SMUADX __smuadx +#define __SMLAD __smlad +#define __SMLADX __smladx +#define __SMLALD __smlald +#define __SMLALDX __smlaldx +#define __SMUSD __smusd +#define __SMUSDX __smusdx +#define __SMLSD __smlsd +#define __SMLSDX __smlsdx +#define __SMLSLD __smlsld +#define __SMLSLDX __smlsldx +#define __SEL __sel +#define __QADD __qadd +#define __QSUB __qsub + +#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ + ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) + +#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ + ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) + + +/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ + + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#include + +/*------ CM4 SIMDDSP Intrinsics -----------------------------------------------------*/ +/* intrinsic __SADD8 see intrinsics.h */ +/* intrinsic __QADD8 see intrinsics.h */ +/* intrinsic __SHADD8 see intrinsics.h */ +/* intrinsic __UADD8 see intrinsics.h */ +/* intrinsic __UQADD8 see intrinsics.h */ +/* intrinsic __UHADD8 see intrinsics.h */ +/* intrinsic __SSUB8 see intrinsics.h */ +/* intrinsic __QSUB8 see intrinsics.h */ +/* intrinsic __SHSUB8 see intrinsics.h */ +/* intrinsic __USUB8 see intrinsics.h */ +/* intrinsic __UQSUB8 see intrinsics.h */ +/* intrinsic __UHSUB8 see intrinsics.h */ +/* intrinsic __SADD16 see intrinsics.h */ +/* intrinsic __QADD16 see intrinsics.h */ +/* intrinsic __SHADD16 see intrinsics.h */ +/* intrinsic __UADD16 see intrinsics.h */ +/* intrinsic __UQADD16 see intrinsics.h */ +/* intrinsic __UHADD16 see intrinsics.h */ +/* intrinsic __SSUB16 see intrinsics.h */ +/* intrinsic __QSUB16 see intrinsics.h */ +/* intrinsic __SHSUB16 see intrinsics.h */ +/* intrinsic __USUB16 see intrinsics.h */ +/* intrinsic __UQSUB16 see intrinsics.h */ +/* intrinsic __UHSUB16 see intrinsics.h */ +/* intrinsic __SASX see intrinsics.h */ +/* intrinsic __QASX see intrinsics.h */ +/* intrinsic __SHASX see intrinsics.h */ +/* intrinsic __UASX see intrinsics.h */ +/* intrinsic __UQASX see intrinsics.h */ +/* intrinsic __UHASX see intrinsics.h */ +/* intrinsic __SSAX see intrinsics.h */ +/* intrinsic __QSAX see intrinsics.h */ +/* intrinsic __SHSAX see intrinsics.h */ +/* intrinsic __USAX see intrinsics.h */ +/* intrinsic __UQSAX see intrinsics.h */ +/* intrinsic __UHSAX see intrinsics.h */ +/* intrinsic __USAD8 see intrinsics.h */ +/* intrinsic __USADA8 see intrinsics.h */ +/* intrinsic __SSAT16 see intrinsics.h */ +/* intrinsic __USAT16 see intrinsics.h */ +/* intrinsic __UXTB16 see intrinsics.h */ +/* intrinsic __SXTB16 see intrinsics.h */ +/* intrinsic __UXTAB16 see intrinsics.h */ +/* intrinsic __SXTAB16 see intrinsics.h */ +/* intrinsic __SMUAD see intrinsics.h */ +/* intrinsic __SMUADX see intrinsics.h */ +/* intrinsic __SMLAD see intrinsics.h */ +/* intrinsic __SMLADX see intrinsics.h */ +/* intrinsic __SMLALD see intrinsics.h */ +/* intrinsic __SMLALDX see intrinsics.h */ +/* intrinsic __SMUSD see intrinsics.h */ +/* intrinsic __SMUSDX see intrinsics.h */ +/* intrinsic __SMLSD see intrinsics.h */ +/* intrinsic __SMLSDX see intrinsics.h */ +/* intrinsic __SMLSLD see intrinsics.h */ +/* intrinsic __SMLSLDX see intrinsics.h */ +/* intrinsic __SEL see intrinsics.h */ +/* intrinsic __QADD see intrinsics.h */ +/* intrinsic __QSUB see intrinsics.h */ +/* intrinsic __PKHBT see intrinsics.h */ +/* intrinsic __PKHTB see intrinsics.h */ + +/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ + + + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __QASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __USAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SSAT16(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +#define __USAT16(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SMLALD(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ + (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ + }) + +#define __SMLALDX(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ + (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ + }) + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SMLSLD(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ + (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ + }) + +#define __SMLSLDX(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \ + (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \ + }) + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __SEL (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __QADD(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) static __INLINE uint32_t __QSUB(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +#define __PKHBT(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) + +#define __PKHTB(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + if (ARG3 == 0) \ + __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ + else \ + __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) + +/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ + + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ + + +/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/ +/* not yet supported */ +/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ + + +#endif + +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#endif /* __CORE_CM4_SIMD_H */ + +#ifdef __cplusplus +} +#endif diff --git a/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cmFunc.h b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cmFunc.h new file mode 100644 index 000000000..88819f9dd --- /dev/null +++ b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cmFunc.h @@ -0,0 +1,609 @@ +/**************************************************************************//** + * @file core_cmFunc.h + * @brief CMSIS Cortex-M Core Function Access Header File + * @version V2.10 + * @date 26. July 2011 + * + * @note + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CORE_CMFUNC_H +#define __CORE_CMFUNC_H + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#if (__ARMCC_VERSION < 400677) + #error "Please use ARM Compiler Toolchain V4.0.677 or later!" +#endif + +/* intrinsic void __enable_irq(); */ +/* intrinsic void __disable_irq(); */ + +/** \brief Get Control Register + + This function returns the content of the Control Register. + + \return Control Register value + */ +static __INLINE uint32_t __get_CONTROL(void) +{ + register uint32_t __regControl __ASM("control"); + return(__regControl); +} + + +/** \brief Set Control Register + + This function writes the given value to the Control Register. + + \param [in] control Control Register value to set + */ +static __INLINE void __set_CONTROL(uint32_t control) +{ + register uint32_t __regControl __ASM("control"); + __regControl = control; +} + + +/** \brief Get ISPR Register + + This function returns the content of the ISPR Register. + + \return ISPR Register value + */ +static __INLINE uint32_t __get_IPSR(void) +{ + register uint32_t __regIPSR __ASM("ipsr"); + return(__regIPSR); +} + + +/** \brief Get APSR Register + + This function returns the content of the APSR Register. + + \return APSR Register value + */ +static __INLINE uint32_t __get_APSR(void) +{ + register uint32_t __regAPSR __ASM("apsr"); + return(__regAPSR); +} + + +/** \brief Get xPSR Register + + This function returns the content of the xPSR Register. + + \return xPSR Register value + */ +static __INLINE uint32_t __get_xPSR(void) +{ + register uint32_t __regXPSR __ASM("xpsr"); + return(__regXPSR); +} + + +/** \brief Get Process Stack Pointer + + This function returns the current value of the Process Stack Pointer (PSP). + + \return PSP Register value + */ +static __INLINE uint32_t __get_PSP(void) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + return(__regProcessStackPointer); +} + + +/** \brief Set Process Stack Pointer + + This function assigns the given value to the Process Stack Pointer (PSP). + + \param [in] topOfProcStack Process Stack Pointer value to set + */ +static __INLINE void __set_PSP(uint32_t topOfProcStack) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + __regProcessStackPointer = topOfProcStack; +} + + +/** \brief Get Main Stack Pointer + + This function returns the current value of the Main Stack Pointer (MSP). + + \return MSP Register value + */ +static __INLINE uint32_t __get_MSP(void) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + return(__regMainStackPointer); +} + + +/** \brief Set Main Stack Pointer + + This function assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +static __INLINE void __set_MSP(uint32_t topOfMainStack) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + __regMainStackPointer = topOfMainStack; +} + + +/** \brief Get Priority Mask + + This function returns the current state of the priority mask bit from the Priority Mask Register. + + \return Priority Mask value + */ +static __INLINE uint32_t __get_PRIMASK(void) +{ + register uint32_t __regPriMask __ASM("primask"); + return(__regPriMask); +} + + +/** \brief Set Priority Mask + + This function assigns the given value to the Priority Mask Register. + + \param [in] priMask Priority Mask + */ +static __INLINE void __set_PRIMASK(uint32_t priMask) +{ + register uint32_t __regPriMask __ASM("primask"); + __regPriMask = (priMask); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Enable FIQ + + This function enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq + + +/** \brief Disable FIQ + + This function disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq + + +/** \brief Get Base Priority + + This function returns the current value of the Base Priority register. + + \return Base Priority register value + */ +static __INLINE uint32_t __get_BASEPRI(void) +{ + register uint32_t __regBasePri __ASM("basepri"); + return(__regBasePri); +} + + +/** \brief Set Base Priority + + This function assigns the given value to the Base Priority register. + + \param [in] basePri Base Priority value to set + */ +static __INLINE void __set_BASEPRI(uint32_t basePri) +{ + register uint32_t __regBasePri __ASM("basepri"); + __regBasePri = (basePri & 0xff); +} + + +/** \brief Get Fault Mask + + This function returns the current value of the Fault Mask register. + + \return Fault Mask register value + */ +static __INLINE uint32_t __get_FAULTMASK(void) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + return(__regFaultMask); +} + + +/** \brief Set Fault Mask + + This function assigns the given value to the Fault Mask register. + + \param [in] faultMask Fault Mask value to set + */ +static __INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + __regFaultMask = (faultMask & (uint32_t)1); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + +#if (__CORTEX_M == 0x04) + +/** \brief Get FPSCR + + This function returns the current value of the Floating Point Status/Control register. + + \return Floating Point Status/Control register value + */ +static __INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + register uint32_t __regfpscr __ASM("fpscr"); + return(__regfpscr); +#else + return(0); +#endif +} + + +/** \brief Set FPSCR + + This function assigns the given value to the Floating Point Status/Control register. + + \param [in] fpscr Floating Point Status/Control value to set + */ +static __INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + register uint32_t __regfpscr __ASM("fpscr"); + __regfpscr = (fpscr); +#endif +} + +#endif /* (__CORTEX_M == 0x04) */ + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#include + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** \brief Enable IRQ Interrupts + + This function enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __enable_irq(void) +{ + __ASM volatile ("cpsie i"); +} + + +/** \brief Disable IRQ Interrupts + + This function disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __disable_irq(void) +{ + __ASM volatile ("cpsid i"); +} + + +/** \brief Get Control Register + + This function returns the content of the Control Register. + + \return Control Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +/** \brief Set Control Register + + This function writes the given value to the Control Register. + + \param [in] control Control Register value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) ); +} + + +/** \brief Get ISPR Register + + This function returns the content of the ISPR Register. + + \return ISPR Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get APSR Register + + This function returns the content of the APSR Register. + + \return APSR Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get xPSR Register + + This function returns the content of the xPSR Register. + + \return xPSR Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get Process Stack Pointer + + This function returns the current value of the Process Stack Pointer (PSP). + + \return PSP Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, psp\n" : "=r" (result) ); + return(result); +} + + +/** \brief Set Process Stack Pointer + + This function assigns the given value to the Process Stack Pointer (PSP). + + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) ); +} + + +/** \brief Get Main Stack Pointer + + This function returns the current value of the Main Stack Pointer (MSP). + + \return MSP Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_MSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, msp\n" : "=r" (result) ); + return(result); +} + + +/** \brief Set Main Stack Pointer + + This function assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) ); +} + + +/** \brief Get Priority Mask + + This function returns the current state of the priority mask bit from the Priority Mask Register. + + \return Priority Mask value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +/** \brief Set Priority Mask + + This function assigns the given value to the Priority Mask Register. + + \param [in] priMask Priority Mask + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) ); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Enable FIQ + + This function enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __enable_fault_irq(void) +{ + __ASM volatile ("cpsie f"); +} + + +/** \brief Disable FIQ + + This function disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __disable_fault_irq(void) +{ + __ASM volatile ("cpsid f"); +} + + +/** \brief Get Base Priority + + This function returns the current value of the Base Priority register. + + \return Base Priority register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); + return(result); +} + + +/** \brief Set Base Priority + + This function assigns the given value to the Base Priority register. + + \param [in] basePri Base Priority value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_BASEPRI(uint32_t value) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (value) ); +} + + +/** \brief Get Fault Mask + + This function returns the current value of the Fault Mask register. + + \return Fault Mask register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +/** \brief Set Fault Mask + + This function assigns the given value to the Fault Mask register. + + \param [in] faultMask Fault Mask value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) ); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + +#if (__CORTEX_M == 0x04) + +/** \brief Get FPSCR + + This function returns the current value of the Floating Point Status/Control register. + + \return Floating Point Status/Control register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + uint32_t result; + + __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); + return(result); +#else + return(0); +#endif +} + + +/** \brief Set FPSCR + + This function assigns the given value to the Floating Point Status/Control register. + + \param [in] fpscr Floating Point Status/Control value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) ); +#endif +} + +#endif /* (__CORTEX_M == 0x04) */ + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all instrinsics, + * Including the CMSIS ones. + */ + +#endif + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +#endif /* __CORE_CMFUNC_H */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cmInstr.h b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cmInstr.h new file mode 100644 index 000000000..78d2ef80b --- /dev/null +++ b/flight/PiOS/Common/Libraries/CMSIS2/Include/core_cmInstr.h @@ -0,0 +1,585 @@ +/**************************************************************************//** + * @file core_cmInstr.h + * @brief CMSIS Cortex-M Core Instruction Access Header File + * @version V2.10 + * @date 19. July 2011 + * + * @note + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CORE_CMINSTR_H +#define __CORE_CMINSTR_H + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#if (__ARMCC_VERSION < 400677) + #error "Please use ARM Compiler Toolchain V4.0.677 or later!" +#endif + + +/** \brief No Operation + + No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __nop + + +/** \brief Wait For Interrupt + + Wait For Interrupt is a hint instruction that suspends execution + until one of a number of events occurs. + */ +#define __WFI __wfi + + +/** \brief Wait For Event + + Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE __wfe + + +/** \brief Send Event + + Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __sev + + +/** \brief Instruction Synchronization Barrier + + Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or + memory, after the instruction has been completed. + */ +#define __ISB() __isb(0xF) + + +/** \brief Data Synchronization Barrier + + This function acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __dsb(0xF) + + +/** \brief Data Memory Barrier + + This function ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __dmb(0xF) + + +/** \brief Reverse byte order (32 bit) + + This function reverses the byte order in integer value. + + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV __rev + + +/** \brief Reverse byte order (16 bit) + + This function reverses the byte order in two unsigned short values. + + \param [in] value Value to reverse + \return Reversed value + */ +static __INLINE __ASM uint32_t __REV16(uint32_t value) +{ + rev16 r0, r0 + bx lr +} + + +/** \brief Reverse byte order in signed short value + + This function reverses the byte order in a signed short value with sign extension to integer. + + \param [in] value Value to reverse + \return Reversed value + */ +static __INLINE __ASM int32_t __REVSH(int32_t value) +{ + revsh r0, r0 + bx lr +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Reverse bit order of value + + This function reverses the bit order of the given value. + + \param [in] value Value to reverse + \return Reversed value + */ +#define __RBIT __rbit + + +/** \brief LDR Exclusive (8 bit) + + This function performs a exclusive LDR command for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) + + +/** \brief LDR Exclusive (16 bit) + + This function performs a exclusive LDR command for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) + + +/** \brief LDR Exclusive (32 bit) + + This function performs a exclusive LDR command for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) + + +/** \brief STR Exclusive (8 bit) + + This function performs a exclusive STR command for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXB(value, ptr) __strex(value, ptr) + + +/** \brief STR Exclusive (16 bit) + + This function performs a exclusive STR command for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXH(value, ptr) __strex(value, ptr) + + +/** \brief STR Exclusive (32 bit) + + This function performs a exclusive STR command for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXW(value, ptr) __strex(value, ptr) + + +/** \brief Remove the exclusive lock + + This function removes the exclusive lock which is created by LDREX. + + */ +#define __CLREX __clrex + + +/** \brief Signed Saturate + + This function saturates a signed value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT __ssat + + +/** \brief Unsigned Saturate + + This function saturates an unsigned value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT __usat + + +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ __clz + +#endif /* (__CORTEX_M >= 0x03) */ + + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#include + + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** \brief No Operation + + No Operation does nothing. This instruction can be used for code alignment purposes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __NOP(void) +{ + __ASM volatile ("nop"); +} + + +/** \brief Wait For Interrupt + + Wait For Interrupt is a hint instruction that suspends execution + until one of a number of events occurs. + */ +__attribute__( ( always_inline ) ) static __INLINE void __WFI(void) +{ + __ASM volatile ("wfi"); +} + + +/** \brief Wait For Event + + Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +__attribute__( ( always_inline ) ) static __INLINE void __WFE(void) +{ + __ASM volatile ("wfe"); +} + + +/** \brief Send Event + + Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +__attribute__( ( always_inline ) ) static __INLINE void __SEV(void) +{ + __ASM volatile ("sev"); +} + + +/** \brief Instruction Synchronization Barrier + + Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or + memory, after the instruction has been completed. + */ +__attribute__( ( always_inline ) ) static __INLINE void __ISB(void) +{ + __ASM volatile ("isb"); +} + + +/** \brief Data Synchronization Barrier + + This function acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +__attribute__( ( always_inline ) ) static __INLINE void __DSB(void) +{ + __ASM volatile ("dsb"); +} + + +/** \brief Data Memory Barrier + + This function ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +__attribute__( ( always_inline ) ) static __INLINE void __DMB(void) +{ + __ASM volatile ("dmb"); +} + + +/** \brief Reverse byte order (32 bit) + + This function reverses the byte order in integer value. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __REV(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief Reverse byte order (16 bit) + + This function reverses the byte order in two unsigned short values. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __REV16(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief Reverse byte order in signed short value + + This function reverses the byte order in a signed short value with sign extension to integer. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE int32_t __REVSH(int32_t value) +{ + uint32_t result; + + __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Reverse bit order of value + + This function reverses the bit order of the given value. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief LDR Exclusive (8 bit) + + This function performs a exclusive LDR command for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__attribute__( ( always_inline ) ) static __INLINE uint8_t __LDREXB(volatile uint8_t *addr) +{ + uint8_t result; + + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief LDR Exclusive (16 bit) + + This function performs a exclusive LDR command for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__attribute__( ( always_inline ) ) static __INLINE uint16_t __LDREXH(volatile uint16_t *addr) +{ + uint16_t result; + + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief LDR Exclusive (32 bit) + + This function performs a exclusive LDR command for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __LDREXW(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief STR Exclusive (8 bit) + + This function performs a exclusive STR command for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexb %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief STR Exclusive (16 bit) + + This function performs a exclusive STR command for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexh %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief STR Exclusive (32 bit) + + This function performs a exclusive STR command for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief Remove the exclusive lock + + This function removes the exclusive lock which is created by LDREX. + + */ +__attribute__( ( always_inline ) ) static __INLINE void __CLREX(void) +{ + __ASM volatile ("clrex"); +} + + +/** \brief Signed Saturate + + This function saturates a signed value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** \brief Unsigned Saturate + + This function saturates an unsigned value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +__attribute__( ( always_inline ) ) static __INLINE uint8_t __CLZ(uint32_t value) +{ + uint8_t result; + + __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + +#endif + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + +#endif /* __CORE_CMINSTR_H */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/library.mk b/flight/PiOS/Common/Libraries/CMSIS2/library.mk new file mode 100644 index 000000000..a2b8636ea --- /dev/null +++ b/flight/PiOS/Common/Libraries/CMSIS2/library.mk @@ -0,0 +1,6 @@ +# +# Rules to add CMSIS2 to a PiOS target +# + +CMSIS2_DIR := $(dir $(lastword $(MAKEFILE_LIST))) +EXTRAINCDIRS += $(CMSIS2_DIR)/Include diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h new file mode 100644 index 000000000..e495d7d35 --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h @@ -0,0 +1,473 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef INC_FREERTOS_H +#define INC_FREERTOS_H + + +/* + * Include the generic headers required for the FreeRTOS port being used. + */ +#include + +/* Basic FreeRTOS definitions. */ +#include "projdefs.h" + +/* Application specific configuration options. */ +#include "FreeRTOSConfig.h" + +/* Definitions specific to the port being used. */ +#include "portable.h" + + +/* Defines the prototype to which the application task hook function must +conform. */ +typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); + + + + + +/* + * Check all the required application specific macros have been defined. + * These macros are application specific and (as downloaded) are defined + * within FreeRTOSConfig.h. + */ + +#ifndef configUSE_PREEMPTION + #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_IDLE_HOOK + #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_TICK_HOOK + #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_CO_ROUTINES + #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskPrioritySet + #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_uxTaskPriorityGet + #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelete + #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskSuspend + #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelayUntil + #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelay + #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_16_BIT_TICKS + #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_xTaskGetIdleTaskHandle + #define INCLUDE_xTaskGetIdleTaskHandle 0 +#endif + +#ifndef INCLUDE_xTimerGetTimerDaemonTaskHandle + #define INCLUDE_xTimerGetTimerDaemonTaskHandle 0 +#endif + +#ifndef INCLUDE_pcTaskGetTaskName + #define INCLUDE_pcTaskGetTaskName 0 +#endif + +#ifndef configUSE_APPLICATION_TASK_TAG + #define configUSE_APPLICATION_TASK_TAG 0 +#endif + +#ifndef INCLUDE_uxTaskGetStackHighWaterMark + #define INCLUDE_uxTaskGetStackHighWaterMark 0 +#endif + +#ifndef configUSE_RECURSIVE_MUTEXES + #define configUSE_RECURSIVE_MUTEXES 0 +#endif + +#ifndef configUSE_MUTEXES + #define configUSE_MUTEXES 0 +#endif + +#ifndef configUSE_TIMERS + #define configUSE_TIMERS 0 +#endif + +#ifndef configUSE_COUNTING_SEMAPHORES + #define configUSE_COUNTING_SEMAPHORES 0 +#endif + +#ifndef configUSE_ALTERNATIVE_API + #define configUSE_ALTERNATIVE_API 0 +#endif + +#ifndef portCRITICAL_NESTING_IN_TCB + #define portCRITICAL_NESTING_IN_TCB 0 +#endif + +#ifndef configMAX_TASK_NAME_LEN + #define configMAX_TASK_NAME_LEN 16 +#endif + +#ifndef configIDLE_SHOULD_YIELD + #define configIDLE_SHOULD_YIELD 1 +#endif + +#if configMAX_TASK_NAME_LEN < 1 + #error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h +#endif + +#ifndef INCLUDE_xTaskResumeFromISR + #define INCLUDE_xTaskResumeFromISR 1 +#endif + +#ifndef configASSERT + #define configASSERT( x ) +#endif + +/* The timers module relies on xTaskGetSchedulerState(). */ +#if configUSE_TIMERS == 1 + + #ifndef configTIMER_TASK_PRIORITY + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined. + #endif /* configTIMER_TASK_PRIORITY */ + + #ifndef configTIMER_QUEUE_LENGTH + #error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined. + #endif /* configTIMER_QUEUE_LENGTH */ + + #ifndef configTIMER_TASK_STACK_DEPTH + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined. + #endif /* configTIMER_TASK_STACK_DEPTH */ + +#endif /* configUSE_TIMERS */ + +#ifndef INCLUDE_xTaskGetSchedulerState + #define INCLUDE_xTaskGetSchedulerState 0 +#endif + +#ifndef INCLUDE_xTaskGetCurrentTaskHandle + #define INCLUDE_xTaskGetCurrentTaskHandle 0 +#endif + + +#ifndef portSET_INTERRUPT_MASK_FROM_ISR + #define portSET_INTERRUPT_MASK_FROM_ISR() 0 +#endif + +#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR + #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue +#endif + + +#ifndef configQUEUE_REGISTRY_SIZE + #define configQUEUE_REGISTRY_SIZE 0U +#endif + +#if ( configQUEUE_REGISTRY_SIZE < 1 ) + #define vQueueAddToRegistry( xQueue, pcName ) + #define vQueueUnregisterQueue( xQueue ) +#endif + +#ifndef portPOINTER_SIZE_TYPE + #define portPOINTER_SIZE_TYPE unsigned long +#endif + +/* Remove any unused trace macros. */ +#ifndef traceSTART + /* Used to perform any necessary initialisation - for example, open a file + into which trace is to be written. */ + #define traceSTART() +#endif + +#ifndef traceEND + /* Use to close a trace, for example close a file into which trace has been + written. */ + #define traceEND() +#endif + +#ifndef traceTASK_SWITCHED_IN + /* Called after a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the selected task. */ + #define traceTASK_SWITCHED_IN() +#endif + +#ifndef traceTASK_SWITCHED_OUT + /* Called before a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the task being switched out. */ + #define traceTASK_SWITCHED_OUT() +#endif + +#ifndef traceBLOCKING_ON_QUEUE_RECEIVE + /* Task is about to block because it cannot read from a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the read was attempted. pxCurrentTCB points to the TCB of the + task that attempted the read. */ + #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_SEND + /* Task is about to block because it cannot write to a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the write was attempted. pxCurrentTCB points to the TCB of the + task that attempted the write. */ + #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) +#endif + +#ifndef configCHECK_FOR_STACK_OVERFLOW + #define configCHECK_FOR_STACK_OVERFLOW 0 +#endif + +/* The following event macros are embedded in the kernel API calls. */ + +#ifndef traceQUEUE_CREATE + #define traceQUEUE_CREATE( pxNewQueue ) +#endif + +#ifndef traceQUEUE_CREATE_FAILED + #define traceQUEUE_CREATE_FAILED() +#endif + +#ifndef traceCREATE_MUTEX + #define traceCREATE_MUTEX( pxNewQueue ) +#endif + +#ifndef traceCREATE_MUTEX_FAILED + #define traceCREATE_MUTEX_FAILED() +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE + #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED + #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE + #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED + #define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE + #define traceCREATE_COUNTING_SEMAPHORE() +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED + #define traceCREATE_COUNTING_SEMAPHORE_FAILED() +#endif + +#ifndef traceQUEUE_SEND + #define traceQUEUE_SEND( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FAILED + #define traceQUEUE_SEND_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE + #define traceQUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK + #define traceQUEUE_PEEK( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FAILED + #define traceQUEUE_RECEIVE_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR + #define traceQUEUE_SEND_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR_FAILED + #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR + #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED + #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_DELETE + #define traceQUEUE_DELETE( pxQueue ) +#endif + +#ifndef traceTASK_CREATE + #define traceTASK_CREATE( pxNewTCB ) +#endif + +#ifndef traceTASK_CREATE_FAILED + #define traceTASK_CREATE_FAILED() +#endif + +#ifndef traceTASK_DELETE + #define traceTASK_DELETE( pxTaskToDelete ) +#endif + +#ifndef traceTASK_DELAY_UNTIL + #define traceTASK_DELAY_UNTIL() +#endif + +#ifndef traceTASK_DELAY + #define traceTASK_DELAY() +#endif + +#ifndef traceTASK_PRIORITY_SET + #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) +#endif + +#ifndef traceTASK_SUSPEND + #define traceTASK_SUSPEND( pxTaskToSuspend ) +#endif + +#ifndef traceTASK_RESUME + #define traceTASK_RESUME( pxTaskToResume ) +#endif + +#ifndef traceTASK_RESUME_FROM_ISR + #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) +#endif + +#ifndef traceTASK_INCREMENT_TICK + #define traceTASK_INCREMENT_TICK( xTickCount ) +#endif + +#ifndef traceTIMER_CREATE + #define traceTIMER_CREATE( pxNewTimer ) +#endif + +#ifndef traceTIMER_CREATE_FAILED + #define traceTIMER_CREATE_FAILED() +#endif + +#ifndef traceTIMER_COMMAND_SEND + #define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn ) +#endif + +#ifndef traceTIMER_EXPIRED + #define traceTIMER_EXPIRED( pxTimer ) +#endif + +#ifndef traceTIMER_COMMAND_RECEIVED + #define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue ) +#endif + +#ifndef configGENERATE_RUN_TIME_STATS + #define configGENERATE_RUN_TIME_STATS 0 +#endif + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. + #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ + + #ifndef portGET_RUN_TIME_COUNTER_VALUE + #ifndef portALT_GET_RUN_TIME_COUNTER_VALUE + #error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined. See the examples provided and the FreeRTOS web site for more information. + #endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */ + #endif /* portGET_RUN_TIME_COUNTER_VALUE */ + +#endif /* configGENERATE_RUN_TIME_STATS */ + +#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() +#endif + +#ifndef configUSE_MALLOC_FAILED_HOOK + #define configUSE_MALLOC_FAILED_HOOK 0 +#endif + +#ifndef portPRIVILEGE_BIT + #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) +#endif + +#ifndef portYIELD_WITHIN_API + #define portYIELD_WITHIN_API portYIELD +#endif + +#ifndef pvPortMallocAligned + #define pvPortMallocAligned( x, puxStackBuffer ) ( ( ( puxStackBuffer ) == NULL ) ? ( pvPortMalloc( ( x ) ) ) : ( puxStackBuffer ) ) +#endif + +#ifndef vPortFreeAligned + #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) +#endif + +#endif /* INC_FREERTOS_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h new file mode 100644 index 000000000..8b555cec7 --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h @@ -0,0 +1,168 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef STACK_MACROS_H +#define STACK_MACROS_H + +/* + * Call the stack overflow hook function if the stack of the task being swapped + * out is currently overflowed, or looks like it might have overflowed in the + * past. + * + * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check + * the current stack state only - comparing the current top of stack value to + * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 + * will also cause the last few stack bytes to be checked to ensure the value + * to which the bytes were set when the task was created have not been + * overwritten. Note this second test does not guarantee that an overflowed + * stack will always be recognised. + */ + +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) + + /* FreeRTOSConfig.h is not set to check for stack overflows. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) + + /* FreeRTOSConfig.h is only set to use the first method of + overflow checking. */ + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#endif /* STACK_MACROS_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h new file mode 100644 index 000000000..a5a0d6980 --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h @@ -0,0 +1,746 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef CO_ROUTINE_H +#define CO_ROUTINE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include croutine.h" +#endif + +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Used to hide the implementation of the co-routine control block. The +control block structure however has to be included in the header due to +the macro implementation of the co-routine functionality. */ +typedef void * xCoRoutineHandle; + +/* Defines the prototype to which co-routine functions must conform. */ +typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); + +typedef struct corCoRoutineControlBlock +{ + crCOROUTINE_CODE pxCoRoutineFunction; + xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ + unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ + unsigned short uxState; /*< Used internally by the co-routine implementation. */ +} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ + +/** + * croutine. h + *
+ portBASE_TYPE xCoRoutineCreate(
+                                 crCOROUTINE_CODE pxCoRoutineCode,
+                                 unsigned portBASE_TYPE uxPriority,
+                                 unsigned portBASE_TYPE uxIndex
+                               );
+ * + * Create a new co-routine and add it to the list of co-routines that are + * ready to run. + * + * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine + * functions require special syntax - see the co-routine section of the WEB + * documentation for more information. + * + * @param uxPriority The priority with respect to other co-routines at which + * the co-routine will run. + * + * @param uxIndex Used to distinguish between different co-routines that + * execute the same function. See the example below and the co-routine section + * of the WEB documentation for further information. + * + * @return pdPASS if the co-routine was successfully created and added to a ready + * list, otherwise an error code defined with ProjDefs.h. + * + * Example usage: +
+ // Co-routine to be created.
+ void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ static const char cLedToFlash[ 2 ] = { 5, 6 };
+ static const portTickType uxFlashRates[ 2 ] = { 200, 400 };
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // This co-routine just delays for a fixed period, then toggles
+         // an LED.  Two co-routines are created using this function, so
+         // the uxIndex parameter is used to tell the co-routine which
+         // LED to flash and how long to delay.  This assumes xQueue has
+         // already been created.
+         vParTestToggleLED( cLedToFlash[ uxIndex ] );
+         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+
+ // Function that creates two co-routines.
+ void vOtherFunction( void )
+ {
+ unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+		
+     // Create two co-routines at priority 0.  The first is given index 0
+     // so (from the code above) toggles LED 5 every 200 ticks.  The second
+     // is given index 1 so toggles LED 6 every 400 ticks.
+     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
+     {
+         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
+     }
+ }
+   
+ * \defgroup xCoRoutineCreate xCoRoutineCreate + * \ingroup Tasks + */ +signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); + + +/** + * croutine. h + *
+ void vCoRoutineSchedule( void );
+ * + * Run a co-routine. + * + * vCoRoutineSchedule() executes the highest priority co-routine that is able + * to run. The co-routine will execute until it either blocks, yields or is + * preempted by a task. Co-routines execute cooperatively so one + * co-routine cannot be preempted by another, but can be preempted by a task. + * + * If an application comprises of both tasks and co-routines then + * vCoRoutineSchedule should be called from the idle task (in an idle task + * hook). + * + * Example usage: +
+ // This idle task hook will schedule a co-routine each time it is called.
+ // The rest of the idle task will execute between co-routine calls.
+ void vApplicationIdleHook( void )
+ {
+	vCoRoutineSchedule();
+ }
+
+ // Alternatively, if you do not require any other part of the idle task to
+ // execute, the idle task hook can call vCoRoutineScheduler() within an
+ // infinite loop.
+ void vApplicationIdleHook( void )
+ {
+    for( ;; )
+    {
+        vCoRoutineSchedule();
+    }
+ }
+ 
+ * \defgroup vCoRoutineSchedule vCoRoutineSchedule + * \ingroup Tasks + */ +void vCoRoutineSchedule( void ); + +/** + * croutine. h + *
+ crSTART( xCoRoutineHandle xHandle );
+ * + * This macro MUST always be called at the start of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crSTART( pxCRCB ) switch( ( ( corCRCB * )( pxCRCB ) )->uxState ) { case 0: + +/** + * croutine. h + *
+ crEND();
+ * + * This macro MUST always be called at the end of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crEND() } + +/* + * These macros are intended for internal use by the co-routine implementation + * only. The macros should not be used directly by application writers. + */ +#define crSET_STATE0( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): +#define crSET_STATE1( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): + +/** + * croutine. h + *
+ crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
+ * + * Delay a co-routine for a fixed period of time. + * + * crDELAY can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * @param xHandle The handle of the co-routine to delay. This is the xHandle + * parameter of the co-routine function. + * + * @param xTickToDelay The number of ticks that the co-routine should delay + * for. The actual amount of time this equates to is defined by + * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS + * can be used to convert ticks to milliseconds. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ // We are to delay for 200ms.
+ static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+        // Delay for 200ms.
+        crDELAY( xHandle, xDelayTime );
+
+        // Do something here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crDELAY crDELAY + * \ingroup Tasks + */ +#define crDELAY( xHandle, xTicksToDelay ) \ + if( ( xTicksToDelay ) > 0 ) \ + { \ + vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL ); \ + } \ + crSET_STATE0( ( xHandle ) ); + +/** + *
+ crQUEUE_SEND(
+                  xCoRoutineHandle xHandle,
+                  xQueueHandle pxQueue,
+                  void *pvItemToQueue,
+                  portTickType xTicksToWait,
+                  portBASE_TYPE *pxResult
+             )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_SEND can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue on which the data will be posted. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvItemToQueue A pointer to the data being posted onto the queue. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied from pvItemToQueue into the queue + * itself. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for space to become available on the queue, should space not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example + * below). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully posted onto the queue, otherwise it will be set to an + * error defined within ProjDefs.h. + * + * Example usage: +
+ // Co-routine function that blocks for a fixed period then posts a number onto
+ // a queue.
+ static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xNumberToPost = 0;
+ static portBASE_TYPE xResult;
+
+    // Co-routines must begin with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // This assumes the queue has already been created.
+        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
+
+        if( xResult != pdPASS )
+        {
+            // The message was not posted!
+        }
+
+        // Increment the number to be posted onto the queue.
+        xNumberToPost++;
+
+        // Delay for 100 ticks.
+        crDELAY( xHandle, 100 );
+    }
+
+    // Co-routines must end with a call to crEND().
+    crEND();
+ }
+ * \defgroup crQUEUE_SEND crQUEUE_SEND + * \ingroup Tasks + */ +#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 ); \ + } \ + if( *pxResult == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *pxResult = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_RECEIVE(
+                     xCoRoutineHandle xHandle,
+                     xQueueHandle pxQueue,
+                     void *pvBuffer,
+                     portTickType xTicksToWait,
+                     portBASE_TYPE *pxResult
+                 )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_RECEIVE can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue from which the data will be received. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvBuffer The buffer into which the received item is to be copied. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied into pvBuffer. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for data to become available from the queue, should data not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the + * crQUEUE_SEND example). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully retrieved from the queue, otherwise it will be set to + * an error code as defined within ProjDefs.h. + * + * Example usage: +
+ // A co-routine receives the number of an LED to flash from a queue.  It
+ // blocks on the queue until the number is received.
+ static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xResult;
+ static unsigned portBASE_TYPE uxLEDToFlash;
+
+    // All co-routines must start with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // Wait for data to become available on the queue.
+        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+        if( xResult == pdPASS )
+        {
+            // We received the LED to flash - flash it!
+            vParTestToggleLED( uxLEDToFlash );
+        }
+    }
+
+    crEND();
+ }
+ * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 ); \ + } \ + if( *( pxResult ) == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *( pxResult ) = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvItemToQueue,
+                            portBASE_TYPE xCoRoutinePreviouslyWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue + * that is being used from within a co-routine. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto + * the same queue multiple times from a single interrupt. The first call + * should always pass in pdFALSE. Subsequent calls should pass in + * the value returned from the previous call. + * + * @return pdTRUE if a co-routine was woken by posting onto the queue. This is + * used by the ISR to determine if a context switch may be required following + * the ISR. + * + * Example usage: +
+ // A co-routine that blocks on a queue waiting for characters to be received.
+ static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ char cRxedChar;
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Wait for data to become available on the queue.  This assumes the
+         // queue xCommsRxQueue has already been created!
+         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+         // Was a character received?
+         if( xResult == pdPASS )
+         {
+             // Process the character here.
+         }
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to send characters received on a serial port to
+ // a co-routine.
+ void vUART_ISR( void )
+ {
+ char cRxedChar;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     // We loop around reading characters until there are none left in the UART.
+     while( UART_RX_REG_NOT_EMPTY() )
+     {
+         // Obtain the character from the UART.
+         cRxedChar = UART_RX_REG;
+
+         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
+         // the first time around the loop.  If the post causes a co-routine
+         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
+         // In this manner we can ensure that if more than one co-routine is
+         // blocked on the queue only one is woken by this ISR no matter how
+         // many characters are posted to the queue.
+         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
+     }
+ }
+ * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) ) + + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvBuffer,
+                            portBASE_TYPE * pxCoRoutineWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data + * from a queue that is being used from within a co-routine (a co-routine + * posted to the queue). + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvBuffer A pointer to a buffer into which the received item will be + * placed. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from the queue into + * pvBuffer. + * + * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become + * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a + * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise + * *pxCoRoutineWoken will remain unchanged. + * + * @return pdTRUE an item was successfully received from the queue, otherwise + * pdFALSE. + * + * Example usage: +
+ // A co-routine that posts a character to a queue then blocks for a fixed
+ // period.  The character is incremented each time.
+ static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // cChar holds its value while this co-routine is blocked and must therefore
+ // be declared static.
+ static char cCharToTx = 'a';
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Send the next character to the queue.
+         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
+
+         if( xResult == pdPASS )
+         {
+             // The character was successfully posted to the queue.
+         }
+		 else
+		 {
+			// Could not post the character to the queue.
+		 }
+
+         // Enable the UART Tx interrupt to cause an interrupt in this
+		 // hypothetical UART.  The interrupt will obtain the character
+		 // from the queue and send it.
+		 ENABLE_RX_INTERRUPT();
+
+		 // Increment to the next character then block for a fixed period.
+		 // cCharToTx will maintain its value across the delay as it is
+		 // declared static.
+		 cCharToTx++;
+		 if( cCharToTx > 'x' )
+		 {
+			cCharToTx = 'a';
+		 }
+		 crDELAY( 100 );
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to receive characters to send on a UART.
+ void vUART_ISR( void )
+ {
+ char cCharToTx;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     while( UART_TX_REG_EMPTY() )
+     {
+         // Are there any characters in the queue waiting to be sent?
+		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
+		 // is woken by the post - ensuring that only a single co-routine is
+		 // woken no matter how many times we go around this loop.
+         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
+		 {
+			 SEND_CHARACTER( cCharToTx );
+		 }
+     }
+ }
+ * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) ) + +/* + * This function is intended for internal use by the co-routine macros only. + * The macro nature of the co-routine implementation requires that the + * prototype appears here. The function should not be used by application + * writers. + * + * Removes the current co-routine from its ready list and places it in the + * appropriate delayed list. + */ +void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); + +/* + * This function is intended for internal use by the queue implementation only. + * The function should not be used by application writers. + * + * Removes the highest priority co-routine from the event list and places it in + * the pending ready list. + */ +signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); + +#ifdef __cplusplus +} +#endif + +#endif /* CO_ROUTINE_H */ diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h new file mode 100644 index 000000000..d5dfda514 --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h @@ -0,0 +1,308 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/* + * This is the list implementation used by the scheduler. While it is tailored + * heavily for the schedulers needs, it is also available for use by + * application code. + * + * xLists can only store pointers to xListItems. Each xListItem contains a + * numeric value (xItemValue). Most of the time the lists are sorted in + * descending item value order. + * + * Lists are created already containing one list item. The value of this + * item is the maximum possible that can be stored, it is therefore always at + * the end of the list and acts as a marker. The list member pxHead always + * points to this marker - even though it is at the tail of the list. This + * is because the tail contains a wrap back pointer to the true head of + * the list. + * + * In addition to it's value, each list item contains a pointer to the next + * item in the list (pxNext), a pointer to the list it is in (pxContainer) + * and a pointer to back to the object that contains it. These later two + * pointers are included for efficiency of list manipulation. There is + * effectively a two way link between the object containing the list item and + * the list item itself. + * + * + * \page ListIntroduction List Implementation + * \ingroup FreeRTOSIntro + */ + + +#ifndef LIST_H +#define LIST_H + +#ifdef __cplusplus +extern "C" { +#endif +/* + * Definition of the only type of object that a list can contain. + */ +struct xLIST_ITEM +{ + portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ + volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ + volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ + void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ + void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ +}; +typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ + +struct xMINI_LIST_ITEM +{ + portTickType xItemValue; + volatile struct xLIST_ITEM *pxNext; + volatile struct xLIST_ITEM *pxPrevious; +}; +typedef struct xMINI_LIST_ITEM xMiniListItem; + +/* + * Definition of the type of queue used by the scheduler. + */ +typedef struct xLIST +{ + volatile unsigned portBASE_TYPE uxNumberOfItems; + volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ + volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ +} xList; + +/* + * Access macro to set the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) + +/* + * Access macro to set the value of the list item. In most cases the value is + * used to sort the list in descending order. + * + * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = ( xValue ) + +/* + * Access macro the retrieve the value of the list item. The value can + * represent anything - for example a the priority of a task, or the time at + * which a task should be unblocked. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) + +/* + * Access macro the retrieve the value of the list item at the head of a given + * list. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->xItemValue ) + +/* + * Access macro to determine if a list contains any items. The macro will + * only have the value true if the list is empty. + * + * \page listLIST_IS_EMPTY listLIST_IS_EMPTY + * \ingroup LinkedList + */ +#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) + +/* + * Access macro to return the number of items in the list. + */ +#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) + +/* + * Access function to obtain the owner of the next entry in a list. + * + * The list member pxIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list + * and returns that entries pxOwner parameter. Using multiple calls to this + * function it is therefore possible to move through every item contained in + * a list. + * + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the next item owner is to be returned. + * + * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ +{ \ +xList * const pxConstList = ( pxList ); \ + /* Increment the index to the next item and return the item, ensuring */ \ + /* we don't return the marker used at the end of the list. */ \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ + { \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + } \ + ( pxTCB ) = ( pxConstList )->pxIndex->pvOwner; \ +} + + +/* + * Access function to obtain the owner of the first entry in a list. Lists + * are normally sorted in ascending item value order. + * + * This function returns the pxOwner member of the first item in the list. + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the owner of the head item is to be + * returned. + * + * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner ) + +/* + * Check to see if a list item is within a list. The list item maintains a + * "container" pointer that points to the list it is in. All this macro does + * is check to see if the container and the list match. + * + * @param pxList The list we want to know if the list item is within. + * @param pxListItem The list item we want to know if is in the list. + * @return pdTRUE is the list item is in the list, otherwise pdFALSE. + * pointer against + */ +#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) ( pxList ) ) + +/* + * Must be called before a list is used! This initialises all the members + * of the list structure and inserts the xListEnd item into the list as a + * marker to the back of the list. + * + * @param pxList Pointer to the list being initialised. + * + * \page vListInitialise vListInitialise + * \ingroup LinkedList + */ +void vListInitialise( xList *pxList ); + +/* + * Must be called before a list item is used. This sets the list container to + * null so the item does not think that it is already contained in a list. + * + * @param pxItem Pointer to the list item being initialised. + * + * \page vListInitialiseItem vListInitialiseItem + * \ingroup LinkedList + */ +void vListInitialiseItem( xListItem *pxItem ); + +/* + * Insert a list item into a list. The item will be inserted into the list in + * a position determined by its item value (descending item value order). + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The item to that is to be placed in the list. + * + * \page vListInsert vListInsert + * \ingroup LinkedList + */ +void vListInsert( xList *pxList, xListItem *pxNewListItem ); + +/* + * Insert a list item into a list. The item will be inserted in a position + * such that it will be the last item within the list returned by multiple + * calls to listGET_OWNER_OF_NEXT_ENTRY. + * + * The list member pvIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. + * Placing an item in a list using vListInsertEnd effectively places the item + * in the list position pointed to by pvIndex. This means that every other + * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before + * the pvIndex parameter again points to the item being inserted. + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The list item to be inserted into the list. + * + * \page vListInsertEnd vListInsertEnd + * \ingroup LinkedList + */ +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); + +/* + * Remove an item from a list. The list item has a pointer to the list that + * it is in, so only the list item need be passed into the function. + * + * @param vListRemove The item to be removed. The item will remove itself from + * the list pointed to by it's pxContainer parameter. + * + * \page vListRemove vListRemove + * \ingroup LinkedList + */ +void vListRemove( xListItem *pxItemToRemove ); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h new file mode 100644 index 000000000..a2759d5e8 --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h @@ -0,0 +1,135 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef MPU_WRAPPERS_H +#define MPU_WRAPPERS_H + +/* This file redefines API functions to be called through a wrapper macro, but +only for ports that are using the MPU. */ +#ifdef portUSING_MPU_WRAPPERS + + /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is + included from queue.c or task.c to prevent it from having an effect within + those files. */ + #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + + #define xTaskGenericCreate MPU_xTaskGenericCreate + #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions + #define vTaskDelete MPU_vTaskDelete + #define vTaskDelayUntil MPU_vTaskDelayUntil + #define vTaskDelay MPU_vTaskDelay + #define uxTaskPriorityGet MPU_uxTaskPriorityGet + #define vTaskPrioritySet MPU_vTaskPrioritySet + #define vTaskSuspend MPU_vTaskSuspend + #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended + #define vTaskResume MPU_vTaskResume + #define vTaskSuspendAll MPU_vTaskSuspendAll + #define xTaskResumeAll MPU_xTaskResumeAll + #define xTaskGetTickCount MPU_xTaskGetTickCount + #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks + #define vTaskList MPU_vTaskList + #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats + #define vTaskStartTrace MPU_vTaskStartTrace + #define ulTaskEndTrace MPU_ulTaskEndTrace + #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag + #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag + #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook + #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark + #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle + #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState + + #define xQueueCreate MPU_xQueueCreate + #define xQueueCreateMutex MPU_xQueueCreateMutex + #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive + #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive + #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore + #define xQueueGenericSend MPU_xQueueGenericSend + #define xQueueAltGenericSend MPU_xQueueAltGenericSend + #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive + #define xQueueGenericReceive MPU_xQueueGenericReceive + #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting + #define vQueueDelete MPU_vQueueDelete + + #define pvPortMalloc MPU_pvPortMalloc + #define vPortFree MPU_vPortFree + #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize + #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks + + #if configQUEUE_REGISTRY_SIZE > 0 + #define vQueueAddToRegistry MPU_vQueueAddToRegistry + #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue + #endif + + /* Remove the privileged function macro. */ + #define PRIVILEGED_FUNCTION + + #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + + /* Ensure API functions go in the privileged execution section. */ + #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) + #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) + //#define PRIVILEGED_DATA + + #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + +#else /* portUSING_MPU_WRAPPERS */ + + #define PRIVILEGED_FUNCTION + #define PRIVILEGED_DATA + #define portUSING_MPU_WRAPPERS 0 + +#endif /* portUSING_MPU_WRAPPERS */ + + +#endif /* MPU_WRAPPERS_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h new file mode 100644 index 000000000..b46ad87d3 --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h @@ -0,0 +1,390 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/*----------------------------------------------------------- + * Portable layer API. Each function must be defined for each port. + *----------------------------------------------------------*/ + +#ifndef PORTABLE_H +#define PORTABLE_H + +/* Include the macro file relevant to the port being used. */ + +#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT + #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT + #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef GCC_MEGA_AVR + #include "../portable/GCC/ATMega323/portmacro.h" +#endif + +#ifdef IAR_MEGA_AVR + #include "../portable/IAR/ATMega323/portmacro.h" +#endif + +#ifdef MPLAB_PIC24_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_DSPIC_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_PIC18F_PORT + #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" +#endif + +#ifdef MPLAB_PIC32MX_PORT + #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" +#endif + +#ifdef _FEDPICC + #include "libFreeRTOS/Include/portmacro.h" +#endif + +#ifdef SDCC_CYGNAL + #include "../../Source/portable/SDCC/Cygnal/portmacro.h" +#endif + +#ifdef GCC_ARM7 + #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" +#endif + +#ifdef GCC_ARM7_ECLIPSE + #include "portmacro.h" +#endif + +#ifdef ROWLEY_LPC23xx + #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" +#endif + +#ifdef IAR_MSP430 + #include "..\..\Source\portable\IAR\MSP430\portmacro.h" +#endif + +#ifdef GCC_MSP430 + #include "../../Source/portable/GCC/MSP430F449/portmacro.h" +#endif + +#ifdef ROWLEY_MSP430 + #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" +#endif + +#ifdef ARM7_LPC21xx_KEIL_RVDS + #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" +#endif + +#ifdef SAM7_GCC + #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" +#endif + +#ifdef SAM7_IAR + #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" +#endif + +#ifdef SAM9XE_IAR + #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" +#endif + +#ifdef LPC2000_IAR + #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" +#endif + +#ifdef STR71X_IAR + #include "..\..\Source\portable\IAR\STR71x\portmacro.h" +#endif + +#ifdef STR75X_IAR + #include "..\..\Source\portable\IAR\STR75x\portmacro.h" +#endif + +#ifdef STR75X_GCC + #include "..\..\Source\portable\GCC\STR75x\portmacro.h" +#endif + +#ifdef STR91X_IAR + #include "..\..\Source\portable\IAR\STR91x\portmacro.h" +#endif + +#ifdef GCC_H8S + #include "../../Source/portable/GCC/H8S2329/portmacro.h" +#endif + +#ifdef GCC_AT91FR40008 + #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" +#endif + +#ifdef RVDS_ARMCM3_LM3S102 + #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3_LM3S102 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARM_CM3 + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARMCM3_LM + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef HCS12_CODE_WARRIOR + #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" +#endif + +#ifdef MICROBLAZE_GCC + #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" +#endif + +#ifdef TERN_EE + #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" +#endif + +#ifdef GCC_HCS12 + #include "../../Source/portable/GCC/HCS12/portmacro.h" +#endif + +#ifdef GCC_MCF5235 + #include "../../Source/portable/GCC/MCF5235/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_GCC + #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_CODEWARRIOR + #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" +#endif + +#ifdef GCC_PPC405 + #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" +#endif + +#ifdef GCC_PPC440 + #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" +#endif + +#ifdef _16FX_SOFTUNE + #include "..\..\Source\portable\Softune\MB96340\portmacro.h" +#endif + +#ifdef BCC_INDUSTRIAL_PC_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef BCC_FLASH_LITE_186_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef __GNUC__ + #ifdef __AVR32_AVR32A__ + #include "portmacro.h" + #endif +#endif + +#ifdef __ICCAVR32__ + #ifdef __CORE__ + #if __CORE__ == __AVR32A__ + #include "portmacro.h" + #endif + #endif +#endif + +#ifdef __91467D + #include "portmacro.h" +#endif + +#ifdef __96340 + #include "portmacro.h" +#endif + + +#ifdef __IAR_V850ES_Fx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3_L__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Hx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3L__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +/* Catch all to ensure portmacro.h is included in the build. Newer demos +have the path as part of the project options, rather than as relative from +the project location. If portENTER_CRITICAL() has not been defined then +portmacro.h has not yet been included - as every portmacro.h provides a +portENTER_CRITICAL() definition. Check the demo application for your demo +to find the path to the correct portmacro.h file. */ +#ifndef portENTER_CRITICAL + #include "portmacro.h" +#endif + +#if portBYTE_ALIGNMENT == 8 + #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) +#endif + +#if portBYTE_ALIGNMENT == 4 + #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) +#endif + +#if portBYTE_ALIGNMENT == 2 + #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) +#endif + +#if portBYTE_ALIGNMENT == 1 + #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) +#endif + +#ifndef portBYTE_ALIGNMENT_MASK + #error "Invalid portBYTE_ALIGNMENT definition" +#endif + +#ifndef portNUM_CONFIGURABLE_REGIONS + #define portNUM_CONFIGURABLE_REGIONS 1 +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#include "mpu_wrappers.h" + +/* + * Setup the stack of a new task so it is ready to be placed under the + * scheduler control. The registers have to be placed on the stack in + * the order that the port expects to find them. + * + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, portSTACK_TYPE *pxStartOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; +#else + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, portSTACK_TYPE *pxStartOfStack, pdTASK_CODE pxCode, void *pvParameters ); +#endif + +/* + * Map to the memory management routines required for the port. + */ +void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; +void vPortFree( void *pv ) PRIVILEGED_FUNCTION; +void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; +size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; + +/* + * Setup the hardware ready for the scheduler to take control. This generally + * sets up a tick interrupt and sets timers for the correct tick frequency. + */ +portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so + * the hardware is left in its original condition after the scheduler stops + * executing. + */ +void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * The structures and methods of manipulating the MPU are contained within the + * port layer. + * + * Fills the xMPUSettings structure with the memory region information + * contained in xRegions. + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + struct xMEMORY_REGION; + void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* PORTABLE_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h new file mode 100644 index 000000000..d0b73c85e --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h @@ -0,0 +1,82 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef PROJDEFS_H +#define PROJDEFS_H + +void PIOS_DEBUG_PinValue8Bit(unsigned char value); + +/* Defines the prototype to which task functions must conform. */ +typedef void (*pdTASK_CODE)( void * ); + +#define pdTRUE ( 1 ) +#define pdFALSE ( 0 ) + +#define pdPASS ( 1 ) +#define pdFAIL ( 0 ) +#define errQUEUE_EMPTY ( 0 ) +#define errQUEUE_FULL ( 0 ) + +/* Error definitions. */ +#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) +#define errNO_TASK_TO_RUN ( -2 ) +#define errQUEUE_BLOCKED ( -4 ) +#define errQUEUE_YIELD ( -5 ) + +// Uncomment this line to output the second character of the task that is being switched in on the debug-pins +//#define traceTASK_SWITCHED_IN() PIOS_DEBUG_PinValue8Bit(pxCurrentTCB->pcTaskName[1]); + +#endif /* PROJDEFS_H */ + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h new file mode 100644 index 000000000..5026306bd --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h @@ -0,0 +1,1264 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef QUEUE_H +#define QUEUE_H + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include queue.h" +#endif + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "mpu_wrappers.h" + +/** + * Type by which queues are referenced. For example, a call to xQueueCreate + * returns (via a pointer parameter) an xQueueHandle variable that can then + * be used as a parameter to xQueueSend(), xQueueReceive(), etc. + */ +typedef void * xQueueHandle; + + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + + +/** + * queue. h + *
+ xQueueHandle xQueueCreate(
+							  unsigned portBASE_TYPE uxQueueLength,
+							  unsigned portBASE_TYPE uxItemSize
+						  );
+ * 
+ * + * Creates a new queue instance. This allocates the storage required by the + * new queue and returns a handle for the queue. + * + * @param uxQueueLength The maximum number of items that the queue can contain. + * + * @param uxItemSize The number of bytes each item in the queue will require. + * Items are queued by copy, not by reference, so this is the number of bytes + * that will be copied for each posted item. Each item on the queue must be + * the same size. + * + * @return If the queue is successfully create then a handle to the newly + * created queue is returned. If the queue cannot be created then 0 is + * returned. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+	if( xQueue1 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue2 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueCreate xQueueCreate + * \ingroup QueueManagement + */ +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToToFront(
+								   xQueueHandle	xQueue,
+								   const void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the front of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBack(
+								   xQueueHandle	xQueue,
+								   const	void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the back of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the queue + * is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSend(
+							  xQueueHandle xQueue,
+							  const void * pvItemToQueue,
+							  portTickType xTicksToWait
+						 );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). It is included for + * backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToFront() and xQueueSendToBack() macros. It is + * equivalent to xQueueSendToBack(). + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSend(
+									xQueueHandle xQueue,
+									const void * pvItemToQueue,
+									portTickType xTicksToWait
+									portBASE_TYPE xCopyPosition
+								);
+ * 
+ * + * It is preferred that the macros xQueueSend(), xQueueSendToFront() and + * xQueueSendToBack() are used in place of calling this function directly. + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueuePeek(
+							 xQueueHandle xQueue,
+							 void *pvBuffer,
+							 portTickType xTicksToWait
+						 );
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue without removing the item from the queue. + * The item is received by copy so a buffer of adequate size must be + * provided. The number of bytes copied into the buffer was defined when + * the queue was created. + * + * Successfully received items remain on the queue so will be returned again + * by the next call, or a call to xQueueReceive(). + * + * This macro must not be used in an interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue + * is empty. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to peek the data from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Peek a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask, but the item still remains on the queue.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceive(
+								 xQueueHandle xQueue,
+								 void *pvBuffer,
+								 portTickType xTicksToWait
+							);
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * Successfully received items are removed from the queue. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. xQueueReceive() will return immediately if xTicksToWait + * is zero and the queue is empty. The time is defined in tick periods so the + * constant portTICK_RATE_MS should be used to convert to real time if this is + * required. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericReceive(
+									   xQueueHandle	xQueue,
+									   void	*pvBuffer,
+									   portTickType	xTicksToWait
+									   portBASE_TYPE	xJustPeek
+									);
+ * + * It is preferred that the macro xQueueReceive() be used rather than calling + * this function directly. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueueGenericReceive() will return immediately if the queue is empty and + * xTicksToWait is 0. + * + * @param xJustPeek When set to true, the item received from the queue is not + * actually removed from the queue - meaning a subsequent call to + * xQueueReceive() will return the same item. When set to false, the item + * being received from the queue is also removed from the queue. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); + +/** + * queue. h + *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
+ * + * Return the number of messages stored in a queue. + * + * @param xQueue A handle to the queue being queried. + * + * @return The number of messages available in the queue. + * + * \page uxQueueMessagesWaiting uxQueueMessagesWaiting + * \ingroup QueueManagement + */ +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); + +/** + * queue. h + *
void vQueueDelete( xQueueHandle xQueue );
+ * + * Delete a queue - freeing all the memory allocated for storing of items + * placed on the queue. + * + * @param xQueue A handle to the queue to be deleted. + * + * \page vQueueDelete vQueueDelete + * \ingroup QueueManagement + */ +void vQueueDelete( xQueueHandle pxQueue ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToFrontFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the front of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPrioritTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBackFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the back of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendFromISR(
+									 xQueueHandle pxQueue,
+									 const void *pvItemToQueue,
+									 portBASE_TYPE *pxHigherPriorityTaskWoken
+								);
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). It is included + * for backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() + * macros. + * + * Post an item to the back of a queue. It is safe to use this function from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		// Actual macro used here is port specific.
+		taskYIELD_FROM_ISR ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSendFromISR(
+										   xQueueHandle	pxQueue,
+										   const	void	*pvItemToQueue,
+										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
+										   portBASE_TYPE	xCopyPosition
+									   );
+ 
+ * + * It is preferred that the macros xQueueSendFromISR(), + * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place + * of calling this function directly. + * + * Post an item on a queue. It is safe to use this function from within an + * interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWokenByPost;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWokenByPost = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post each byte.
+		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.  Note that the
+	// name of the yield function required is port specific.
+	if( xHigherPriorityTaskWokenByPost )
+	{
+		taskYIELD_YIELD_FROM_ISR();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceiveFromISR(
+									   xQueueHandle	pxQueue,
+									   void	*pvBuffer,
+									   portBASE_TYPE	*pxTaskWoken
+								   );
+ * 
+ * + * Receive an item from a queue. It is safe to use this function from within an + * interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param pxTaskWoken A task may be blocked waiting for space to become + * available on the queue. If xQueueReceiveFromISR causes such a task to + * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will + * remain unchanged. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+
+ xQueueHandle xQueue;
+
+ // Function to create a queue and post some values.
+ void vAFunction( void *pvParameters )
+ {
+ char cValueToPost;
+ const portTickType xBlockTime = ( portTickType )0xff;
+
+	// Create a queue capable of containing 10 characters.
+	xQueue = xQueueCreate( 10, sizeof( char ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Post some characters that will be used within an ISR.  If the queue
+	// is full then this task will block for xBlockTime ticks.
+	cValueToPost = 'a';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+	cValueToPost = 'b';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+
+	// ... keep posting characters ... this task may block when the queue
+	// becomes full.
+
+	cValueToPost = 'c';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+ }
+
+ // ISR that outputs all the characters received on the queue.
+ void vISR_Routine( void )
+ {
+ portBASE_TYPE xTaskWokenByReceive = pdFALSE;
+ char cRxedChar;
+
+	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
+	{
+		// A character was received.  Output the character now.
+		vOutputCharacter( cRxedChar );
+
+		// If removing the character from the queue woke the task that was
+		// posting onto the queue cTaskWokenByReceive will have been set to
+		// pdTRUE.  No matter how many times this loop iterates only one
+		// task will be woken.
+	}
+
+	if( cTaskWokenByPost != ( char ) pdFALSE;
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ); + +/* + * Utilities to query queue that are safe to use from an ISR. These utilities + * should be used only from witin an ISR, or within a critical section. + */ +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); + + +/* + * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). + * Likewise xQueueAltGenericReceive() is an alternative version of + * xQueueGenericReceive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); +#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) +#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) +#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) +#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) + +/* + * The functions defined above are for passing data to and from tasks. The + * functions below are the equivalents for passing data to and from + * co-routines. + * + * These functions are called from the co-routine macro implementation and + * should not be called directly from application code. Instead use the macro + * wrappers defined within croutine.h. + */ +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); + +/* + * For internal use only. Use xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting() instead of calling these functions directly. + */ +xQueueHandle xQueueCreateMutex( void ); +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); + +/* + * For internal use only. Use xSemaphoreTakeMutexRecursive() or + * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. + */ +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ); +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ); + +/* + * The registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add + * a queue, semaphore or mutex handle to the registry if you want the handle + * to be available to a kernel aware debugger. If you are not using a kernel + * aware debugger then this function can be ignored. + * + * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the + * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 + * within FreeRTOSConfig.h for the registry to be available. Its value + * does not effect the number of queues, semaphores and mutexes that can be + * created - just the number that the registry can hold. + * + * @param xQueue The handle of the queue being added to the registry. This + * is the handle returned by a call to xQueueCreate(). Semaphore and mutex + * handles can also be passed in here. + * + * @param pcName The name to be associated with the handle. This is the + * name that the kernel aware debugger will display. + */ +#if configQUEUE_REGISTRY_SIZE > 0U + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); +#endif + +/* Not a public API function, hence the 'Restricted' in the name. */ +void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ); + + +#ifdef __cplusplus +} +#endif + +#endif /* QUEUE_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h new file mode 100644 index 000000000..13b8ee63d --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h @@ -0,0 +1,724 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef SEMAPHORE_H +#define SEMAPHORE_H + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include semphr.h" +#endif + +#include "queue.h" + +typedef xQueueHandle xSemaphoreHandle; + +#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1U ) +#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0U ) +#define semGIVE_BLOCK_TIME ( ( portTickType ) 0U ) + + +/** + * semphr. h + *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
+ * + * Macro that implements a semaphore by using the existing queue mechanism. + * The queue length is 1 as this is a binary semaphore. The data size is 0 + * as we don't want to actually store any data - we just want to know if the + * queue is empty or full. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
+    // This is a macro so pass the variable in directly.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary + * \ingroup Semaphores + */ +#define vSemaphoreCreateBinary( xSemaphore ) { \ + ( xSemaphore ) = xQueueCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH ); \ + if( ( xSemaphore ) != NULL ) \ + { \ + xSemaphoreGive( ( xSemaphore ) ); \ + } \ + } + +/** + * semphr. h + *
xSemaphoreTake( 
+ *                   xSemaphoreHandle xSemaphore, 
+ *                   portTickType xBlockTime 
+ *               )
+ * + * Macro to obtain a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). + * + * @param xSemaphore A handle to the semaphore being taken - obtained when + * the semaphore was created. + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. A block + * time of portMAX_DELAY can be used to block indefinitely (provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). + * + * @return pdTRUE if the semaphore was obtained. pdFALSE + * if xBlockTime expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // A task that creates a semaphore.
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+ }
+
+ // A task that uses the semaphore.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xSemaphore != NULL )
+    {
+        // See if we can obtain the semaphore.  If the semaphore is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the semaphore and can now access the
+            // shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource.  Release the 
+            // semaphore.
+            xSemaphoreGive( xSemaphore );
+        }
+        else
+        {
+            // We could not obtain the semaphore and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTake xSemaphoreTake + * \ingroup Semaphores + */ +#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) + +/** + * semphr. h + * xSemaphoreTakeRecursive( + * xSemaphoreHandle xMutex, + * portTickType xBlockTime + * ) + * + * Macro to recursively obtain, or 'take', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being obtained. This is the + * handle returned by xSemaphoreCreateRecursiveMutex(); + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. If + * the task already owns the semaphore then xSemaphoreTakeRecursive() will + * return immediately no matter what the value of xBlockTime. + * + * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime + * expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, but instead buried in a more complex
+			// call structure.  This is just for illustrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive + * \ingroup Semaphores + */ +#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) ) + + +/* + * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) + +/** + * semphr. h + *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). + * + * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for + * an alternative which can be used from an ISR. + * + * This macro must also not be used on semaphores created using + * xSemaphoreCreateRecursiveMutex(). + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. + * Semaphores are implemented using queues. An error can occur if there is + * no space on the queue to post a message - indicating that the + * semaphore was not first obtained correctly. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+        {
+            // We would expect this call to fail because we cannot give
+            // a semaphore without first "taking" it!
+        }
+
+        // Obtain the semaphore - don't block if the semaphore is not
+        // immediately available.
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
+        {
+            // We now have the semaphore and can access the shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource so can free the
+            // semaphore.
+            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+            {
+                // We would not expect this call to fail because we must have
+                // obtained the semaphore to get here.
+            }
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGive xSemaphoreGive + * \ingroup Semaphores + */ +#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
+ * + * Macro to recursively release, or 'give', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being released, or 'given'. This is the + * handle returned by xSemaphoreCreateMutex(); + * + * @return pdTRUE if the semaphore was given. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, it would be more likely that the calls
+			// to xSemaphoreGiveRecursive() would be called as a call stack
+			// unwound.  This is just for demonstrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive + * \ingroup Semaphores + */ +#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) ) + +/* + * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
+ xSemaphoreGiveFromISR( 
+                          xSemaphoreHandle xSemaphore, 
+                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR. + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. + * + * Example usage: +
+ \#define LONG_TIME 0xffff
+ \#define TICKS_TO_WAIT	10
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // Repetitive task.
+ void vATask( void * pvParameters )
+ {
+    for( ;; )
+    {
+        // We want this task to run every 10 ticks of a timer.  The semaphore 
+        // was created before this task was started.
+
+        // Block waiting for the semaphore to become available.
+        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
+        {
+            // It is time to execute.
+
+            // ...
+
+            // We have finished our task.  Return to the top of the loop where
+            // we will block on the semaphore until it is time to execute 
+            // again.  Note when using the semaphore for synchronisation with an
+			// ISR in this manner there is no need to 'give' the semaphore back.
+        }
+    }
+ }
+
+ // Timer ISR
+ void vTimerISR( void * pvParameters )
+ {
+ static unsigned char ucLocalTickCount = 0;
+ static signed portBASE_TYPE xHigherPriorityTaskWoken;
+
+    // A timer tick has occurred.
+
+    // ... Do other time functions.
+
+    // Is it time for vATask () to run?
+	xHigherPriorityTaskWoken = pdFALSE;
+    ucLocalTickCount++;
+    if( ucLocalTickCount >= TICKS_TO_WAIT )
+    {
+        // Unblock the task by releasing the semaphore.
+        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
+
+        // Reset the count so we release the semaphore again in 10 ticks time.
+        ucLocalTickCount = 0;
+    }
+
+    if( xHigherPriorityTaskWoken != pdFALSE )
+    {
+        // We can force a context switch here.  Context switching from an
+        // ISR uses port specific syntax.  Check the demo task for your port
+        // to find the syntax required.
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR + * \ingroup Semaphores + */ +#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateMutex( void )
+ * + * Macro that implements a mutex semaphore by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the xSemaphoreTake() + * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and + * xSemaphoreGiveRecursive() macros should not be used. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateMutex() xQueueCreateMutex() + + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
+ * + * Macro that implements a recursive mutex by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the + * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The + * xSemaphoreTake() and xSemaphoreGive() macros should not be used. + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateRecursiveMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex() + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
+ * + * Macro that creates a counting semaphore by using the existing + * queue mechanism. + * + * Counting semaphores are typically used for two things: + * + * 1) Counting events. + * + * In this usage scenario an event handler will 'give' a semaphore each time + * an event occurs (incrementing the semaphore count value), and a handler + * task will 'take' a semaphore each time it processes an event + * (decrementing the semaphore count value). The count value is therefore + * the difference between the number of events that have occurred and the + * number that have been processed. In this case it is desirable for the + * initial count value to be zero. + * + * 2) Resource management. + * + * In this usage scenario the count value indicates the number of resources + * available. To obtain control of a resource a task must first obtain a + * semaphore - decrementing the semaphore count value. When the count value + * reaches zero there are no free resources. When a task finishes with the + * resource it 'gives' the semaphore back - incrementing the semaphore count + * value. In this case it is desirable for the initial count value to be + * equal to the maximum count value, indicating that all resources are free. + * + * @param uxMaxCount The maximum count value that can be reached. When the + * semaphore reaches this value it can no longer be 'given'. + * + * @param uxInitialCount The count value assigned to the semaphore when it is + * created. + * + * @return Handle to the created semaphore. Null if the semaphore could not be + * created. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+ xSemaphoreHandle xSemaphore = NULL;
+
+    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
+    // The max value to which the semaphore can count should be 10, and the
+    // initial value assigned to the count should be 0.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting + * \ingroup Semaphores + */ +#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) + +/** + * semphr. h + *
void vSemaphoreDelete( xSemaphoreHandle xSemaphore );
+ * + * Delete a semaphore. This function must be used with care. For example, + * do not delete a mutex type semaphore if the mutex is held by a task. + * + * @param xSemaphore A handle to the semaphore to be deleted. + * + * \page vSemaphoreDelete vSemaphoreDelete + * \ingroup Semaphores + */ +#define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( xQueueHandle ) xSemaphore ) + +#endif /* SEMAPHORE_H */ + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h new file mode 100644 index 000000000..4e69f8c54 --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h @@ -0,0 +1,1323 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef TASK_H +#define TASK_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include task.h" +#endif + +#include "portable.h" +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + +#define tskKERNEL_VERSION_NUMBER "V7.0.1" + +/** + * task. h + * + * Type by which tasks are referenced. For example, a call to xTaskCreate + * returns (via a pointer parameter) an xTaskHandle variable that can then + * be used as a parameter to vTaskDelete to delete the task. + * + * \page xTaskHandle xTaskHandle + * \ingroup Tasks + */ +typedef void * xTaskHandle; + +/* + * Used internally only. + */ +typedef struct xTIME_OUT +{ + portBASE_TYPE xOverflowCount; + portTickType xTimeOnEntering; +} xTimeOutType; + +/* + * Defines the memory ranges allocated to the task when an MPU is used. + */ +typedef struct xMEMORY_REGION +{ + void *pvBaseAddress; + unsigned long ulLengthInBytes; + unsigned long ulParameters; +} xMemoryRegion; + +/* + * Parameters required to create an MPU protected task. + */ +typedef struct xTASK_PARAMTERS +{ + pdTASK_CODE pvTaskCode; + const signed char * const pcName; + unsigned short usStackDepth; + void *pvParameters; + unsigned portBASE_TYPE uxPriority; + portSTACK_TYPE *puxStackBuffer; + xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; +} xTaskParameters; + +/* + * Defines the priority used by the idle task. This must not be modified. + * + * \ingroup TaskUtils + */ +#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0U ) + +/** + * task. h + * + * Macro for forcing a context switch. + * + * \page taskYIELD taskYIELD + * \ingroup SchedulerControl + */ +#define taskYIELD() portYIELD() + +/** + * task. h + * + * Macro to mark the start of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskENTER_CRITICAL taskENTER_CRITICAL + * \ingroup SchedulerControl + */ +#define taskENTER_CRITICAL() portENTER_CRITICAL() + +/** + * task. h + * + * Macro to mark the end of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskEXIT_CRITICAL taskEXIT_CRITICAL + * \ingroup SchedulerControl + */ +#define taskEXIT_CRITICAL() portEXIT_CRITICAL() + +/** + * task. h + * + * Macro to disable all maskable interrupts. + * + * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() + +/** + * task. h + * + * Macro to enable microcontroller interrupts. + * + * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() + +/* Definitions returned by xTaskGetSchedulerState(). */ +#define taskSCHEDULER_NOT_STARTED 0 +#define taskSCHEDULER_RUNNING 1 +#define taskSCHEDULER_SUSPENDED 2 + +/*----------------------------------------------------------- + * TASK CREATION API + *----------------------------------------------------------*/ + +/** + * task. h + *
+ portBASE_TYPE xTaskCreate(
+							  pdTASK_CODE pvTaskCode,
+							  const char * const pcName,
+							  unsigned short usStackDepth,
+							  void *pvParameters,
+							  unsigned portBASE_TYPE uxPriority,
+							  xTaskHandle *pvCreatedTask
+						  );
+ * + * Create a new task and add it to the list of tasks that are ready to run. + * + * xTaskCreate() can only be used to create a task that has unrestricted + * access to the entire microcontroller memory map. Systems that include MPU + * support can alternatively create an MPU constrained task using + * xTaskCreateRestricted(). + * + * @param pvTaskCode Pointer to the task entry function. Tasks + * must be implemented to never return (i.e. continuous loop). + * + * @param pcName A descriptive name for the task. This is mainly used to + * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default + * is 16. + * + * @param usStackDepth The size of the task stack specified as the number of + * variables the stack can hold - not the number of bytes. For example, if + * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes + * will be allocated for stack storage. + * + * @param pvParameters Pointer that will be used as the parameter for the task + * being created. + * + * @param uxPriority The priority at which the task should run. Systems that + * include MPU support can optionally create tasks in a privileged (system) + * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For + * example, to create a privileged task at priority 2 the uxPriority parameter + * should be set to ( 2 | portPRIVILEGE_BIT ). + * + * @param pvCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+ // Task to be created.
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+	 }
+ }
+
+ // Function that creates a task.
+ void vOtherFunction( void )
+ {
+ static unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
+	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
+	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
+	 // the new task attempts to access it.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup xTaskCreate xTaskCreate + * \ingroup Tasks + */ +#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) + +/** + * task. h + *
+ portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
+ * + * xTaskCreateRestricted() should only be used in systems that include an MPU + * implementation. + * + * Create a new task and add it to the list of tasks that are ready to run. + * The function parameters define the memory regions and associated access + * permissions allocated to the task. + * + * @param pxTaskDefinition Pointer to a structure that contains a member + * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API + * documentation) plus an optional stack buffer and the memory region + * definitions. + * + * @param pxCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+// Create an xTaskParameters structure that defines the task to be created.
+static const xTaskParameters xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{											
+		// Base address					Length	Parameters
+        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+};
+
+int main( void )
+{
+xTaskHandle xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// task.
+	for( ;; );
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) + +/** + * task. h + *
+ void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
+ * + * Memory regions are assigned to a restricted task when the task is created by + * a call to xTaskCreateRestricted(). These regions can be redefined using + * vTaskAllocateMPURegions(). + * + * @param xTask The handle of the task being updated. + * + * @param xRegions A pointer to an xMemoryRegion structure that contains the + * new memory region definitions. + * + * Example usage: +
+// Define an array of xMemoryRegion structures that configures an MPU region
+// allowing read/write access for 1024 bytes starting at the beginning of the
+// ucOneKByte array.  The other two of the maximum 3 definable regions are
+// unused so set to zero.
+static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
+{											
+	// Base address		Length		Parameters
+	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
+	{ 0,				0,			0 },
+	{ 0,				0,			0 }
+};
+
+void vATask( void *pvParameters )
+{
+	// This task was created such that it has access to certain regions of
+	// memory as defined by the MPU configuration.  At some point it is
+	// desired that these MPU regions are replaced with that defined in the
+	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
+	// for this purpose.  NULL is used as the task handle to indicate that this
+	// function should modify the MPU regions of the calling task.
+	vTaskAllocateMPURegions( NULL, xAltRegions );
+	
+	// Now the task can continue its function, but from this point on can only
+	// access its stack and the ucOneKByte array (unless any other statically
+	// defined or shared regions have been declared elsewhere).
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelete( xTaskHandle pxTask );
+ * + * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Remove a task from the RTOS real time kernels management. The task being + * deleted will be removed from all ready, blocked, suspended and event lists. + * + * NOTE: The idle task is responsible for freeing the kernel allocated + * memory from tasks that have been deleted. It is therefore important that + * the idle task is not starved of microcontroller processing time if your + * application makes any calls to vTaskDelete (). Memory allocated by the + * task code is not automatically freed, and should be freed before the task + * is deleted. + * + * See the demo application file death.c for sample code that utilises + * vTaskDelete (). + * + * @param pxTask The handle of the task to be deleted. Passing NULL will + * cause the calling task to be deleted. + * + * Example usage: +
+ void vOtherFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup vTaskDelete vTaskDelete + * \ingroup Tasks + */ +void vTaskDelete( xTaskHandle pxTaskToDelete ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK CONTROL API + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskDelay( portTickType xTicksToDelay );
+ * + * Delay a task for a given number of ticks. The actual time that the + * task remains blocked depends on the tick rate. The constant + * portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * + * vTaskDelay() specifies a time at which the task wishes to unblock relative to + * the time at which vTaskDelay() is called. For example, specifying a block + * period of 100 ticks will cause the task to unblock 100 ticks after + * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method + * of controlling the frequency of a cyclical task as the path taken through the + * code, as well as other task and interrupt activity, will effect the frequency + * at which vTaskDelay() gets called and therefore the time at which the task + * next executes. See vTaskDelayUntil() for an alternative API function designed + * to facilitate fixed frequency execution. It does this by specifying an + * absolute time (rather than a relative time) at which the calling task should + * unblock. + * + * @param xTicksToDelay The amount of time, in tick periods, that + * the calling task should block. + * + * Example usage: + + void vTaskFunction( void * pvParameters ) + { + void vTaskFunction( void * pvParameters ) + { + // Block for 500ms. + const portTickType xDelay = 500 / portTICK_RATE_MS; + + for( ;; ) + { + // Simply toggle the LED every 500ms, blocking between each toggle. + vToggleLED(); + vTaskDelay( xDelay ); + } + } + + * \defgroup vTaskDelay vTaskDelay + * \ingroup TaskCtrl + */ +void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
+ * + * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Delay a task until a specified time. This function can be used by cyclical + * tasks to ensure a constant execution frequency. + * + * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will + * cause a task to block for the specified number of ticks from the time vTaskDelay () is + * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed + * execution frequency as the time between a task starting to execute and that task + * calling vTaskDelay () may not be fixed [the task may take a different path though the + * code between calls, or may get interrupted or preempted a different number of times + * each time it executes]. + * + * Whereas vTaskDelay () specifies a wake time relative to the time at which the function + * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to + * unblock. + * + * The constant portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the + * task was last unblocked. The variable must be initialised with the current time + * prior to its first use (see the example below). Following this the variable is + * automatically updated within vTaskDelayUntil (). + * + * @param xTimeIncrement The cycle time period. The task will be unblocked at + * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the + * same xTimeIncrement parameter value will cause the task to execute with + * a fixed interface period. + * + * Example usage: +
+ // Perform an action every 10 ticks.
+ void vTaskFunction( void * pvParameters )
+ {
+ portTickType xLastWakeTime;
+ const portTickType xFrequency = 10;
+
+	 // Initialise the xLastWakeTime variable with the current time.
+	 xLastWakeTime = xTaskGetTickCount ();
+	 for( ;; )
+	 {
+		 // Wait for the next cycle.
+		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
+
+		 // Perform action here.
+	 }
+ }
+   
+ * \defgroup vTaskDelayUntil vTaskDelayUntil + * \ingroup TaskCtrl + */ +void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
+ * + * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Obtain the priority of any task. + * + * @param pxTask Handle of the task to be queried. Passing a NULL + * handle results in the priority of the calling task being returned. + * + * @return The priority of pxTask. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to obtain the priority of the created task.
+	 // It was created with tskIDLE_PRIORITY, but may have changed
+	 // it itself.
+	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
+	 {
+		 // The task has changed it's priority.
+	 }
+
+	 // ...
+
+	 // Is our priority higher than the created task?
+	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
+	 {
+		 // Our priority (obtained using NULL handle) is higher.
+	 }
+ }
+   
+ * \defgroup uxTaskPriorityGet uxTaskPriorityGet + * \ingroup TaskCtrl + */ +unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
+ * + * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Set the priority of any task. + * + * A context switch will occur before the function returns if the priority + * being set is higher than the currently executing task. + * + * @param pxTask Handle to the task for which the priority is being set. + * Passing a NULL handle results in the priority of the calling task being set. + * + * @param uxNewPriority The priority to which the task will be set. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to raise the priority of the created task.
+	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
+
+	 // ...
+
+	 // Use a NULL handle to raise our priority to the same value.
+	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
+ }
+   
+ * \defgroup vTaskPrioritySet vTaskPrioritySet + * \ingroup TaskCtrl + */ +void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Suspend any task. When suspended a task will never get any microcontroller + * processing time, no matter what its priority. + * + * Calls to vTaskSuspend are not accumulative - + * i.e. calling vTaskSuspend () twice on the same task still only requires one + * call to vTaskResume () to ready the suspended task. + * + * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL + * handle will cause the calling task to be suspended. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Suspend ourselves.
+	 vTaskSuspend( NULL );
+
+	 // We cannot get here unless another task calls vTaskResume
+	 // with our handle as the parameter.
+ }
+   
+ * \defgroup vTaskSuspend vTaskSuspend + * \ingroup TaskCtrl + */ +void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskResume( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Resumes a suspended task. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * vTaskResume (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Resume the suspended task ourselves.
+	 vTaskResume( xHandle );
+
+	 // The created task will once again get microcontroller processing
+	 // time in accordance with it priority within the system.
+ }
+   
+ * \defgroup vTaskResume vTaskResume + * \ingroup TaskCtrl + */ +void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * An implementation of vTaskResume() that can be called from within an ISR. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * xTaskResumeFromISR (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * \defgroup vTaskResumeFromISR vTaskResumeFromISR + * \ingroup TaskCtrl + */ +portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * SCHEDULER CONTROL + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskStartScheduler( void );
+ * + * Starts the real time kernel tick processing. After calling the kernel + * has control over which tasks are executed and when. This function + * does not return until an executing task calls vTaskEndScheduler (). + * + * At least one task should be created via a call to xTaskCreate () + * before calling vTaskStartScheduler (). The idle task is created + * automatically when the first application task is created. + * + * See the demo application file main.c for an example of creating + * tasks and starting the kernel. + * + * Example usage: +
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will not get here unless a task calls vTaskEndScheduler ()
+ }
+   
+ * + * \defgroup vTaskStartScheduler vTaskStartScheduler + * \ingroup SchedulerControl + */ +void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskEndScheduler( void );
+ * + * Stops the real time kernel tick. All created tasks will be automatically + * deleted and multitasking (either preemptive or cooperative) will + * stop. Execution then resumes from the point where vTaskStartScheduler () + * was called, as if vTaskStartScheduler () had just returned. + * + * See the demo application file main. c in the demo/PC directory for an + * example that uses vTaskEndScheduler (). + * + * vTaskEndScheduler () requires an exit function to be defined within the + * portable layer (see vPortEndScheduler () in port. c for the PC port). This + * performs hardware specific operations such as stopping the kernel tick. + * + * vTaskEndScheduler () will cause all of the resources allocated by the + * kernel to be freed - but will not free resources allocated by application + * tasks. + * + * Example usage: +
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // At some point we want to end the real time kernel processing
+		 // so call ...
+		 vTaskEndScheduler ();
+	 }
+ }
+
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will only get here when the vTaskCode () task has called
+	 // vTaskEndScheduler ().  When we get here we are back to single task
+	 // execution.
+ }
+   
+ * + * \defgroup vTaskEndScheduler vTaskEndScheduler + * \ingroup SchedulerControl + */ +void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspendAll( void );
+ * + * Suspends all real time kernel activity while keeping interrupts (including the + * kernel tick) enabled. + * + * After calling vTaskSuspendAll () the calling task will continue to execute + * without risk of being swapped out until a call to xTaskResumeAll () has been + * made. + * + * API functions that have the potential to cause a context switch (for example, + * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler + * is suspended. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the kernel
+		 // tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.
+		 xTaskResumeAll ();
+	 }
+ }
+   
+ * \defgroup vTaskSuspendAll vTaskSuspendAll + * \ingroup SchedulerControl + */ +void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
char xTaskResumeAll( void );
+ * + * Resumes real time kernel activity following a call to vTaskSuspendAll (). + * After a call to vTaskSuspendAll () the kernel will take control of which + * task is executing at any time. + * + * @return If resuming the scheduler caused a context switch then pdTRUE is + * returned, otherwise pdFALSE is returned. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the real
+		 // time kernel tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.  We want to force
+		 // a context switch - but there is no point if resuming the scheduler
+		 // caused a context switch already.
+		 if( !xTaskResumeAll () )
+		 {
+			  taskYIELD ();
+		 }
+	 }
+ }
+   
+ * \defgroup xTaskResumeAll xTaskResumeAll + * \ingroup SchedulerControl + */ +signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
+ * + * Utility task that simply returns pdTRUE if the task referenced by xTask is + * currently in the Suspended state, or pdFALSE if the task referenced by xTask + * is in any other state. + * + */ +signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK UTILITIES + *----------------------------------------------------------*/ + +/** + * task. h + *
portTickType xTaskGetTickCount( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * \page xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
portTickType xTaskGetTickCountFromISR( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * This is a version of xTaskGetTickCount() that is safe to be called from an + * ISR - provided that portTickType is the natural word size of the + * microcontroller being used or interrupt nesting is either not supported or + * not being used. + * + * \page xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +portTickType xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned short uxTaskGetNumberOfTasks( void );
+ * + * @return The number of tasks that the real time kernel is currently managing. + * This includes all ready, blocked and suspended tasks. A task that + * has been deleted but not yet freed by the idle task will also be + * included in the count. + * + * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks + * \ingroup TaskUtils + */ +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery );
+ * + * @return The text (human readable) name of the task referenced by the handle + * xTaskToQueury. A task can query its own name by either passing in its own + * handle, or by setting xTaskToQuery to NULL. INCLUDE_pcTaskGetTaskName must be + * set to 1 in FreeRTOSConfig.h for pcTaskGetTaskName() to be available. + * + * \page pcTaskGetTaskName pcTaskGetTaskName + * \ingroup TaskUtils + */ +signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ); + +/** + * task. h + *
void vTaskList( char *pcWriteBuffer );
+ * + * configUSE_TRACE_FACILITY must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Lists all the current tasks, along with their current state and stack + * usage high water mark. + * + * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or + * suspended ('S'). + * + * @param pcWriteBuffer A buffer into which the above mentioned details + * will be written, in ascii form. This buffer is assumed to be large + * enough to contain the generated report. Approximately 40 bytes per + * task should be sufficient. + * + * \page vTaskList vTaskList + * \ingroup TaskUtils + */ +void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
+ * + * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function + * to be available. The application must also then provide definitions + * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and + * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter + * and return the timers current count value respectively. The counter + * should be at least 10 times the frequency of the tick count. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total + * accumulated execution time being stored for each task. The resolution + * of the accumulated time value depends on the frequency of the timer + * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. + * Calling vTaskGetRunTimeStats() writes the total execution time of each + * task into a buffer, both as an absolute count value and as a percentage + * of the total system execution time. + * + * @param pcWriteBuffer A buffer into which the execution times will be + * written, in ascii form. This buffer is assumed to be large enough to + * contain the generated report. Approximately 40 bytes per task should + * be sufficient. + * + * \page vTaskGetRunTimeStats vTaskGetRunTimeStats + * \ingroup TaskUtils + */ +void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskStartTrace( char * pcBuffer, unsigned portBASE_TYPE uxBufferSize );
+ * + * Starts a real time kernel activity trace. The trace logs the identity of + * which task is running when. + * + * The trace file is stored in binary format. A separate DOS utility called + * convtrce.exe is used to convert this into a tab delimited text file which + * can be viewed and plotted in a spread sheet. + * + * @param pcBuffer The buffer into which the trace will be written. + * + * @param ulBufferSize The size of pcBuffer in bytes. The trace will continue + * until either the buffer in full, or ulTaskEndTrace () is called. + * + * \page vTaskStartTrace vTaskStartTrace + * \ingroup TaskUtils + */ +void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned long ulTaskEndTrace( void );
+ * + * Stops a kernel activity trace. See vTaskStartTrace (). + * + * @return The number of bytes that have been written into the trace buffer. + * + * \page usTaskEndTrace usTaskEndTrace + * \ingroup TaskUtils + */ +unsigned long ulTaskEndTrace( void ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
+ * + * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for + * this function to be available. + * + * Returns the high water mark of the stack associated with xTask. That is, + * the minimum free stack space there has been (in words, so on a 32 bit machine + * a value of 1 means 4 bytes) since the task started. The smaller the returned + * number the closer the task has come to overflowing its stack. + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The smallest amount of free stack space there has been (in bytes) + * since the task referenced by xTask was created. + */ +unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask );
+ * + * Returns the run time of selected task + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The run time of selected task + */ +unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ); + +/* When using trace macros it is sometimes necessary to include tasks.h before +FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, +so the following two prototypes will cause a compilation error. This can be +fixed by simply guarding against the inclusion of these two prototypes unless +they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration +constant. */ +#ifdef configUSE_APPLICATION_TASK_TAG + #if configUSE_APPLICATION_TASK_TAG == 1 + /** + * task.h + *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Sets pxHookFunction to be the task hook function used by the task xTask. + * Passing xTask as NULL has the effect of setting the calling tasks hook + * function. + */ + void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; + + /** + * task.h + *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
+ * + * Returns the pxHookFunction value assigned to the task xTask. + */ + pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + #endif /* configUSE_APPLICATION_TASK_TAG ==1 */ +#endif /* ifdef configUSE_APPLICATION_TASK_TAG */ + +/** + * task.h + *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Calls the hook function associated with xTask. Passing xTask as NULL has + * the effect of calling the Running tasks (the calling task) hook function. + * + * pvParameter is passed to the hook function for the task to interpret as it + * wants. + */ +portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; + +/** + * xTaskGetIdleTaskHandle() is only available if + * INCLUDE_xTaskGetIdleTaskHandle is set to 1 in FreeRTOSConfig.h. + * + * Simply returns the handle of the idle task. It is not valid to call + * xTaskGetIdleTaskHandle() before the scheduler has been started. + */ +xTaskHandle xTaskGetIdleTaskHandle( void ); + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + *----------------------------------------------------------*/ + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Called from the real time kernel tick (either preemptive or cooperative), + * this increments the tick count and checks if any tasks that are blocked + * for a finite period required removing from a blocked list and placing on + * a ready list. + */ +void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes the calling task from the ready list and places it both + * on the list of tasks waiting for a particular event, and the + * list of delayed tasks. The task will be removed from both lists + * and replaced on the ready list should either the event occur (and + * there be no higher priority tasks waiting on the same event) or + * the delay period expires. + * + * @param pxEventList The list containing tasks that are blocked waiting + * for the event to occur. + * + * @param xTicksToWait The maximum amount of time that the task should wait + * for the event to occur. This is specified in kernel ticks,the constant + * portTICK_RATE_MS can be used to convert kernel ticks into a real time + * period. + */ +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * This function performs nearly the same function as vTaskPlaceOnEventList(). + * The difference being that this function does not permit tasks to block + * indefinitely, whereas vTaskPlaceOnEventList() does. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes a task from both the specified event list and the list of blocked + * tasks, and places it on a ready queue. + * + * xTaskRemoveFromEventList () will be called if either an event occurs to + * unblock a task, or the block timeout period expires. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Sets the pointer to the current TCB to the TCB of the highest priority task + * that is ready to run. + */ +void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; + +/* + * Return the handle of the calling task. + */ +xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; + +/* + * Capture the current time status for future reference. + */ +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; + +/* + * Compare the time status now with that previously captured to see if the + * timeout has expired. + */ +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * Shortcut used by the queue implementation to prevent unnecessary call to + * taskYIELD(); + */ +void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; + +/* + * Returns the scheduler state as taskSCHEDULER_RUNNING, + * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. + */ +portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; + +/* + * Raises the priority of the mutex holder to that of the calling task should + * the mutex holder have a priority less than the calling task. + */ +void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Set the priority of a task back to its proper priority in the case that it + * inherited a higher priority while it was holding a semaphore. + */ +void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Generic version of the task creation function which is in turn called by the + * xTaskCreate() and xTaskCreateRestricted() macros. + */ +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; + +#ifdef __cplusplus +} +#endif +#endif /* TASK_H */ + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h new file mode 100644 index 000000000..606439e0d --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h @@ -0,0 +1,940 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef TIMERS_H +#define TIMERS_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include timers.h" +#endif + +#include "portable.h" +#include "list.h" +#include "task.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* IDs for commands that can be sent/received on the timer queue. These are to +be used solely through the macros that make up the public software timer API, +as defined below. */ +#define tmrCOMMAND_START 0 +#define tmrCOMMAND_STOP 1 +#define tmrCOMMAND_CHANGE_PERIOD 2 +#define tmrCOMMAND_DELETE 3 + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + + /** + * Type by which software timers are referenced. For example, a call to + * xTimerCreate() returns an xTimerHandle variable that can then be used to + * reference the subject timer in calls to other software timer API functions + * (for example, xTimerStart(), xTimerReset(), etc.). + */ +typedef void * xTimerHandle; + +/* Define the prototype to which timer callback functions must conform. */ +typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); + +/** + * xTimerHandle xTimerCreate( const signed char *pcTimerName, + * portTickType xTimerPeriod, + * unsigned portBASE_TYPE uxAutoReload, + * void * pvTimerID, + * tmrTIMER_CALLBACK pxCallbackFunction ); + * + * Creates a new software timer instance. This allocates the storage required + * by the new timer, initialises the new timers internal state, and returns a + * handle by which the new timer can be referenced. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the + * active state. + * + * @param pcTimerName A text name that is assigned to the timer. This is done + * purely to assist debugging. The kernel itself only ever references a timer by + * its handle, and never by its name. + * + * @param xTimerPeriod The timer period. The time is defined in tick periods so + * the constant portTICK_RATE_MS can be used to convert a time that has been + * specified in milliseconds. For example, if the timer must expire after 100 + * ticks, then xTimerPeriod should be set to 100. Alternatively, if the timer + * must expire after 500ms, then xPeriod can be set to ( 500 / portTICK_RATE_MS ) + * provided configTICK_RATE_HZ is less than or equal to 1000. + * + * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will + * expire repeatedly with a frequency set by the xTimerPeriod parameter. If + * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and + * enter the dormant state after it expires. + * + * @param pvTimerID An identifier that is assigned to the timer being created. + * Typically this would be used in the timer callback function to identify which + * timer expired when the same callback function is assigned to more than one + * timer. + * + * @param pxCallbackFunction The function to call when the timer expires. + * Callback functions must have the prototype defined by tmrTIMER_CALLBACK, + * which is "void vCallbackFunction( xTimerHandle xTimer );". + * + * @return If the timer is successfully create then a handle to the newly + * created timer is returned. If the timer cannot be created (because either + * there is insufficient FreeRTOS heap remaining to allocate the timer + * structures, or the timer period was set to 0) then 0 is returned. + * + * Example usage: + * + * + * #define NUM_TIMERS 5 + * + * // An array to hold handles to the created timers. + * xTimerHandle xTimers[ NUM_TIMERS ]; + * + * // An array to hold a count of the number of times each timer expires. + * long lExpireCounters[ NUM_TIMERS ] = { 0 }; + * + * // Define a callback function that will be used by multiple timer instances. + * // The callback function does nothing but count the number of times the + * // associated timer expires, and stop the timer once the timer has expired + * // 10 times. + * void vTimerCallback( xTimerHandle pxTimer ) + * { + * long lArrayIndex; + * const long xMaxExpiryCountBeforeStopping = 10; + * + * // Optionally do something if the pxTimer parameter is NULL. + * configASSERT( pxTimer ); + * + * // Which timer expired? + * lArrayIndex = ( long ) pvTimerGetTimerID( pxTimer ); + * + * // Increment the number of times that pxTimer has expired. + * lExpireCounters[ lArrayIndex ] += 1; + * + * // If the timer has expired 10 times then stop it from running. + * if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping ) + * { + * // Do not use a block time if calling a timer API function from a + * // timer callback function, as doing so could cause a deadlock! + * xTimerStop( pxTimer, 0 ); + * } + * } + * + * void main( void ) + * { + * long x; + * + * // Create then start some timers. Starting the timers before the scheduler + * // has been started means the timers will start running immediately that + * // the scheduler starts. + * for( x = 0; x < NUM_TIMERS; x++ ) + * { + * xTimers[ x ] = xTimerCreate( "Timer", // Just a text name, not used by the kernel. + * ( 100 * x ), // The timer period in ticks. + * pdTRUE, // The timers will auto-reload themselves when they expire. + * ( void * ) x, // Assign each timer a unique id equal to its array index. + * vTimerCallback // Each timer calls the same callback when it expires. + * ); + * + * if( xTimers[ x ] == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xTimers[ x ], 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timers running as they have already + * // been set into the active state. + * xTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + */ +xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void * pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) PRIVILEGED_FUNCTION; + +/** + * void *pvTimerGetTimerID( xTimerHandle xTimer ); + * + * Returns the ID assigned to the timer. + * + * IDs are assigned to timers using the pvTimerID parameter of the call to + * xTimerCreated() that was used to create the timer. + * + * If the same callback function is assigned to multiple timers then the timer + * ID can be used within the callback function to identify which timer actually + * expired. + * + * @param xTimer The timer being queried. + * + * @return The ID assigned to the timer being queried. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + */ +void *pvTimerGetTimerID( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; + +/** + * portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ); + * + * Queries a timer to see if it is active or dormant. + * + * A timer will be dormant if: + * 1) It has been created but not started, or + * 2) It is an expired on-shot timer that has not been restarted. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the + * active state. + * + * @param xTimer The timer being queried. + * + * @return pdFALSE will be returned if the timer is dormant. A value other than + * pdFALSE will be returned if the timer is active. + * + * Example usage: + * + * // This function assumes xTimer has already been created. + * void vAFunction( xTimerHandle xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is active, do something. + * } + * else + * { + * // xTimer is not active, do something else. + * } + * } + */ +portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; + +/** + * xTimerGetTimerDaemonTaskHandle() is only available if + * INCLUDE_xTimerGetTimerDaemonTaskHandle is set to 1 in FreeRTOSConfig.h. + * + * Simply returns the handle of the timer service/daemon task. It it not valid + * to call xTimerGetTimerDaemonTaskHandle() before the scheduler has been started. + */ +xTaskHandle xTimerGetTimerDaemonTaskHandle( void ); + +/** + * portBASE_TYPE xTimerStart( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStart() starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerStart() has equivalent functionality + * to the xTimerReset() API function. + * + * Starting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerStart() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerStart() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerStart() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart() + * to be available. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the start command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStart() was called. xBlockTime is ignored if xTimerStart() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStart( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerStop( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStop() stops a timer that was previously started using either of the + * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(), + * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions. + * + * Stopping a timer ensures the timer is not in the active state. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop() + * to be available. + * + * @param xTimer The handle of the timer being stopped. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the stop command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStop() was called. xBlockTime is ignored if xTimerStop() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStop( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerChangePeriod( xTimerHandle xTimer, + * portTickType xNewPeriod, + * portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerChangePeriod() changes the period of a timer that was previously + * created using the xTimerCreate() API function. + * + * xTimerChangePeriod() can be called to change the period of an active or + * dormant state timer. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerChangePeriod() to be available. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_RATE_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the change period command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerChangePeriod() was called. xBlockTime is ignored if + * xTimerChangePeriod() is called before the scheduler is started. + * + * @return pdFAIL will be returned if the change period command could not be + * sent to the timer command queue even after xBlockTime ticks had passed. + * pdPASS will be returned if the command was successfully sent to the timer + * command queue. When the command is actually processed will depend on the + * priority of the timer service/daemon task relative to other tasks in the + * system. The timer service/daemon task priority is set by the + * configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This function assumes xTimer has already been created. If the timer + * // referenced by xTimer is already active when it is called, then the timer + * // is deleted. If the timer referenced by xTimer is not active when it is + * // called, then the period of the timer is set to 500ms and the timer is + * // started. + * void vAFunction( xTimerHandle xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is already active - delete it. + * xTimerDelete( xTimer ); + * } + * else + * { + * // xTimer is not active, change its period to 500ms. This will also + * // cause the timer to start. Block for a maximum of 100 ticks if the + * // change period command cannot immediately be sent to the timer + * // command queue. + * if( xTimerChangePeriod( xTimer, 500 / portTICK_RATE_MS, 100 ) == pdPASS ) + * { + * // The command was successfully sent. + * } + * else + * { + * // The command could not be sent, even after waiting for 100 ticks + * // to pass. Take appropriate action here. + * } + * } + * } + */ + #define xTimerChangePeriod( xTimer, xNewPeriod, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerDelete( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerDelete() deletes a timer that was previously created using the + * xTimerCreate() API function. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerDelete() to be available. + * + * @param xTimer The handle of the timer being deleted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the delete command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerDelete() was called. xBlockTime is ignored if xTimerDelete() + * is called before the scheduler is started. + * + * @return pdFAIL will be returned if the delete command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerChangePeriod() API function example usage scenario. + */ +#define xTimerDelete( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerReset( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerReset() re-starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerReset() will cause the timer to + * re-evaluate its expiry time so that it is relative to when xTimerReset() was + * called. If the timer was in the dormant state then xTimerReset() has + * equivalent functionality to the xTimerStart() API function. + * + * Resetting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerReset() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerReset() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerReset() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset() + * to be available. + * + * @param xTimer The handle of the timer being reset/started/restarted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the reset command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerReset() was called. xBlockTime is ignored if xTimerReset() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * // When a key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer. + * + * xTimerHandle xBacklightTimer = NULL; + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTimerHandle pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press event handler. + * void vKeyPressEventHandler( char cKey ) + * { + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. Wait 10 ticks for the command to be successfully sent + * // if it cannot be sent immediately. + * vSetBacklightState( BACKLIGHT_ON ); + * if( xTimerReset( xBacklightTimer, 100 ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * } + * + * void main( void ) + * { + * long x; + * + * // Create then start the one-shot timer that is responsible for turning + * // the back-light off if no keys are pressed within a 5 second period. + * xBacklightTimer = xTimerCreate( "BacklightTimer", // Just a text name, not used by the kernel. + * ( 5000 / portTICK_RATE_MS), // The timer period in ticks. + * pdFALSE, // The timer is a one-shot timer. + * 0, // The id is not used by the callback so can take any value. + * vBacklightTimerCallback // The callback function that switches the LCD back-light off. + * ); + * + * if( xBacklightTimer == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xBacklightTimer, 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timer running as it has already + * // been set into the active state. + * xTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + */ +#define xTimerReset( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerStartFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStart() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStartFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStartFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStartFromISR() function. If + * xTimerStartFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerStartFromISR() is actually called. The timer service/daemon + * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTimerHandle pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then restart the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The start command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerStopFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStop() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being stopped. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStopFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStopFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStopFromISR() function. If + * xTimerStopFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the timer should be simply stopped. + * + * // The interrupt service routine that stops the timer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - simply stop the timer. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The stop command was not executed successfully. Take appropriate + * // action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0, ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerChangePeriodFromISR( xTimerHandle xTimer, + * portTickType xNewPeriod, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerChangePeriod() that can be called from an interrupt + * service routine. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_RATE_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerChangePeriodFromISR() writes a message to the + * timer command queue, so has the potential to transition the timer service/ + * daemon task out of the Blocked state. If calling xTimerChangePeriodFromISR() + * causes the timer service/daemon task to leave the Blocked state, and the + * timer service/daemon task has a priority equal to or greater than the + * currently executing task (the task that was interrupted), then + * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the + * xTimerChangePeriodFromISR() function. If xTimerChangePeriodFromISR() sets + * this value to pdTRUE then a context switch should be performed before the + * interrupt exits. + * + * @return pdFAIL will be returned if the command to change the timers period + * could not be sent to the timer command queue. pdPASS will be returned if the + * command was successfully sent to the timer command queue. When the command + * is actually processed will depend on the priority of the timer service/daemon + * task relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the period of xTimer should be changed to 500ms. + * + * // The interrupt service routine that changes the period of xTimer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - change the period of xTimer to 500ms. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The command to change the timers period was not executed + * // successfully. Take appropriate action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerResetFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerReset() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer that is to be started, reset, or + * restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerResetFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerResetFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerResetFromISR() function. If + * xTimerResetFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerResetFromISR() is actually called. The timer service/daemon + * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTimerHandle pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + +/* + * Functions beyond this part are not part of the public API and are intended + * for use by the kernel only. + */ +portBASE_TYPE xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; +portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) PRIVILEGED_FUNCTION; + +#ifdef __cplusplus +} +#endif +#endif /* TIMERS_H */ + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c new file mode 100644 index 000000000..ab9699602 --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c @@ -0,0 +1,191 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#include +#include "FreeRTOS.h" +#include "list.h" + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +void vListInitialise( xList *pxList ) +{ + /* The list structure contains a list item which is used to mark the + end of the list. To initialise the list the list end is inserted + as the only list entry. */ + pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); + + /* The list end value is the highest possible value in the list to + ensure it remains at the end of the list. */ + pxList->xListEnd.xItemValue = portMAX_DELAY; + + /* The list end next and previous pointers point to itself so we know + when the list is empty. */ + pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); + pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); + + pxList->uxNumberOfItems = ( unsigned portBASE_TYPE ) 0U; +} +/*-----------------------------------------------------------*/ + +void vListInitialiseItem( xListItem *pxItem ) +{ + /* Make sure the list item is not recorded as being on a list. */ + pxItem->pvContainer = NULL; +} +/*-----------------------------------------------------------*/ + +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) +{ +volatile xListItem * pxIndex; + + /* Insert a new list item into pxList, but rather than sort the list, + makes the new list item the last item to be removed by a call to + pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by + the pxIndex member. */ + pxIndex = pxList->pxIndex; + + pxNewListItem->pxNext = pxIndex->pxNext; + pxNewListItem->pxPrevious = pxList->pxIndex; + pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; + pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListInsert( xList *pxList, xListItem *pxNewListItem ) +{ +volatile xListItem *pxIterator; +portTickType xValueOfInsertion; + + /* Insert the new list item into the list, sorted in ulListItem order. */ + xValueOfInsertion = pxNewListItem->xItemValue; + + /* If the list already contains a list item with the same item value then + the new list item should be placed after it. This ensures that TCB's which + are stored in ready lists (all of which have the same ulListItem value) + get an equal share of the CPU. However, if the xItemValue is the same as + the back marker the iteration loop below will not end. This means we need + to guard against this by checking the value first and modifying the + algorithm slightly if necessary. */ + if( xValueOfInsertion == portMAX_DELAY ) + { + pxIterator = pxList->xListEnd.pxPrevious; + } + else + { + /* *** NOTE *********************************************************** + If you find your application is crashing here then likely causes are: + 1) Stack overflow - + see http://www.freertos.org/Stacks-and-stack-overflow-checking.html + 2) Incorrect interrupt priority assignment, especially on Cortex-M3 + parts where numerically high priority values denote low actual + interrupt priories, which can seem counter intuitive. See + configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html + 3) Calling an API function from within a critical section or when + the scheduler is suspended. + 4) Using a queue or semaphore before it has been initialised or + before the scheduler has been started (are interrupts firing + before vTaskStartScheduler() has been called?). + See http://www.freertos.org/FAQHelp.html for more tips. + **********************************************************************/ + + for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) + { + /* There is nothing to do here, we are just iterating to the + wanted insertion position. */ + } + } + + pxNewListItem->pxNext = pxIterator->pxNext; + pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxNewListItem->pxPrevious = pxIterator; + pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. This allows fast removal of the + item later. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListRemove( xListItem *pxItemToRemove ) +{ +xList * pxList; + + pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; + pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; + + /* The list item knows which list it is in. Obtain the list from the list + item. */ + pxList = ( xList * ) pxItemToRemove->pvContainer; + + /* Make sure the index is left pointing to a valid item. */ + if( pxList->pxIndex == pxItemToRemove ) + { + pxList->pxIndex = pxItemToRemove->pxPrevious; + } + + pxItemToRemove->pvContainer = NULL; + ( pxList->uxNumberOfItems )--; +} +/*-----------------------------------------------------------*/ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c new file mode 100644 index 000000000..4e8976db9 --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c @@ -0,0 +1,1536 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#if ( configUSE_CO_ROUTINES == 1 ) + #include "croutine.h" +#endif + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +/* Constants used with the cRxLock and cTxLock structure members. */ +#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) +#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) + +#define queueERRONEOUS_UNBLOCK ( -1 ) + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + +/* Effectively make a union out of the xQUEUE structure. */ +#define pxMutexHolder pcTail +#define uxQueueType pcHead +#define uxRecursiveCallCount pcReadFrom +#define queueQUEUE_IS_MUTEX NULL + +/* Semaphores do not actually store or copy data, so have an items size of +zero. */ +#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned portBASE_TYPE ) 0 ) +#define queueDONT_BLOCK ( ( portTickType ) 0U ) +#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0U ) + +/* + * Definition of the queue used by the scheduler. + * Items are queued by copy, not reference. + */ +typedef struct QueueDefinition +{ + signed char *pcHead; /*< Points to the beginning of the queue storage area. */ + signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ + + signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ + signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ + + xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ + xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ + + volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ + unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ + unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ + + signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + +} xQUEUE; +/*-----------------------------------------------------------*/ + +/* + * Inside this file xQueueHandle is a pointer to a xQUEUE structure. + * To keep the definition private the API header file defines it as a + * pointer to void. + */ +typedef xQUEUE * xQueueHandle; + +/* + * Prototypes for public functions are included here so we don't have to + * include the API header file (as it defines xQueueHandle differently). These + * functions are documented in the API header file. + */ +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateMutex( void ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * Co-routine queue functions differ from task queue functions. Co-routines are + * an optional component. + */ +#if configUSE_CO_ROUTINES == 1 + signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; +#endif + +/* + * The queue registry is just a means for kernel aware debuggers to locate + * queue structures. It has no other purpose so is an optional component. + */ +#if configQUEUE_REGISTRY_SIZE > 0 + + /* The type stored within the queue registry array. This allows a name + to be assigned to each queue making kernel aware debugging a little + more user friendly. */ + typedef struct QUEUE_REGISTRY_ITEM + { + signed char *pcQueueName; + xQueueHandle xHandle; + } xQueueRegistryItem; + + /* The queue registry is simply an array of xQueueRegistryItem structures. + The pcQueueName member of a structure being NULL is indicative of the + array position being vacant. */ + xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; + + /* Removes a queue from the registry by simply setting the pcQueueName + member to NULL. */ + static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; +#endif + +/* + * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not + * prevent an ISR from adding or removing items to the queue, but does prevent + * an ISR from removing tasks from the queue event lists. If an ISR finds a + * queue is locked it will instead increment the appropriate queue lock count + * to indicate that a task may require unblocking. When the queue in unlocked + * these lock counts are inspected, and the appropriate action taken. + */ +static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any data in a queue. + * + * @return pdTRUE if the queue contains no items, otherwise pdFALSE. + */ +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any space in a queue. + * + * @return pdTRUE if there is no space, otherwise pdFALSE; + */ +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Copies an item into the queue, either at the front of the queue or the + * back of the queue. + */ +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; + +/* + * Copies an item out of a queue. + */ +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; +/*-----------------------------------------------------------*/ + +/* + * Macro to mark a queue as locked. Locking a queue prevents an ISR from + * accessing the queue event lists. + */ +#define prvLockQueue( pxQueue ) \ + taskENTER_CRITICAL(); \ + { \ + if( ( pxQueue )->xRxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->xRxLock = queueLOCKED_UNMODIFIED; \ + } \ + if( ( pxQueue )->xTxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->xTxLock = queueLOCKED_UNMODIFIED; \ + } \ + } \ + taskEXIT_CRITICAL() +/*-----------------------------------------------------------*/ + + +/*----------------------------------------------------------- + * PUBLIC QUEUE MANAGEMENT API documented in queue.h + *----------------------------------------------------------*/ + +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) +{ +xQUEUE *pxNewQueue; +size_t xQueueSizeInBytes; +xQueueHandle xReturn = NULL; + + /* Allocate the new queue structure. */ + if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) + { + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Create the list of pointers to queue items. The queue is one byte + longer than asked for to make wrap checking easier/faster. */ + xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; + + pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); + if( pxNewQueue->pcHead != NULL ) + { + /* Initialise the queue members as described above where the + queue type is defined. */ + pxNewQueue->pcTail = pxNewQueue->pcHead + ( uxQueueLength * uxItemSize ); + pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; + pxNewQueue->pcWriteTo = pxNewQueue->pcHead; + pxNewQueue->pcReadFrom = pxNewQueue->pcHead + ( ( uxQueueLength - ( unsigned portBASE_TYPE ) 1U ) * uxItemSize ); + pxNewQueue->uxLength = uxQueueLength; + pxNewQueue->uxItemSize = uxItemSize; + pxNewQueue->xRxLock = queueUNLOCKED; + pxNewQueue->xTxLock = queueUNLOCKED; + + /* Likewise ensure the event queues start with the correct state. */ + vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + + traceQUEUE_CREATE( pxNewQueue ); + xReturn = pxNewQueue; + } + else + { + traceQUEUE_CREATE_FAILED(); + vPortFree( pxNewQueue ); + } + } + } + + configASSERT( xReturn ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + xQueueHandle xQueueCreateMutex( void ) + { + xQUEUE *pxNewQueue; + + /* Allocate the new queue structure. */ + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Information required for priority inheritance. */ + pxNewQueue->pxMutexHolder = NULL; + pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; + + /* Queues used as a mutex no data is actually copied into or out + of the queue. */ + pxNewQueue->pcWriteTo = NULL; + pxNewQueue->pcReadFrom = NULL; + + /* Each mutex has a length of 1 (like a binary semaphore) and + an item size of 0 as nothing is actually copied into or out + of the mutex. */ + pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; + pxNewQueue->uxLength = ( unsigned portBASE_TYPE ) 1U; + pxNewQueue->uxItemSize = ( unsigned portBASE_TYPE ) 0U; + pxNewQueue->xRxLock = queueUNLOCKED; + pxNewQueue->xTxLock = queueUNLOCKED; + + /* Ensure the event queues start with the correct state. */ + vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + + /* Start with the semaphore in the expected state. */ + xQueueGenericSend( pxNewQueue, NULL, ( portTickType ) 0U, queueSEND_TO_BACK ); + + traceCREATE_MUTEX( pxNewQueue ); + } + else + { + traceCREATE_MUTEX_FAILED(); + } + + configASSERT( pxNewQueue ); + return pxNewQueue; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_RECURSIVE_MUTEXES == 1 + + portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) + { + portBASE_TYPE xReturn; + + configASSERT( pxMutex ); + + /* If this is the task that holds the mutex then pxMutexHolder will not + change outside of this task. If this task does not hold the mutex then + pxMutexHolder can never coincidentally equal the tasks handle, and as + this is the only condition we are interested in it does not matter if + pxMutexHolder is accessed simultaneously by another task. Therefore no + mutual exclusion is required to test the pxMutexHolder variable. */ + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + traceGIVE_MUTEX_RECURSIVE( pxMutex ); + + /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to + the task handle, therefore no underflow check is required. Also, + uxRecursiveCallCount is only modified by the mutex holder, and as + there can only be one, no mutual exclusion is required to modify the + uxRecursiveCallCount member. */ + ( pxMutex->uxRecursiveCallCount )--; + + /* Have we unwound the call count? */ + if( pxMutex->uxRecursiveCallCount == 0 ) + { + /* Return the mutex. This will automatically unblock any other + task that might be waiting to access the mutex. */ + xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); + } + + xReturn = pdPASS; + } + else + { + /* We cannot give the mutex because we are not the holder. */ + xReturn = pdFAIL; + + traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_RECURSIVE_MUTEXES == 1 + + portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) + { + portBASE_TYPE xReturn; + + configASSERT( pxMutex ); + + /* Comments regarding mutual exclusion as per those within + xQueueGiveMutexRecursive(). */ + + traceTAKE_MUTEX_RECURSIVE( pxMutex ); + + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + ( pxMutex->uxRecursiveCallCount )++; + xReturn = pdPASS; + } + else + { + xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); + + /* pdPASS will only be returned if we successfully obtained the mutex, + we may have blocked to reach here. */ + if( xReturn == pdPASS ) + { + ( pxMutex->uxRecursiveCallCount )++; + } + else + { + traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_COUNTING_SEMAPHORES == 1 + + xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) + { + xQueueHandle pxHandle; + + pxHandle = xQueueCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH ); + + if( pxHandle != NULL ) + { + pxHandle->uxMessagesWaiting = uxInitialCount; + + traceCREATE_COUNTING_SEMAPHORE(); + } + else + { + traceCREATE_COUNTING_SEMAPHORE_FAILED(); + } + + configASSERT( pxHandle ); + return pxHandle; + } + +#endif /* configUSE_COUNTING_SEMAPHORES */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. Yes it is ok to do + this from within the critical section - the kernel + takes care of that. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting the + function. */ + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was full and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting + the function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was full and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + + /* Unlocking the queue means queue events can effect the + event list. It is possible that interrupts occurring now + remove this task from the event list again - but as the + scheduler is suspended the task will go onto the pending + ready last instead of the actual ready list. */ + prvUnlockQueue( pxQueue ); + + /* Resuming the scheduler will move tasks from the pending + ready list into the ready list - so it is feasible that this + task is already in a ready list before it yields - in which + case the yield will not cause a context switch unless there + is also a higher priority task in the pending ready list. */ + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* The timeout has expired. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + /* Return to the original privilege level before exiting the + function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } +} +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } + taskEXIT_CRITICAL(); + } + } + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + signed char *pcOriginalReadPosition; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + for( ;; ) + { + taskENTER_CRITICAL(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } + taskEXIT_CRITICAL(); + } + } + + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + configASSERT( pxQueue ); + configASSERT( pxHigherPriorityTaskWoken ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* Similar to xQueueGenericSend, except we don't block if there is no room + in the queue. Also we don't directly wake a task that was blocked on a + queue read, instead we return a flag to say whether a context switch is + required or not (i.e. has a task with a higher priority than us been woken + by this post). */ + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND_FROM_ISR( pxQueue ); + + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If the queue is locked we do not alter the event list. This will + be done when the queue is unlocked later. */ + if( pxQueue->xTxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + *pxHigherPriorityTaskWoken = pdTRUE; + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was posted while it was locked. */ + ++( pxQueue->xTxLock ); + } + + xReturn = pdPASS; + } + else + { + traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); + xReturn = errQUEUE_FULL; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; +signed char *pcOriginalReadPosition; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there data in the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was empty and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was empty and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + { + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + } + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + configASSERT( pxQueue ); + configASSERT( pxTaskWoken ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* We cannot block from an ISR, so check there is data available. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + --( pxQueue->uxMessagesWaiting ); + + /* If the queue is locked we will not modify the event list. Instead + we update the lock count so the task that unlocks the queue will know + that an ISR has removed data while the queue was locked. */ + if( pxQueue->xRxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than us so + force a context switch. */ + *pxTaskWoken = pdTRUE; + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was removed while it was locked. */ + ++( pxQueue->xRxLock ); + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + uxReturn = pxQueue->uxMessagesWaiting; + taskEXIT_CRITICAL(); + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + configASSERT( pxQueue ); + + uxReturn = pxQueue->uxMessagesWaiting; + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +void vQueueDelete( xQueueHandle pxQueue ) +{ + configASSERT( pxQueue ); + + traceQUEUE_DELETE( pxQueue ); + vQueueUnregisterQueue( pxQueue ); + vPortFree( pxQueue->pcHead ); + vPortFree( pxQueue ); +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) +{ + if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) + { + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* The mutex is no longer being held. */ + vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); + pxQueue->pxMutexHolder = NULL; + } + } + #endif + } + else if( xPosition == queueSEND_TO_BACK ) + { + memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcWriteTo += pxQueue->uxItemSize; + if( pxQueue->pcWriteTo >= pxQueue->pcTail ) + { + pxQueue->pcWriteTo = pxQueue->pcHead; + } + } + else + { + memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcReadFrom -= pxQueue->uxItemSize; + if( pxQueue->pcReadFrom < pxQueue->pcHead ) + { + pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); + } + } + + ++( pxQueue->uxMessagesWaiting ); +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) +{ + if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) + { + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + } +} +/*-----------------------------------------------------------*/ + +static void prvUnlockQueue( xQueueHandle pxQueue ) +{ + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ + + /* The lock counts contains the number of extra data items placed or + removed from the queue while the queue was locked. When a queue is + locked items can be added or removed, but the event lists cannot be + updated. */ + taskENTER_CRITICAL(); + { + /* See if data was added to the queue while it was locked. */ + while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) + { + /* Data was posted while the queue was locked. Are any tasks + blocked waiting for data to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + vTaskMissedYield(); + } + + --( pxQueue->xTxLock ); + } + else + { + break; + } + } + + pxQueue->xTxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); + + /* Do the same for the Rx lock. */ + taskENTER_CRITICAL(); + { + while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + vTaskMissedYield(); + } + + --( pxQueue->xRxLock ); + } + else + { + break; + } + } + + pxQueue->xRxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + configASSERT( pxQueue ); + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + configASSERT( pxQueue ); + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already full we may have to block. A critical section + is required to prevent an interrupt removing something from the queue + between the check to see if the queue is full and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + /* The queue is full - do we want to block or just leave without + posting? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is called from a coroutine we cannot block directly, but + return indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + /* There is room in the queue, copy the data into the queue. */ + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + xReturn = pdPASS; + + /* Were any co-routines waiting for data to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The co-routine waiting has a higher priority so record + that a yield might be appropriate. */ + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = errQUEUE_FULL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already empty we may have to block. A critical section + is required to prevent an interrupt adding something to the queue + between the check to see if the queue is empty and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) + { + /* There are no messages in the queue, do we want to block or just + leave with nothing? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is a co-routine we cannot block directly, but return + indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Data is available from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + xReturn = pdPASS; + + /* Were any co-routines waiting for space to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = pdFAIL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + + + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) +{ + /* Cannot block within an ISR so if there is no space on the queue then + exit without doing anything. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + + /* We only want to wake one co-routine per ISR, so check that a + co-routine has not already been woken. */ + if( xCoRoutinePreviouslyWoken == pdFALSE ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + return pdTRUE; + } + } + } + } + + return xCoRoutinePreviouslyWoken; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) +{ +signed portBASE_TYPE xReturn; + + /* We cannot block from an ISR, so check there is data available. If + not then just leave without doing anything. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Copy the data from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + if( ( *pxCoRoutineWoken ) == pdFALSE ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + *pxCoRoutineWoken = pdTRUE; + } + } + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) + { + unsigned portBASE_TYPE ux; + + /* See if there is an empty space in the registry. A NULL name denotes + a free slot. */ + for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].pcQueueName == NULL ) + { + /* Store the information on this queue. */ + xQueueRegistry[ ux ].pcQueueName = pcQueueName; + xQueueRegistry[ ux ].xHandle = xQueue; + break; + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + static void vQueueUnregisterQueue( xQueueHandle xQueue ) + { + unsigned portBASE_TYPE ux; + + /* See if the handle of the queue being unregistered in actually in the + registry. */ + for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].xHandle == xQueue ) + { + /* Set the name to NULL to show that this slot if free again. */ + xQueueRegistry[ ux ].pcQueueName = NULL; + break; + } + } + + } + +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_TIMERS == 1 + + void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) + { + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements. + It can result in vListInsert() being called on a list that can only + possibly ever have one item in it, so the list will be fast, but even + so it should be called with the scheduler locked and not from a critical + section. */ + + /* Only do anything if there are no messages in the queue. This function + will not actually cause the task to block, just place it on a blocked + list. It will not block until the scheduler is unlocked - at which + time a yield will be performed. If an item is added to the queue while + the queue is locked, and the calling task blocks on the queue, then the + calling task will be immediately unblocked when the queue is unlocked. */ + prvLockQueue( pxQueue ); + if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0U ) + { + /* There is nothing in the queue, block for the specified period. */ + vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + } + prvUnlockQueue( pxQueue ); + } + +#endif + diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/tasks.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c similarity index 73% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/tasks.c rename to flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c index 20f9ab309..89ab31af4 100644 --- a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/peabody124/tasks.c +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c @@ -1,2332 +1,2521 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#include -#include -#include -#include -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "StackMacros.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* - * Macro to define the amount of stack available to the idle task. - */ -#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE - -/* - * Task control block. A task control block (TCB) is allocated to each task, - * and stores the context of the task. - */ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - - #if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ - #endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - - #if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ - #endif - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; - #endif - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ - #endif - - #if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ - #endif - -} tskTCB; - - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - -/*lint -e956 */ -PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; - -/* Lists for ready and blocked tasks. --------------------*/ - -PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ -PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ - -#if ( INCLUDE_vTaskDelete == 1 ) - - PRIVILEGED_DATA static volatile xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ - PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0; - -#endif - -#if ( INCLUDE_vTaskSuspend == 1 ) - - PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ - -#endif - -/* File private variables. --------------------------------*/ -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0; - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - PRIVILEGED_DATA static char pcStatsString[ 50 ] ; - PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; - -#endif - -/* Debugging and trace facilities private variables and macros. ------------*/ - -/* - * The value used to fill the stack of a task when the task is created. This - * is used purely for checking the high water mark for tasks. - */ -#define tskSTACK_FILL_BYTE ( 0xa5 ) - -/* - * Macros used by vListTask to indicate which state a task is in. - */ -#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) -#define tskREADY_CHAR ( ( signed char ) 'R' ) -#define tskDELETED_CHAR ( ( signed char ) 'D' ) -#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) - -/* - * Macros and private variables used by the trace facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define tskSIZE_OF_EACH_TRACE_LINE ( ( unsigned long ) ( sizeof( unsigned long ) + sizeof( unsigned long ) ) ) - PRIVILEGED_DATA static volatile signed char * volatile pcTraceBuffer; - PRIVILEGED_DATA static signed char *pcTraceBufferStart; - PRIVILEGED_DATA static signed char *pcTraceBufferEnd; - PRIVILEGED_DATA static signed portBASE_TYPE xTracing = pdFALSE; - static unsigned portBASE_TYPE uxPreviousTask = 255; - PRIVILEGED_DATA static char pcStatusString[ 50 ]; - -#endif - -/*-----------------------------------------------------------*/ - -/* - * Macro that writes a trace of scheduler activity to a buffer. This trace - * shows which task is running when and is very useful as a debugging tool. - * As this macro is called each context switch it is a good idea to undefine - * it if not using the facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define vWriteTraceToBuffer() \ - { \ - if( xTracing ) \ - { \ - if( uxPreviousTask != pxCurrentTCB->uxTCBNumber ) \ - { \ - if( ( pcTraceBuffer + tskSIZE_OF_EACH_TRACE_LINE ) < pcTraceBufferEnd ) \ - { \ - uxPreviousTask = pxCurrentTCB->uxTCBNumber; \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) xTickCount; \ - pcTraceBuffer += sizeof( unsigned long ); \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) uxPreviousTask; \ - pcTraceBuffer += sizeof( unsigned long ); \ - } \ - else \ - { \ - xTracing = pdFALSE; \ - } \ - } \ - } \ - } - -#else - - #define vWriteTraceToBuffer() - -#endif -/*-----------------------------------------------------------*/ - -/* - * Place the task represented by pxTCB into the appropriate ready queue for - * the task. It is inserted at the end of the list. One quirk of this is - * that if the task being inserted is at the same priority as the currently - * executing task, then it will only be rescheduled after the currently - * executing task has been rescheduled. - */ -#define prvAddTaskToReadyQueue( pxTCB ) \ -{ \ - if( pxTCB->uxPriority > uxTopReadyPriority ) \ - { \ - uxTopReadyPriority = pxTCB->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ); \ -} -/*-----------------------------------------------------------*/ - -/* - * Macro that looks at the list of tasks that are currently delayed to see if - * any require waking. - * - * Tasks are stored in the queue in the order of their wake time - meaning - * once one tasks has been found whose timer has not expired we need not look - * any further down the list. - */ -#define prvCheckDelayedTasks() \ -{ \ -register tskTCB *pxTCB; \ - \ - while( ( pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ) ) != NULL ) \ - { \ - if( xTickCount < listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ) ) \ - { \ - break; \ - } \ - vListRemove( &( pxTCB->xGenericListItem ) ); \ - /* Is the task waiting on an event also? */ \ - if( pxTCB->xEventListItem.pvContainer ) \ - { \ - vListRemove( &( pxTCB->xEventListItem ) ); \ - } \ - prvAddTaskToReadyQueue( pxTCB ); \ - } \ -} -/*-----------------------------------------------------------*/ - -/* - * Several functions take an xTaskHandle parameter that can optionally be NULL, - * where NULL is used to indicate that the handle of the currently executing - * task should be used in place of the parameter. This macro simply checks to - * see if the parameter is NULL and returns a pointer to the appropriate TCB. - */ -#define prvGetTCBFromHandle( pxHandle ) ( ( pxHandle == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) pxHandle ) - - -/* File private functions. --------------------------------*/ - -/* - * Utility to ready a TCB for a given task. Mainly just copies the parameters - * into the TCB structure. - */ -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first task. - */ -static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; - -/* - * The idle task, which as all tasks is implemented as a never ending loop. - * The idle task is automatically created and added to the ready lists upon - * creation of the first user task. - * - * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); - -/* - * Utility to free all memory allocated by the scheduler to hold a TCB, - * including the stack pointed to by the TCB. - * - * This does not free memory allocated by the task itself (i.e. memory - * allocated by calls to pvPortMalloc from within the tasks application code). - */ -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) - - static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; - -#endif - -/* - * Used only by the idle task. This checks to see if anything has been placed - * in the list of tasks waiting to be deleted. If so the task is cleaned up - * and its TCB deleted. - */ -static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; - -/* - * Allocates memory from the heap for a TCB and associated stack. Checks the - * allocation was successful. - */ -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; - -/* - * Called from vTaskList. vListTasks details all the tasks currently under - * control of the scheduler. The tasks may be in one of a number of lists. - * prvListTaskWithinSingleList accepts a list and details the tasks from - * within just that list. - * - * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM - * NORMAL APPLICATION CODE. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; - -#endif - -/* - * When a task is created, the stack of the task is filled with a known value. - * This function determines the 'high water mark' of the task stack by - * determining how much of the stack remains at the original preset value. - */ -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; - -#endif - - -/*lint +e956 */ - - - -/*----------------------------------------------------------- - * TASK CREATION API documented in task.h - *----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) -{ -signed portBASE_TYPE xReturn; -tskTCB * pxNewTCB; - - /* Allocate the memory required by the TCB and stack for the new task, - checking that the allocation was successful. */ - pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); - - if( pxNewTCB != NULL ) - { - portSTACK_TYPE *pxTopOfStack; - - #if( portUSING_MPU_WRAPPERS == 1 ) - /* Should the task be created in privileged mode? */ - portBASE_TYPE xRunPrivileged; - if( ( uxPriority & portPRIVILEGE_BIT ) != 0x00 ) - { - xRunPrivileged = pdTRUE; - } - else - { - xRunPrivileged = pdFALSE; - } - uxPriority &= ~portPRIVILEGE_BIT; - #endif /* portUSING_MPU_WRAPPERS == 1 */ - - /* Calculate the top of stack address. This depends on whether the - stack grows from high memory to low (as per the 80x86) or visa versa. - portSTACK_GROWTH is used to make the result positive or negative as - required by the port. */ - #if( portSTACK_GROWTH < 0 ) - { - pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( unsigned long ) pxTopOfStack ) & ( ( unsigned long ) ~portBYTE_ALIGNMENT_MASK ) ); - } - #else - { - pxTopOfStack = pxNewTCB->pxStack; - - /* If we want to use stack checking on architectures that use - a positive stack growth direction then we also need to store the - other extreme of the stack space. */ - pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - } - #endif - - /* Setup the newly allocated TCB with the initial state of the task. */ - prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); - - /* Initialize the TCB stack to look as if the task was already running, - but had been interrupted by the scheduler. The return address is set - to the start of the task function. Once the stack has been initialised - the top of stack variable is updated. */ - #if( portUSING_MPU_WRAPPERS == 1 ) - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); - } - #else - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); - } - #endif - - /* We are going to manipulate the task queues to add this task to a - ready list, so must make sure no interrupts occur. */ - portENTER_CRITICAL(); - { - uxCurrentNumberOfTasks++; - if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) - { - /* As this is the first task it must also be the current task. */ - pxCurrentTCB = pxNewTCB; - - /* This is the first task to be created so do the preliminary - initialisation required. We will not recover if this call - fails, but we will report the failure. */ - prvInitialiseTaskLists(); - } - else - { - /* If the scheduler is not already running, make this task the - current task if it is the highest priority task to be created - so far. */ - if( xSchedulerRunning == pdFALSE ) - { - if( pxCurrentTCB->uxPriority <= uxPriority ) - { - pxCurrentTCB = pxNewTCB; - } - } - } - - /* Remember the top priority to make context switching faster. Use - the priority in pxNewTCB as this has been capped to a valid value. */ - if( pxNewTCB->uxPriority > uxTopUsedPriority ) - { - uxTopUsedPriority = pxNewTCB->uxPriority; - } - - #if ( configUSE_TRACE_FACILITY == 1 ) - { - /* Add a counter into the TCB for tracing only. */ - pxNewTCB->uxTCBNumber = uxTaskNumber; - } - #endif - uxTaskNumber++; - - prvAddTaskToReadyQueue( pxNewTCB ); - - xReturn = pdPASS; - traceTASK_CREATE( pxNewTCB ); - } - portEXIT_CRITICAL(); - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - traceTASK_CREATE_FAILED( pxNewTCB ); - } - - if( xReturn == pdPASS ) - { - if( ( void * ) pxCreatedTask != NULL ) - { - /* Pass the TCB out - in an anonymous way. The calling function/ - task can use this as a handle to delete the task later if - required.*/ - *pxCreatedTask = ( xTaskHandle ) pxNewTCB; - } - - if( xSchedulerRunning != pdFALSE ) - { - /* If the created task is of a higher priority than the current task - then it should run now. */ - if( pxCurrentTCB->uxPriority < uxPriority ) - { - portYIELD_WITHIN_API(); - } - } - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - void vTaskDelete( xTaskHandle pxTaskToDelete ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - deleted. */ - if( pxTaskToDelete == pxCurrentTCB ) - { - pxTaskToDelete = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); - - /* Remove task from the ready list and place in the termination list. - This will stop the task from be scheduled. The idle task will check - the termination list and free up any memory allocated by the - scheduler for the TCB and stack. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); - - /* Increment the ucTasksDeleted variable so the idle task knows - there is a task that has been deleted and that it should therefore - check the xTasksWaitingTermination list. */ - ++uxTasksDeleted; - - /* Increment the uxTaskNumberVariable also so kernel aware debuggers - can detect that the task lists need re-generating. */ - uxTaskNumber++; - - traceTASK_DELETE( pxTCB ); - } - portEXIT_CRITICAL(); - - /* Force a reschedule if we have just deleted the current task. */ - if( xSchedulerRunning != pdFALSE ) - { - if( ( void * ) pxTaskToDelete == NULL ) - { - portYIELD_WITHIN_API(); - } - } - } - -#endif - - - - - - -/*----------------------------------------------------------- - * TASK CONTROL API documented in task.h - *----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelayUntil == 1 ) - - void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) - { - portTickType xTimeToWake; - portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; - - vTaskSuspendAll(); - { - /* Generate the tick time at which the task wants to wake. */ - xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; - - if( xTickCount < *pxPreviousWakeTime ) - { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - else - { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - - /* Update the wake time ready for the next call. */ - *pxPreviousWakeTime = xTimeToWake; - - if( xShouldDelay ) - { - traceTASK_DELAY_UNTIL(); - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - } - xAlreadyYielded = xTaskResumeAll(); - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( !xAlreadyYielded ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelay == 1 ) - - void vTaskDelay( portTickType xTicksToDelay ) - { - portTickType xTimeToWake; - signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* A delay time of zero just forces a reschedule. */ - if( xTicksToDelay > ( portTickType ) 0 ) - { - vTaskSuspendAll(); - { - traceTASK_DELAY(); - - /* A task that is removed from the event list while the - scheduler is suspended will not get placed in the ready - list or removed from the blocked list until the scheduler - is resumed. - - This task cannot be in an event list as it is the currently - executing task. */ - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - xAlreadyYielded = xTaskResumeAll(); - } - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( !xAlreadyYielded ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskPriorityGet == 1 ) - - unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxReturn; - - portENTER_CRITICAL(); - { - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - uxReturn = pxTCB->uxPriority; - } - portEXIT_CRITICAL(); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskPrioritySet == 1 ) - - void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxCurrentPriority, xYieldRequired = pdFALSE; - - /* Ensure the new priority is valid. */ - if( uxNewPriority >= configMAX_PRIORITIES ) - { - uxNewPriority = configMAX_PRIORITIES - 1; - } - - portENTER_CRITICAL(); - { - if( pxTask == pxCurrentTCB ) - { - pxTask = NULL; - } - - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - - traceTASK_PRIORITY_SET( pxTask, uxNewPriority ); - - #if ( configUSE_MUTEXES == 1 ) - { - uxCurrentPriority = pxTCB->uxBasePriority; - } - #else - { - uxCurrentPriority = pxTCB->uxPriority; - } - #endif - - if( uxCurrentPriority != uxNewPriority ) - { - /* The priority change may have readied a task of higher - priority than the calling task. */ - if( uxNewPriority > uxCurrentPriority ) - { - if( pxTask != NULL ) - { - /* The priority of another task is being raised. If we - were raising the priority of the currently running task - there would be no need to switch as it must have already - been the highest priority task. */ - xYieldRequired = pdTRUE; - } - } - else if( pxTask == NULL ) - { - /* Setting our own priority down means there may now be another - task of higher priority that is ready to execute. */ - xYieldRequired = pdTRUE; - } - - - - #if ( configUSE_MUTEXES == 1 ) - { - /* Only change the priority being used if the task is not - currently using an inherited priority. */ - if( pxTCB->uxBasePriority == pxTCB->uxPriority ) - { - pxTCB->uxPriority = uxNewPriority; - } - - /* The base priority gets set whatever. */ - pxTCB->uxBasePriority = uxNewPriority; - } - #else - { - pxTCB->uxPriority = uxNewPriority; - } - #endif - - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); - - /* If the task is in the blocked or suspended list we need do - nothing more than change it's priority variable. However, if - the task is in a ready list it needs to be removed and placed - in the queue appropriate to its new priority. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - /* The task is currently in its ready list - remove before adding - it to it's new ready list. As we are in a critical section we - can do this even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - - if( xYieldRequired == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - portEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskSuspend( xTaskHandle pxTaskToSuspend ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - suspended. */ - if( pxTaskToSuspend == pxCurrentTCB ) - { - pxTaskToSuspend = NULL; - } - - /* If null is passed in here then we are suspending ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); - - traceTASK_SUSPEND( pxTCB ); - - /* Remove task from the ready/delayed list and place in the suspended list. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); - } - portEXIT_CRITICAL(); - - /* We may have just suspended the current task. */ - if( ( void * ) pxTaskToSuspend == NULL ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) - { - portBASE_TYPE xReturn = pdFALSE; - const tskTCB * const pxTCB = ( tskTCB * ) xTask; - - /* Is the task we are attempting to resume actually in the - suspended list? */ - if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - /* Has the task already been resumed from within an ISR? */ - if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) - { - /* Is it in the suspended list because it is in the - Suspended state? It is possible to be in the suspended - list because it is blocked on a task with no timeout - specified. */ - if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) - { - xReturn = pdTRUE; - } - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskResume( xTaskHandle pxTaskToResume ) - { - tskTCB *pxTCB; - - /* Remove the task from whichever list it is currently in, and place - it in the ready list. */ - pxTCB = ( tskTCB * ) pxTaskToResume; - - /* The parameter cannot be NULL as it is impossible to resume the - currently executing task. */ - if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) - { - portENTER_CRITICAL(); - { - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME( pxTCB ); - - /* As we are in a critical section we can access the ready - lists even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* We may have just resumed a higher priority task. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* This yield may not cause the task just resumed to run, but - will leave the lists in the correct state for the next yield. */ - portYIELD_WITHIN_API(); - } - } - } - portEXIT_CRITICAL(); - } - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - tskTCB *pxTCB; - - pxTCB = ( tskTCB * ) pxTaskToResume; - - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME_FROM_ISR( pxTCB ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed, at which point a - yield will be performed if necessary. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); - } - } - - return xYieldRequired; - } - -#endif - - - - -/*----------------------------------------------------------- - * PUBLIC SCHEDULER CONTROL documented in task.h - *----------------------------------------------------------*/ - - -void vTaskStartScheduler( void ) -{ -portBASE_TYPE xReturn; - - /* Add the idle task at the lowest priority. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), ( xTaskHandle * ) NULL ); - - if( xReturn == pdPASS ) - { - /* Interrupts are turned off here, to ensure a tick does not occur - before or during the call to xPortStartScheduler(). The stacks of - the created tasks contain a status word with interrupts switched on - so interrupts will automatically get re-enabled when the first task - starts to run. - - STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE - DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ - portDISABLE_INTERRUPTS(); - - xSchedulerRunning = pdTRUE; - xTickCount = ( portTickType ) 0; - - /* If configGENERATE_RUN_TIME_STATS is defined then the following - macro must be defined to configure the timer/counter used to generate - the run time counter time base. */ - portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); - - /* Setting up the timer tick is hardware specific and thus in the - portable interface. */ - if( xPortStartScheduler() ) - { - /* Should not reach here as if the scheduler is running the - function will not return. */ - } - else - { - /* Should only reach here if a task calls xTaskEndScheduler(). */ - } - } -} -/*-----------------------------------------------------------*/ - -void vTaskEndScheduler( void ) -{ - /* Stop the scheduler interrupts and call the portable scheduler end - routine so the original ISRs can be restored if necessary. The port - layer must ensure interrupts enable bit is left in the correct state. */ - portDISABLE_INTERRUPTS(); - xSchedulerRunning = pdFALSE; - vPortEndScheduler(); -} -/*----------------------------------------------------------*/ - -void vTaskSuspendAll( void ) -{ - /* A critical section is not required as the variable is of type - portBASE_TYPE. */ - ++uxSchedulerSuspended; -} -/*----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskResumeAll( void ) -{ -register tskTCB *pxTCB; -signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* It is possible that an ISR caused a task to be removed from an event - list while the scheduler was suspended. If this was the case then the - removed task will have been added to the xPendingReadyList. Once the - scheduler has been resumed it is safe to move all the pending ready - tasks from this list into their appropriate ready list. */ - portENTER_CRITICAL(); - { - --uxSchedulerSuspended; - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0 ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - - /* Move any readied tasks from the pending list into the - appropriate ready list. */ - while( ( pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ) ) != NULL ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* If we have moved a task that has a priority higher than - the current task then we should yield. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - xYieldRequired = pdTRUE; - } - } - - /* If any ticks occurred while the scheduler was suspended then - they should be processed now. This ensures the tick count does not - slip, and that any delayed tasks are resumed at the correct time. */ - if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) - { - while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) - { - vTaskIncrementTick(); - --uxMissedTicks; - } - - /* As we have processed some ticks it is appropriate to yield - to ensure the highest priority task that is ready to run is - the task actually running. */ - #if configUSE_PREEMPTION == 1 - { - xYieldRequired = pdTRUE; - } - #endif - } - - if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) - { - xAlreadyYielded = pdTRUE; - xMissedYield = pdFALSE; - portYIELD_WITHIN_API(); - } - } - } - } - portEXIT_CRITICAL(); - - return xAlreadyYielded; -} - - - - - - -/*----------------------------------------------------------- - * PUBLIC TASK UTILITIES documented in task.h - *----------------------------------------------------------*/ - - - -portTickType xTaskGetTickCount( void ) -{ -portTickType xTicks; - - /* Critical section required if running on a 16 bit processor. */ - portENTER_CRITICAL(); - { - xTicks = xTickCount; - } - portEXIT_CRITICAL(); - - return xTicks; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) -{ - /* A critical section is not required because the variables are of type - portBASE_TYPE. */ - return uxCurrentNumberOfTasks; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskList( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB and - report the task name, state and stack high water mark. */ - - pcWriteBuffer[ 0 ] = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + 1; - - do - { - uxQueue--; - - if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); - } - - if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); - } - - #if( INCLUDE_vTaskDelete == 1 ) - { - if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, tskDELETED_CHAR ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, tskSUSPENDED_CHAR ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - unsigned long ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB, - generating a table of run timer percentages in the provided - buffer. */ - - pcWriteBuffer[ 0 ] = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + 1; - - do - { - uxQueue--; - - if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); - } - - if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); - } - - #if ( INCLUDE_vTaskDelete == 1 ) - { - if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, ulTotalRunTime ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, ulTotalRunTime ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) - { - portENTER_CRITICAL(); - { - pcTraceBuffer = ( signed char * )pcBuffer; - pcTraceBufferStart = pcBuffer; - pcTraceBufferEnd = pcBuffer + ( ulBufferSize - tskSIZE_OF_EACH_TRACE_LINE ); - xTracing = pdTRUE; - } - portEXIT_CRITICAL(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned long ulTaskEndTrace( void ) - { - unsigned long ulBufferLength; - - portENTER_CRITICAL(); - xTracing = pdFALSE; - portEXIT_CRITICAL(); - - ulBufferLength = ( unsigned long ) ( pcTraceBuffer - pcTraceBufferStart ); - - return ulBufferLength; - } - -#endif - - - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - * documented in task.h - *----------------------------------------------------------*/ - - -void vTaskIncrementTick( void ) -{ - /* Called by the portable layer each time a tick interrupt occurs. - Increments the tick then checks to see if the new tick value will cause any - tasks to be unblocked. */ - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - ++xTickCount; - if( xTickCount == ( portTickType ) 0 ) - { - xList *pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. - If there are any items in pxDelayedTaskList here then there is - an error! */ - pxTemp = pxDelayedTaskList; - pxDelayedTaskList = pxOverflowDelayedTaskList; - pxOverflowDelayedTaskList = pxTemp; - xNumOfOverflows++; - } - - /* See if this tick has made a timeout expire. */ - prvCheckDelayedTasks(); - } - else - { - ++uxMissedTicks; - - /* The tick hook gets called at regular intervals, even if the - scheduler is locked. */ - #if ( configUSE_TICK_HOOK == 1 ) - { - extern void vApplicationTickHook( void ); - - vApplicationTickHook(); - } - #endif - } - - #if ( configUSE_TICK_HOOK == 1 ) - { - extern void vApplicationTickHook( void ); - - /* Guard against the tick hook being called when the missed tick - count is being unwound (when the scheduler is being unlocked. */ - if( uxMissedTicks == 0 ) - { - vApplicationTickHook(); - } - } - #endif - - traceTASK_INCREMENT_TICK( xTickCount ); -} -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_vTaskCleanUpResources == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - void vTaskCleanUpResources( void ) - { - unsigned short usQueue; - volatile tskTCB *pxTCB; - - usQueue = ( unsigned short ) uxTopUsedPriority + ( unsigned short ) 1; - - /* Remove any TCB's from the ready queues. */ - do - { - usQueue--; - - while( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ usQueue ] ) ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &( pxReadyTasksLists[ usQueue ] ) ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - }while( usQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - /* Remove any TCB's from the delayed queue. */ - while( !listLIST_IS_EMPTY( &xDelayedTaskList1 ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList1 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - /* Remove any TCB's from the overflow delayed queue. */ - while( !listLIST_IS_EMPTY( &xDelayedTaskList2 ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList2 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - while( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xSuspendedTaskList ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxTagValue ) - { - tskTCB *xTCB; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - portENTER_CRITICAL(); - xTCB->pxTaskTag = pxTagValue; - portEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) - { - tskTCB *xTCB; - pdTASK_HOOK_CODE xReturn; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - portENTER_CRITICAL(); - xReturn = xTCB->pxTaskTag; - portEXIT_CRITICAL(); - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) - { - tskTCB *xTCB; - portBASE_TYPE xReturn; - - /* If xTask is NULL then we are calling our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - if( xTCB->pxTaskTag != NULL ) - { - xReturn = xTCB->pxTaskTag( pvParameter ); - } - else - { - xReturn = pdFAIL; - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -void vTaskSwitchContext( void ) -{ - if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) - { - /* The scheduler is currently suspended - do not allow a context - switch. */ - xMissedYield = pdTRUE; - return; - } - - traceTASK_SWITCHED_OUT(); - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - unsigned long ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); - - /* Add the amount of time the task has been running to the accumulated - time so far. The time the task started running was stored in - ulTaskSwitchedInTime. Note that there is no overflow protection here - so count values are only valid until the timer overflows. Generally - this will be about 1 hour assuming a 1uS timer increment. */ - pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); - ulTaskSwitchedInTime = ulTempCounter; - } - #endif - - taskFIRST_CHECK_FOR_STACK_OVERFLOW(); - taskSECOND_CHECK_FOR_STACK_OVERFLOW(); - - /* Find the highest priority queue that contains ready tasks. */ - while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) - { - --uxTopReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the - same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); - - traceTASK_SWITCHED_IN(); - vWriteTraceToBuffer(); -} -/*-----------------------------------------------------------*/ - -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) -{ -portTickType xTimeToWake; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. */ - - /* Place the event list item of the TCB in the appropriate event list. - This is placed in the list in priority order so the highest priority task - is the first to be woken by the event. */ - vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove ourselves from the ready list before adding ourselves - to the blocked list as the same list item is used for both lists. We have - exclusive access to the ready lists as the scheduler is locked. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( xTicksToWait == portMAX_DELAY ) - { - /* Add ourselves to the suspended task list instead of a delayed task - list to ensure we are not woken by a timing event. We will block - indefinitely. */ - vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - } - #else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - #endif -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) -{ -tskTCB *pxUnblockedTCB; -portBASE_TYPE xReturn; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. It can also be called from within an ISR. */ - - /* The event list is sorted in priority order, so we can remove the - first in the list, remove the TCB from the delayed list, and add - it to the ready list. - - If an event is for a queue that is locked then this function will never - get called - the lock count on the queue will get modified instead. This - means we can always expect exclusive access to the event list here. */ - pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - vListRemove( &( pxUnblockedTCB->xEventListItem ) ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxUnblockedTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); - } - - if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* Return true if the task removed from the event list has - a higher priority than the calling task. This allows - the calling task to know if it should force a context - switch now. */ - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) -{ - pxTimeOut->xOverflowCount = xNumOfOverflows; - pxTimeOut->xTimeOnEntering = xTickCount; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) -{ -portBASE_TYPE xReturn; - - portENTER_CRITICAL(); - { - #if ( INCLUDE_vTaskSuspend == 1 ) - /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is - the maximum block time then the task should block indefinitely, and - therefore never time out. */ - if( *pxTicksToWait == portMAX_DELAY ) - { - xReturn = pdFALSE; - } - else /* We are not blocking indefinitely, perform the checks below. */ - #endif - - if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) - { - /* The tick count is greater than the time at which vTaskSetTimeout() - was called, but has also overflowed since vTaskSetTimeOut() was called. - It must have wrapped all the way around and gone past us again. This - passed since vTaskSetTimeout() was called. */ - xReturn = pdTRUE; - } - else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) - { - /* Not a genuine timeout. Adjust parameters for time remaining. */ - *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); - vTaskSetTimeOutState( pxTimeOut ); - xReturn = pdFALSE; - } - else - { - xReturn = pdTRUE; - } - } - portEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskMissedYield( void ) -{ - xMissedYield = pdTRUE; -} - -/* - * ----------------------------------------------------------- - * The Idle task. - * ---------------------------------------------------------- - * - * The portTASK_FUNCTION() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION( prvIdleTask, pvParameters ) -{ - /* Stop warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* See if any tasks have been deleted. */ - prvCheckTasksWaitingTermination(); - - #if ( configUSE_PREEMPTION == 0 ) - { - /* If we are not using preemption we keep forcing a task switch to - see if any other task has become available. If we are using - preemption we don't need to do this as any task becoming available - will automatically get the processor anyway. */ - taskYIELD(); - } - #endif - - #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) - { - /* When using preemption tasks of equal priority will be - timesliced. If a task that is sharing the idle priority is ready - to run then the idle task should yield before the end of the - timeslice. - - A critical region is not required here as we are just reading from - the list, and an occasional incorrect value will not matter. If - the ready list at the idle priority contains more than one task - then a task other than the idle task is ready to execute. */ - if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) - { - taskYIELD(); - } - } - #endif - - #if ( configUSE_IDLE_HOOK == 1 ) - { - extern void vApplicationIdleHook( void ); - - /* Call the user defined function from within the idle task. This - allows the application designer to add background functionality - without the overhead of a separate task. - NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, - CALL A FUNCTION THAT MIGHT BLOCK. */ - vApplicationIdleHook(); - } - #endif - // call nanosleep for smalles sleep time possible - // (depending on kernel settings - around 100 microseconds) - // decreases idle thread CPU load from 100 to practically 0 -#ifndef __CYGWIN__ - sigset_t xSignals; - sigfillset( &xSignals ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL ); - struct timespec x; - x.tv_sec=0; - x.tv_nsec=10000; - nanosleep(&x,NULL); - sigemptyset( &xSignals ); - pthread_sigmask( SIG_SETMASK, &xSignals, NULL ); -#endif - } -} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ - - - - - - - -/*----------------------------------------------------------- - * File private functions documented at the top of the file. - *----------------------------------------------------------*/ - - - -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) -{ - /* Store the function name in the TCB. */ - #if configMAX_TASK_NAME_LEN > 1 - { - /* Don't bring strncpy into the build unnecessarily. */ - strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); - } - #endif - pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = '\0'; - - /* This is used as an array index so must ensure it's not too large. First - remove the privilege bit if one is present. */ - if( uxPriority >= configMAX_PRIORITIES ) - { - uxPriority = configMAX_PRIORITIES - 1; - } - - pxTCB->uxPriority = uxPriority; - #if ( configUSE_MUTEXES == 1 ) - { - pxTCB->uxBasePriority = uxPriority; - } - #endif - - vListInitialiseItem( &( pxTCB->xGenericListItem ) ); - vListInitialiseItem( &( pxTCB->xEventListItem ) ); - - /* Set the pxTCB as a link back from the xListItem. This is so we can get - back to the containing TCB from a generic item in a list. */ - listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - { - pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0; - } - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - { - pxTCB->pxTaskTag = NULL; - } - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - pxTCB->ulRunTimeCounter = 0UL; - } - #endif - - #if ( portUSING_MPU_WRAPPERS == 1 ) - { - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); - } - #else - { - ( void ) xRegions; - ( void ) usStackDepth; - } - #endif -} -/*-----------------------------------------------------------*/ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - - void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) - { - tskTCB *pxTCB; - - if( xTaskToModify == pxCurrentTCB ) - { - xTaskToModify = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( xTaskToModify ); - - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); - } - /*-----------------------------------------------------------*/ -#endif - -static void prvInitialiseTaskLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = 0; uxPriority < configMAX_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedTaskList1 ); - vListInitialise( ( xList * ) &xDelayedTaskList2 ); - vListInitialise( ( xList * ) &xPendingReadyList ); - - #if ( INCLUDE_vTaskDelete == 1 ) - { - vListInitialise( ( xList * ) &xTasksWaitingTermination ); - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - vListInitialise( ( xList * ) &xSuspendedTaskList ); - } - #endif - - /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList - using list2. */ - pxDelayedTaskList = &xDelayedTaskList1; - pxOverflowDelayedTaskList = &xDelayedTaskList2; -} -/*-----------------------------------------------------------*/ - -static void prvCheckTasksWaitingTermination( void ) -{ - #if ( INCLUDE_vTaskDelete == 1 ) - { - portBASE_TYPE xListIsEmpty; - - /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called - too often in the idle task. */ - if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0 ) - { - vTaskSuspendAll(); - xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); - xTaskResumeAll(); - - if( !xListIsEmpty ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - --uxCurrentNumberOfTasks; - --uxTasksDeleted; - } - portEXIT_CRITICAL(); - - prvDeleteTCB( pxTCB ); - } - } - } - #endif -} -/*-----------------------------------------------------------*/ - -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) -{ -tskTCB *pxNewTCB; - - /* Allocate space for the TCB. Where the memory comes from depends on - the implementation of the port malloc function. */ - pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); - - if( pxNewTCB != NULL ) - { - /* Allocate space for the stack used by the task being created. - The base of the stack memory stored in the TCB so the task can - be deleted later if required. */ - pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); - - if( pxNewTCB->pxStack == NULL ) - { - /* Could not allocate the stack. Delete the allocated TCB. */ - vPortFree( pxNewTCB ); - pxNewTCB = NULL; - } - else - { - /* Just to help debugging. */ - memset( pxNewTCB->pxStack, tskSTACK_FILL_BYTE, usStackDepth * sizeof( portSTACK_TYPE ) ); - } - } - - return pxNewTCB; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned short usStackRemaining; - - /* Write the details of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - #if ( portSTACK_GROWTH > 0 ) - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); - } - #else - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); - } - #endif - - sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned long ulStatsAsPercentage; - - /* Write the run time stats of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - /* Get next TCB in from the list. */ - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - - /* Divide by zero check. */ - if( ulTotalRunTime > 0UL ) - { - /* Has the task run at all? */ - if( pxNextTCB->ulRunTimeCounter == 0 ) - { - /* The task has used no CPU time at all. */ - sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); - } - else - { - /* What percentage of the total run time as the task used? - This will always be rounded down to the nearest integer. */ - ulStatsAsPercentage = ( 100UL * pxNextTCB->ulRunTimeCounter ) / ulTotalRunTime; - - if( ulStatsAsPercentage > 0UL ) - { - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); - } - else - { - /* If the percentage is zero here then the task has - consumed less than 1% of the total run time. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); - } - } - - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); - } - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) - { - register unsigned short usCount = 0; - - while( *pucStackByte == tskSTACK_FILL_BYTE ) - { - pucStackByte -= portSTACK_GROWTH; - usCount++; - } - - usCount /= sizeof( portSTACK_TYPE ); - - return usCount; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) - - unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) - { - tskTCB *pxTCB; - unsigned char *pcEndOfStack; - unsigned portBASE_TYPE uxReturn; - - pxTCB = prvGetTCBFromHandle( xTask ); - - #if portSTACK_GROWTH < 0 - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; - } - #else - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; - } - #endif - - uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) - - static void prvDeleteTCB( tskTCB *pxTCB ) - { - /* Free up the memory allocated by the scheduler for the task. It is up to - the task to free any memory allocated at the application level. */ - vPortFreeAligned( pxTCB->pxStack ); - vPortFree( pxTCB ); - } - -#endif - - -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) - - xTaskHandle xTaskGetCurrentTaskHandle( void ) - { - xTaskHandle xReturn; - - /* A critical section is not required as this is not called from - an interrupt and the current TCB will always be the same for any - individual execution thread. */ - xReturn = pxCurrentTCB; - - return xReturn; - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetSchedulerState == 1 ) - - portBASE_TYPE xTaskGetSchedulerState( void ) - { - portBASE_TYPE xReturn; - - if( xSchedulerRunning == pdFALSE ) - { - xReturn = taskSCHEDULER_NOT_STARTED; - } - else - { - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xReturn = taskSCHEDULER_RUNNING; - } - else - { - xReturn = taskSCHEDULER_SUSPENDED; - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) - { - /* Adjust the mutex holder state to account for its new priority. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); - - /* If the task being modified is in the ready state it will need to - be moved in to a new list. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Inherit the priority before being moved into the new list. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* Just inherit the priority. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxMutexHolder != NULL ) - { - if( pxTCB->uxPriority != pxTCB->uxBasePriority ) - { - /* We must be the running task to be able to give the mutex back. - Remove ourselves from the ready list we currently appear in. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Disinherit the priority before adding ourselves into the new - ready list. */ - pxTCB->uxPriority = pxTCB->uxBasePriority; - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); - prvAddTaskToReadyQueue( pxTCB ); - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - - void vTaskEnterCritical( void ) - { - portDISABLE_INTERRUPTS(); - - if( xSchedulerRunning != pdFALSE ) - { - pxCurrentTCB->uxCriticalNesting++; - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - -void vTaskExitCritical( void ) -{ - if( xSchedulerRunning != pdFALSE ) - { - if( pxCurrentTCB->uxCriticalNesting > 0 ) - { - pxCurrentTCB->uxCriticalNesting--; - - if( pxCurrentTCB->uxCriticalNesting == 0 ) - { - portENABLE_INTERRUPTS(); - } - } - } -} - -#endif -/*-----------------------------------------------------------*/ - - - - +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#include +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "timers.h" +#include "StackMacros.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* + * Macro to define the amount of stack available to the idle task. + */ +#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE + +/* + * Task control block. A task control block (TCB) is allocated to each task, + * and stores the context of the task. + */ +typedef struct tskTaskControlBlock +{ + volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ + + #if ( portUSING_MPU_WRAPPERS == 1 ) + xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ + #endif + + xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ + portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ + signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ + + #if ( portSTACK_GROWTH > 0 ) + portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ + #endif + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + unsigned portBASE_TYPE uxCriticalNesting; + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ + #endif + + #if ( configUSE_MUTEXES == 1 ) + unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + pdTASK_HOOK_CODE pxTaskTag; + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ + #endif + +} tskTCB; + + +/* + * Some kernel aware debuggers require data to be viewed to be global, rather + * than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + +/*lint -e956 */ +PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; + +/* Lists for ready and blocked tasks. --------------------*/ + +PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ +PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ +PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ +PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ +PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ +PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ + +#if ( INCLUDE_vTaskDelete == 1 ) + + PRIVILEGED_DATA static xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ + PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0U; + +#endif + +#if ( INCLUDE_vTaskSuspend == 1 ) + + PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ + +#endif + +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + + PRIVILEGED_DATA static xTaskHandle xIdleTaskHandle = NULL; + +#endif + +/* File private variables. --------------------------------*/ +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0U; +PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0U; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0U; +PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; +PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0U; +PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) portMAX_DELAY; + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + PRIVILEGED_DATA static char pcStatsString[ 50 ] ; + PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ + static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; + +#endif + +/* Debugging and trace facilities private variables and macros. ------------*/ + +/* + * The value used to fill the stack of a task when the task is created. This + * is used purely for checking the high water mark for tasks. + */ +#define tskSTACK_FILL_BYTE ( 0xa5U ) + +/* + * Macros used by vListTask to indicate which state a task is in. + */ +#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) +#define tskREADY_CHAR ( ( signed char ) 'R' ) +#define tskDELETED_CHAR ( ( signed char ) 'D' ) +#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) + +/* + * Macros and private variables used by the trace facility. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + #define tskSIZE_OF_EACH_TRACE_LINE ( ( unsigned long ) ( sizeof( unsigned long ) + sizeof( unsigned long ) ) ) + PRIVILEGED_DATA static volatile signed char * volatile pcTraceBuffer; + PRIVILEGED_DATA static signed char *pcTraceBufferStart; + PRIVILEGED_DATA static signed char *pcTraceBufferEnd; + PRIVILEGED_DATA static signed portBASE_TYPE xTracing = pdFALSE; + static unsigned portBASE_TYPE uxPreviousTask = 255U; + PRIVILEGED_DATA static char pcStatusString[ 50 ]; + +#endif + +/*-----------------------------------------------------------*/ + +/* + * Macro that writes a trace of scheduler activity to a buffer. This trace + * shows which task is running when and is very useful as a debugging tool. + * As this macro is called each context switch it is a good idea to undefine + * it if not using the facility. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + #define vWriteTraceToBuffer() \ + { \ + if( xTracing != pdFALSE ) \ + { \ + if( uxPreviousTask != pxCurrentTCB->uxTCBNumber ) \ + { \ + if( ( pcTraceBuffer + tskSIZE_OF_EACH_TRACE_LINE ) < pcTraceBufferEnd ) \ + { \ + uxPreviousTask = pxCurrentTCB->uxTCBNumber; \ + *( unsigned long * ) pcTraceBuffer = ( unsigned long ) xTickCount; \ + pcTraceBuffer += sizeof( unsigned long ); \ + *( unsigned long * ) pcTraceBuffer = ( unsigned long ) uxPreviousTask; \ + pcTraceBuffer += sizeof( unsigned long ); \ + } \ + else \ + { \ + xTracing = pdFALSE; \ + } \ + } \ + } \ + } + +#else + + #define vWriteTraceToBuffer() + +#endif +/*-----------------------------------------------------------*/ + +/* + * Place the task represented by pxTCB into the appropriate ready queue for + * the task. It is inserted at the end of the list. One quirk of this is + * that if the task being inserted is at the same priority as the currently + * executing task, then it will only be rescheduled after the currently + * executing task has been rescheduled. + */ +#define prvAddTaskToReadyQueue( pxTCB ) \ + if( ( pxTCB )->uxPriority > uxTopReadyPriority ) \ + { \ + uxTopReadyPriority = ( pxTCB )->uxPriority; \ + } \ + vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xGenericListItem ) ) +/*-----------------------------------------------------------*/ + +/* + * Macro that looks at the list of tasks that are currently delayed to see if + * any require waking. + * + * Tasks are stored in the queue in the order of their wake time - meaning + * once one tasks has been found whose timer has not expired we need not look + * any further down the list. + */ +#define prvCheckDelayedTasks() \ +{ \ +portTickType xItemValue; \ + \ + /* Is the tick count greater than or equal to the wake time of the first \ + task referenced from the delayed tasks list? */ \ + if( xTickCount >= xNextTaskUnblockTime ) \ + { \ + for( ;; ) \ + { \ + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) \ + { \ + /* The delayed list is empty. Set xNextTaskUnblockTime to the \ + maximum possible value so it is extremely unlikely that the \ + if( xTickCount >= xNextTaskUnblockTime ) test will pass next \ + time through. */ \ + xNextTaskUnblockTime = portMAX_DELAY; \ + break; \ + } \ + else \ + { \ + /* The delayed list is not empty, get the value of the item at \ + the head of the delayed list. This is the time at which the \ + task at the head of the delayed list should be removed from \ + the Blocked state. */ \ + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); \ + xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); \ + \ + if( xTickCount < xItemValue ) \ + { \ + /* It is not time to unblock this item yet, but the item \ + value is the time at which the task at the head of the \ + blocked list should be removed from the Blocked state - \ + so record the item value in xNextTaskUnblockTime. */ \ + xNextTaskUnblockTime = xItemValue; \ + break; \ + } \ + \ + /* It is time to remove the item from the Blocked state. */ \ + vListRemove( &( pxTCB->xGenericListItem ) ); \ + \ + /* Is the task waiting on an event also? */ \ + if( pxTCB->xEventListItem.pvContainer != NULL ) \ + { \ + vListRemove( &( pxTCB->xEventListItem ) ); \ + } \ + prvAddTaskToReadyQueue( pxTCB ); \ + } \ + } \ + } \ +} +/*-----------------------------------------------------------*/ + +/* + * Several functions take an xTaskHandle parameter that can optionally be NULL, + * where NULL is used to indicate that the handle of the currently executing + * task should be used in place of the parameter. This macro simply checks to + * see if the parameter is NULL and returns a pointer to the appropriate TCB. + */ +#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) ( pxHandle ) ) + +/* Callback function prototypes. --------------------------*/ +extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); +extern void vApplicationTickHook( void ); + +/* File private functions. --------------------------------*/ + +/* + * Utility to ready a TCB for a given task. Mainly just copies the parameters + * into the TCB structure. + */ +static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first task. + */ +static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; + +/* + * The idle task, which as all tasks is implemented as a never ending loop. + * The idle task is automatically created and added to the ready lists upon + * creation of the first user task. + * + * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); + +/* + * Utility to free all memory allocated by the scheduler to hold a TCB, + * including the stack pointed to by the TCB. + * + * This does not free memory allocated by the task itself (i.e. memory + * allocated by calls to pvPortMalloc from within the tasks application code). + */ +#if ( INCLUDE_vTaskDelete == 1 ) + + static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Used only by the idle task. This checks to see if anything has been placed + * in the list of tasks waiting to be deleted. If so the task is cleaned up + * and its TCB deleted. + */ +static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; + +/* + * The currently executing task is entering the Blocked state. Add the task to + * either the current or the overflow delayed task list. + */ +static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) PRIVILEGED_FUNCTION; + +/* + * Allocates memory from the heap for a TCB and associated stack. Checks the + * allocation was successful. + */ +static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; + +/* + * Called from vTaskList. vListTasks details all the tasks currently under + * control of the scheduler. The tasks may be in one of a number of lists. + * prvListTaskWithinSingleList accepts a list and details the tasks from + * within just that list. + * + * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM + * NORMAL APPLICATION CODE. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; + +#endif + +/* + * When a task is created, the stack of the task is filled with a known value. + * This function determines the 'high water mark' of the task stack by + * determining how much of the stack remains at the original preset value. + */ +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) + + static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; + +#endif + + +/*lint +e956 */ + + + +/*----------------------------------------------------------- + * TASK CREATION API documented in task.h + *----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) +{ +signed portBASE_TYPE xReturn; +tskTCB * pxNewTCB; + + configASSERT( pxTaskCode ); + configASSERT( ( uxPriority < configMAX_PRIORITIES ) ); + + /* Allocate the memory required by the TCB and stack for the new task, + checking that the allocation was successful. */ + pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); + + if( pxNewTCB != NULL ) + { + portSTACK_TYPE *pxTopOfStack; + + #if( portUSING_MPU_WRAPPERS == 1 ) + /* Should the task be created in privileged mode? */ + portBASE_TYPE xRunPrivileged; + if( ( uxPriority & portPRIVILEGE_BIT ) != 0U ) + { + xRunPrivileged = pdTRUE; + } + else + { + xRunPrivileged = pdFALSE; + } + uxPriority &= ~portPRIVILEGE_BIT; + #endif /* portUSING_MPU_WRAPPERS == 1 */ + + /* Calculate the top of stack address. This depends on whether the + stack grows from high memory to low (as per the 80x86) or visa versa. + portSTACK_GROWTH is used to make the result positive or negative as + required by the port. */ + #if( portSTACK_GROWTH < 0 ) + { + pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - ( unsigned short ) 1 ); + pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack ) & ( ( portPOINTER_SIZE_TYPE ) ~portBYTE_ALIGNMENT_MASK ) ); + + /* Check the alignment of the calculated top of stack is correct. */ + configASSERT( ( ( ( unsigned long ) pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + } + #else + { + pxTopOfStack = pxNewTCB->pxStack; + + /* Check the alignment of the stack buffer is correct. */ + configASSERT( ( ( ( unsigned long ) pxNewTCB->pxStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + /* If we want to use stack checking on architectures that use + a positive stack growth direction then we also need to store the + other extreme of the stack space. */ + pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); + } + #endif + + /* Setup the newly allocated TCB with the initial state of the task. */ + prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); + + /* Initialize the TCB stack to look as if the task was already running, + but had been interrupted by the scheduler. The return address is set + to the start of the task function. Once the stack has been initialised + the top of stack variable is updated. */ + #if( portUSING_MPU_WRAPPERS == 1 ) + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #else + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxStack, pxTaskCode, pvParameters ); + } + #endif + + /* Check the alignment of the initialised stack. */ + configASSERT( ( ( ( unsigned long ) pxNewTCB->pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + if( ( void * ) pxCreatedTask != NULL ) + { + /* Pass the TCB out - in an anonymous way. The calling function/ + task can use this as a handle to delete the task later if + required.*/ + *pxCreatedTask = ( xTaskHandle ) pxNewTCB; + } + + /* We are going to manipulate the task queues to add this task to a + ready list, so must make sure no interrupts occur. */ + taskENTER_CRITICAL(); + { + uxCurrentNumberOfTasks++; + if( pxCurrentTCB == NULL ) + { + /* There are no other tasks, or all the other tasks are in + the suspended state - make this the current task. */ + pxCurrentTCB = pxNewTCB; + + if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) + { + /* This is the first task to be created so do the preliminary + initialisation required. We will not recover if this call + fails, but we will report the failure. */ + prvInitialiseTaskLists(); + } + } + else + { + /* If the scheduler is not already running, make this task the + current task if it is the highest priority task to be created + so far. */ + if( xSchedulerRunning == pdFALSE ) + { + if( pxCurrentTCB->uxPriority <= uxPriority ) + { + pxCurrentTCB = pxNewTCB; + } + } + } + + /* Remember the top priority to make context switching faster. Use + the priority in pxNewTCB as this has been capped to a valid value. */ + if( pxNewTCB->uxPriority > uxTopUsedPriority ) + { + uxTopUsedPriority = pxNewTCB->uxPriority; + } + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + /* Add a counter into the TCB for tracing only. */ + pxNewTCB->uxTCBNumber = uxTaskNumber; + } + #endif + uxTaskNumber++; + + prvAddTaskToReadyQueue( pxNewTCB ); + + xReturn = pdPASS; + traceTASK_CREATE( pxNewTCB ); + } + taskEXIT_CRITICAL(); + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + traceTASK_CREATE_FAILED(); + } + + if( xReturn == pdPASS ) + { + if( xSchedulerRunning != pdFALSE ) + { + /* If the created task is of a higher priority than the current task + then it should run now. */ + if( pxCurrentTCB->uxPriority < uxPriority ) + { + portYIELD_WITHIN_API(); + } + } + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + void vTaskDelete( xTaskHandle pxTaskToDelete ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + /* Ensure a yield is performed if the current task is being + deleted. */ + if( pxTaskToDelete == pxCurrentTCB ) + { + pxTaskToDelete = NULL; + } + + /* If null is passed in here then we are deleting ourselves. */ + pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); + + /* Remove task from the ready list and place in the termination list. + This will stop the task from be scheduled. The idle task will check + the termination list and free up any memory allocated by the + scheduler for the TCB and stack. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Is the task waiting on an event also? */ + if( pxTCB->xEventListItem.pvContainer != NULL ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + } + + vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); + + /* Increment the ucTasksDeleted variable so the idle task knows + there is a task that has been deleted and that it should therefore + check the xTasksWaitingTermination list. */ + ++uxTasksDeleted; + + /* Increment the uxTaskNumberVariable also so kernel aware debuggers + can detect that the task lists need re-generating. */ + uxTaskNumber++; + + traceTASK_DELETE( pxTCB ); + } + taskEXIT_CRITICAL(); + + /* Force a reschedule if we have just deleted the current task. */ + if( xSchedulerRunning != pdFALSE ) + { + if( ( void * ) pxTaskToDelete == NULL ) + { + portYIELD_WITHIN_API(); + } + } + } + +#endif + + + + + + +/*----------------------------------------------------------- + * TASK CONTROL API documented in task.h + *----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelayUntil == 1 ) + + void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) + { + portTickType xTimeToWake; + portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; + + configASSERT( pxPreviousWakeTime ); + configASSERT( ( xTimeIncrement > 0U ) ); + + vTaskSuspendAll(); + { + /* Generate the tick time at which the task wants to wake. */ + xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; + + if( xTickCount < *pxPreviousWakeTime ) + { + /* The tick count has overflowed since this function was + lasted called. In this case the only time we should ever + actually delay is if the wake time has also overflowed, + and the wake time is greater than the tick time. When this + is the case it is as if neither time had overflowed. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) + { + xShouldDelay = pdTRUE; + } + } + else + { + /* The tick time has not overflowed. In this case we will + delay if either the wake time has overflowed, and/or the + tick time is less than the wake time. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) + { + xShouldDelay = pdTRUE; + } + } + + /* Update the wake time ready for the next call. */ + *pxPreviousWakeTime = xTimeToWake; + + if( xShouldDelay != pdFALSE ) + { + traceTASK_DELAY_UNTIL(); + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + } + xAlreadyYielded = xTaskResumeAll(); + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelay == 1 ) + + void vTaskDelay( portTickType xTicksToDelay ) + { + portTickType xTimeToWake; + signed portBASE_TYPE xAlreadyYielded = pdFALSE; + + /* A delay time of zero just forces a reschedule. */ + if( xTicksToDelay > ( portTickType ) 0U ) + { + vTaskSuspendAll(); + { + traceTASK_DELAY(); + + /* A task that is removed from the event list while the + scheduler is suspended will not get placed in the ready + list or removed from the blocked list until the scheduler + is resumed. + + This task cannot be in an event list as it is the currently + executing task. */ + + /* Calculate the time to wake - this may overflow but this is + not a problem. */ + xTimeToWake = xTickCount + xTicksToDelay; + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + xAlreadyYielded = xTaskResumeAll(); + } + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskPriorityGet == 1 ) + + unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) + { + tskTCB *pxTCB; + unsigned portBASE_TYPE uxReturn; + + taskENTER_CRITICAL(); + { + /* If null is passed in here then we are changing the + priority of the calling function. */ + pxTCB = prvGetTCBFromHandle( pxTask ); + uxReturn = pxTCB->uxPriority; + } + taskEXIT_CRITICAL(); + + return uxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskPrioritySet == 1 ) + + void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) + { + tskTCB *pxTCB; + unsigned portBASE_TYPE uxCurrentPriority; + portBASE_TYPE xYieldRequired = pdFALSE; + + configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) ); + + /* Ensure the new priority is valid. */ + if( uxNewPriority >= configMAX_PRIORITIES ) + { + uxNewPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; + } + + taskENTER_CRITICAL(); + { + if( pxTask == pxCurrentTCB ) + { + pxTask = NULL; + } + + /* If null is passed in here then we are changing the + priority of the calling function. */ + pxTCB = prvGetTCBFromHandle( pxTask ); + + traceTASK_PRIORITY_SET( pxTask, uxNewPriority ); + + #if ( configUSE_MUTEXES == 1 ) + { + uxCurrentPriority = pxTCB->uxBasePriority; + } + #else + { + uxCurrentPriority = pxTCB->uxPriority; + } + #endif + + if( uxCurrentPriority != uxNewPriority ) + { + /* The priority change may have readied a task of higher + priority than the calling task. */ + if( uxNewPriority > uxCurrentPriority ) + { + if( pxTask != NULL ) + { + /* The priority of another task is being raised. If we + were raising the priority of the currently running task + there would be no need to switch as it must have already + been the highest priority task. */ + xYieldRequired = pdTRUE; + } + } + else if( pxTask == NULL ) + { + /* Setting our own priority down means there may now be another + task of higher priority that is ready to execute. */ + xYieldRequired = pdTRUE; + } + + + + #if ( configUSE_MUTEXES == 1 ) + { + /* Only change the priority being used if the task is not + currently using an inherited priority. */ + if( pxTCB->uxBasePriority == pxTCB->uxPriority ) + { + pxTCB->uxPriority = uxNewPriority; + } + + /* The base priority gets set whatever. */ + pxTCB->uxBasePriority = uxNewPriority; + } + #else + { + pxTCB->uxPriority = uxNewPriority; + } + #endif + + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); + + /* If the task is in the blocked or suspended list we need do + nothing more than change it's priority variable. However, if + the task is in a ready list it needs to be removed and placed + in the queue appropriate to its new priority. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) + { + /* The task is currently in its ready list - remove before adding + it to it's new ready list. As we are in a critical section we + can do this even if the scheduler is suspended. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + + if( xYieldRequired == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + taskEXIT_CRITICAL(); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskSuspend( xTaskHandle pxTaskToSuspend ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + /* Ensure a yield is performed if the current task is being + suspended. */ + if( pxTaskToSuspend == pxCurrentTCB ) + { + pxTaskToSuspend = NULL; + } + + /* If null is passed in here then we are suspending ourselves. */ + pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); + + traceTASK_SUSPEND( pxTCB ); + + /* Remove task from the ready/delayed list and place in the suspended list. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Is the task waiting on an event also? */ + if( pxTCB->xEventListItem.pvContainer != NULL ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + } + + vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); + } + taskEXIT_CRITICAL(); + + if( ( void * ) pxTaskToSuspend == NULL ) + { + if( xSchedulerRunning != pdFALSE ) + { + /* We have just suspended the current task. */ + portYIELD_WITHIN_API(); + } + else + { + /* The scheduler is not running, but the task that was pointed + to by pxCurrentTCB has just been suspended and pxCurrentTCB + must be adjusted to point to a different task. */ + if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) + { + /* No other tasks are ready, so set pxCurrentTCB back to + NULL so when the next task is created pxCurrentTCB will + be set to point to it no matter what its relative priority + is. */ + pxCurrentTCB = NULL; + } + else + { + vTaskSwitchContext(); + } + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) + { + portBASE_TYPE xReturn = pdFALSE; + const tskTCB * const pxTCB = ( tskTCB * ) xTask; + + /* It does not make sense to check if the calling task is suspended. */ + configASSERT( xTask ); + + /* Is the task we are attempting to resume actually in the + suspended list? */ + if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) + { + /* Has the task already been resumed from within an ISR? */ + if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) + { + /* Is it in the suspended list because it is in the + Suspended state? It is possible to be in the suspended + list because it is blocked on a task with no timeout + specified. */ + if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) + { + xReturn = pdTRUE; + } + } + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskResume( xTaskHandle pxTaskToResume ) + { + tskTCB *pxTCB; + + /* It does not make sense to resume the calling task. */ + configASSERT( pxTaskToResume ); + + /* Remove the task from whichever list it is currently in, and place + it in the ready list. */ + pxTCB = ( tskTCB * ) pxTaskToResume; + + /* The parameter cannot be NULL as it is impossible to resume the + currently executing task. */ + if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) + { + taskENTER_CRITICAL(); + { + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME( pxTCB ); + + /* As we are in a critical section we can access the ready + lists even if the scheduler is suspended. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + + /* We may have just resumed a higher priority task. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* This yield may not cause the task just resumed to run, but + will leave the lists in the correct state for the next yield. */ + portYIELD_WITHIN_API(); + } + } + } + taskEXIT_CRITICAL(); + } + } + +#endif + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) + + portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) + { + portBASE_TYPE xYieldRequired = pdFALSE; + tskTCB *pxTCB; + + configASSERT( pxTaskToResume ); + + pxTCB = ( tskTCB * ) pxTaskToResume; + + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME_FROM_ISR( pxTCB ); + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed, at which point a + yield will be performed if necessary. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + } + + return xYieldRequired; + } + +#endif + + + + +/*----------------------------------------------------------- + * PUBLIC SCHEDULER CONTROL documented in task.h + *----------------------------------------------------------*/ + + +void vTaskStartScheduler( void ) +{ +portBASE_TYPE xReturn; + + /* Add the idle task at the lowest priority. */ + #if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + { + /* Create the idle task, storing its handle in xIdleTaskHandle so it can + be returned by the xTaskGetIdleTaskHandle() function. */ + xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), &xIdleTaskHandle ); + } + #else + { + /* Create the idle task without storing its handle. */ + xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), NULL ); + } + #endif + + #if ( configUSE_TIMERS == 1 ) + { + if( xReturn == pdPASS ) + { + xReturn = xTimerCreateTimerTask(); + } + } + #endif + + if( xReturn == pdPASS ) + { + /* Interrupts are turned off here, to ensure a tick does not occur + before or during the call to xPortStartScheduler(). The stacks of + the created tasks contain a status word with interrupts switched on + so interrupts will automatically get re-enabled when the first task + starts to run. + + STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE + DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ + portDISABLE_INTERRUPTS(); + + xSchedulerRunning = pdTRUE; + xTickCount = ( portTickType ) 0U; + + /* If configGENERATE_RUN_TIME_STATS is defined then the following + macro must be defined to configure the timer/counter used to generate + the run time counter time base. */ + portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); + + /* Setting up the timer tick is hardware specific and thus in the + portable interface. */ + if( xPortStartScheduler() != pdFALSE ) + { + /* Should not reach here as if the scheduler is running the + function will not return. */ + } + else + { + /* Should only reach here if a task calls xTaskEndScheduler(). */ + } + } + + /* This line will only be reached if the kernel could not be started. */ + configASSERT( xReturn ); +} +/*-----------------------------------------------------------*/ + +void vTaskEndScheduler( void ) +{ + /* Stop the scheduler interrupts and call the portable scheduler end + routine so the original ISRs can be restored if necessary. The port + layer must ensure interrupts enable bit is left in the correct state. */ + portDISABLE_INTERRUPTS(); + xSchedulerRunning = pdFALSE; + vPortEndScheduler(); +} +/*----------------------------------------------------------*/ + +void vTaskSuspendAll( void ) +{ + /* A critical section is not required as the variable is of type + portBASE_TYPE. */ + ++uxSchedulerSuspended; +} +/*----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskResumeAll( void ) +{ +register tskTCB *pxTCB; +signed portBASE_TYPE xAlreadyYielded = pdFALSE; + + /* If uxSchedulerSuspended is zero then this function does not match a + previous call to vTaskSuspendAll(). */ + configASSERT( uxSchedulerSuspended ); + + /* It is possible that an ISR caused a task to be removed from an event + list while the scheduler was suspended. If this was the case then the + removed task will have been added to the xPendingReadyList. Once the + scheduler has been resumed it is safe to move all the pending ready + tasks from this list into their appropriate ready list. */ + taskENTER_CRITICAL(); + { + --uxSchedulerSuspended; + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0U ) + { + portBASE_TYPE xYieldRequired = pdFALSE; + + /* Move any readied tasks from the pending list into the + appropriate ready list. */ + while( listLIST_IS_EMPTY( ( xList * ) &xPendingReadyList ) == pdFALSE ) + { + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ); + vListRemove( &( pxTCB->xEventListItem ) ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + + /* If we have moved a task that has a priority higher than + the current task then we should yield. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xYieldRequired = pdTRUE; + } + } + + /* If any ticks occurred while the scheduler was suspended then + they should be processed now. This ensures the tick count does not + slip, and that any delayed tasks are resumed at the correct time. */ + if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) + { + while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) + { + vTaskIncrementTick(); + --uxMissedTicks; + } + + /* As we have processed some ticks it is appropriate to yield + to ensure the highest priority task that is ready to run is + the task actually running. */ + #if configUSE_PREEMPTION == 1 + { + xYieldRequired = pdTRUE; + } + #endif + } + + if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) + { + xAlreadyYielded = pdTRUE; + xMissedYield = pdFALSE; + portYIELD_WITHIN_API(); + } + } + } + } + taskEXIT_CRITICAL(); + + return xAlreadyYielded; +} + + + + + + +/*----------------------------------------------------------- + * PUBLIC TASK UTILITIES documented in task.h + *----------------------------------------------------------*/ + + + +portTickType xTaskGetTickCount( void ) +{ +portTickType xTicks; + + /* Critical section required if running on a 16 bit processor. */ + taskENTER_CRITICAL(); + { + xTicks = xTickCount; + } + taskEXIT_CRITICAL(); + + return xTicks; +} +/*-----------------------------------------------------------*/ + +portTickType xTaskGetTickCountFromISR( void ) +{ +portTickType xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + xReturn = xTickCount; + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) +{ + /* A critical section is not required because the variables are of type + portBASE_TYPE. */ + return uxCurrentNumberOfTasks; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_pcTaskGetTaskName == 1 ) + + signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ) + { + tskTCB *pxTCB; + + /* If null is passed in here then the name of the calling task is being queried. */ + pxTCB = prvGetTCBFromHandle( xTaskToQuery ); + configASSERT( pxTCB ); + return &( pxTCB->pcTaskName[ 0 ] ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTaskList( signed char *pcWriteBuffer ) + { + unsigned portBASE_TYPE uxQueue; + + /* This is a VERY costly function that should be used for debug only. + It leaves interrupts disabled for a LONG time. */ + + vTaskSuspendAll(); + { + /* Run through all the lists that could potentially contain a TCB and + report the task name, state and stack high water mark. */ + + *pcWriteBuffer = ( signed char ) 0x00; + strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); + + uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; + + do + { + uxQueue--; + + if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); + } + + if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); + } + + #if( INCLUDE_vTaskDelete == 1 ) + { + if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, &xTasksWaitingTermination, tskDELETED_CHAR ); + } + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, &xSuspendedTaskList, tskSUSPENDED_CHAR ); + } + } + #endif + } + xTaskResumeAll(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) + { + unsigned portBASE_TYPE uxQueue; + unsigned long ulTotalRunTime; + + /* This is a VERY costly function that should be used for debug only. + It leaves interrupts disabled for a LONG time. */ + + vTaskSuspendAll(); + { + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime ); + #else + ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + + /* Divide ulTotalRunTime by 100 to make the percentage caluclations + simpler in the prvGenerateRunTimeStatsForTasksInList() function. */ + ulTotalRunTime /= 100UL; + + /* Run through all the lists that could potentially contain a TCB, + generating a table of run timer percentages in the provided + buffer. */ + + *pcWriteBuffer = ( signed char ) 0x00; + strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); + + uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; + + do + { + uxQueue--; + + if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); + } + + if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); + } + + #if ( INCLUDE_vTaskDelete == 1 ) + { + if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xTasksWaitingTermination, ulTotalRunTime ); + } + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xSuspendedTaskList, ulTotalRunTime ); + } + } + #endif + } + xTaskResumeAll(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) + { + configASSERT( pcBuffer ); + configASSERT( ulBufferSize ); + + taskENTER_CRITICAL(); + { + pcTraceBuffer = ( signed char * )pcBuffer; + pcTraceBufferStart = pcBuffer; + pcTraceBufferEnd = pcBuffer + ( ulBufferSize - tskSIZE_OF_EACH_TRACE_LINE ); + xTracing = pdTRUE; + } + taskEXIT_CRITICAL(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + unsigned long ulTaskEndTrace( void ) + { + unsigned long ulBufferLength; + + taskENTER_CRITICAL(); + xTracing = pdFALSE; + taskEXIT_CRITICAL(); + + ulBufferLength = ( unsigned long ) ( pcTraceBuffer - pcTraceBufferStart ); + + return ulBufferLength; + } + +#endif +/*----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + + xTaskHandle xTaskGetIdleTaskHandle( void ) + { + /* If xTaskGetIdleTaskHandle() is called before the scheduler has been + started, then xIdleTaskHandle will be NULL. */ + configASSERT( ( xIdleTaskHandle != NULL ) ); + return xIdleTaskHandle; + } + +#endif + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + * documented in task.h + *----------------------------------------------------------*/ + +void vTaskIncrementTick( void ) +{ +tskTCB * pxTCB; + + /* Called by the portable layer each time a tick interrupt occurs. + Increments the tick then checks to see if the new tick value will cause any + tasks to be unblocked. */ + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + ++xTickCount; + if( xTickCount == ( portTickType ) 0U ) + { + xList *pxTemp; + + /* Tick count has overflowed so we need to swap the delay lists. + If there are any items in pxDelayedTaskList here then there is + an error! */ + configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) ); + + pxTemp = pxDelayedTaskList; + pxDelayedTaskList = pxOverflowDelayedTaskList; + pxOverflowDelayedTaskList = pxTemp; + xNumOfOverflows++; + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) + { + /* The new current delayed list is empty. Set + xNextTaskUnblockTime to the maximum possible value so it is + extremely unlikely that the + if( xTickCount >= xNextTaskUnblockTime ) test will pass until + there is an item in the delayed list. */ + xNextTaskUnblockTime = portMAX_DELAY; + } + else + { + /* The new current delayed list is not empty, get the value of + the item at the head of the delayed list. This is the time at + which the task at the head of the delayed list should be removed + from the Blocked state. */ + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); + xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); + } + } + + /* See if this tick has made a timeout expire. */ + prvCheckDelayedTasks(); + } + else + { + ++uxMissedTicks; + + /* The tick hook gets called at regular intervals, even if the + scheduler is locked. */ + #if ( configUSE_TICK_HOOK == 1 ) + { + vApplicationTickHook(); + } + #endif + } + + #if ( configUSE_TICK_HOOK == 1 ) + { + /* Guard against the tick hook being called when the missed tick + count is being unwound (when the scheduler is being unlocked. */ + if( uxMissedTicks == ( unsigned portBASE_TYPE ) 0U ) + { + vApplicationTickHook(); + } + } + #endif + + traceTASK_INCREMENT_TICK( xTickCount ); +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) + { + tskTCB *xTCB; + + /* If xTask is NULL then we are setting our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + xTCB->pxTaskTag = pxHookFunction; + taskEXIT_CRITICAL(); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) + { + tskTCB *xTCB; + pdTASK_HOOK_CODE xReturn; + + /* If xTask is NULL then we are setting our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + xReturn = xTCB->pxTaskTag; + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) + { + tskTCB *xTCB; + portBASE_TYPE xReturn; + + /* If xTask is NULL then we are calling our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + if( xTCB->pxTaskTag != NULL ) + { + xReturn = xTCB->pxTaskTag( pvParameter ); + } + else + { + xReturn = pdFAIL; + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +void vTaskSwitchContext( void ) +{ + if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) + { + /* The scheduler is currently suspended - do not allow a context + switch. */ + xMissedYield = pdTRUE; + } + else + { + traceTASK_SWITCHED_OUT(); + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + unsigned long ulTempCounter; + + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ulTempCounter ); + #else + ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + + /* Add the amount of time the task has been running to the accumulated + time so far. The time the task started running was stored in + ulTaskSwitchedInTime. Note that there is no overflow protection here + so count values are only valid until the timer overflows. Generally + this will be about 1 hour assuming a 1uS timer increment. */ + pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); + ulTaskSwitchedInTime = ulTempCounter; + } + #endif + + taskFIRST_CHECK_FOR_STACK_OVERFLOW(); + taskSECOND_CHECK_FOR_STACK_OVERFLOW(); + + /* Find the highest priority queue that contains ready tasks. */ + while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) + { + configASSERT( uxTopReadyPriority ); + --uxTopReadyPriority; + } + + /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the + same priority get an equal share of the processor time. */ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); + + traceTASK_SWITCHED_IN(); + vWriteTraceToBuffer(); + } +} +/*-----------------------------------------------------------*/ + +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) +{ +portTickType xTimeToWake; + + configASSERT( pxEventList ); + + /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED. */ + + /* Place the event list item of the TCB in the appropriate event list. + This is placed in the list in priority order so the highest priority task + is the first to be woken by the event. */ + vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); + + /* We must remove ourselves from the ready list before adding ourselves + to the blocked list as the same list item is used for both lists. We have + exclusive access to the ready lists as the scheduler is locked. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( xTicksToWait == portMAX_DELAY ) + { + /* Add ourselves to the suspended task list instead of a delayed task + list to ensure we are not woken by a timing event. We will block + indefinitely. */ + vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + } + #else + { + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + #endif +} +/*-----------------------------------------------------------*/ + +#if configUSE_TIMERS == 1 + + void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) + { + portTickType xTimeToWake; + + configASSERT( pxEventList ); + + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements - + it should be called from a critical section. */ + + + /* Place the event list item of the TCB in the appropriate event list. + In this case it is assume that this is the only task that is going to + be waiting on this event list, so the faster vListInsertEnd() function + can be used in place of vListInsert. */ + vListInsertEnd( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); + + /* We must remove this task from the ready list before adding it to the + blocked list as the same list item is used for both lists. This + function is called form a critical section. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + +#endif /* configUSE_TIMERS */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) +{ +tskTCB *pxUnblockedTCB; +portBASE_TYPE xReturn; + + /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED. It can also be called from within an ISR. */ + + /* The event list is sorted in priority order, so we can remove the + first in the list, remove the TCB from the delayed list, and add + it to the ready list. + + If an event is for a queue that is locked then this function will never + get called - the lock count on the queue will get modified instead. This + means we can always expect exclusive access to the event list here. + + This function assumes that a check has already been made to ensure that + pxEventList is not empty. */ + pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); + configASSERT( pxUnblockedTCB ); + vListRemove( &( pxUnblockedTCB->xEventListItem ) ); + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxUnblockedTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); + } + + if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* Return true if the task removed from the event list has + a higher priority than the calling task. This allows + the calling task to know if it should force a context + switch now. */ + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) +{ + configASSERT( pxTimeOut ); + pxTimeOut->xOverflowCount = xNumOfOverflows; + pxTimeOut->xTimeOnEntering = xTickCount; +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) +{ +portBASE_TYPE xReturn; + + configASSERT( pxTimeOut ); + configASSERT( pxTicksToWait ); + + taskENTER_CRITICAL(); + { + #if ( INCLUDE_vTaskSuspend == 1 ) + /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is + the maximum block time then the task should block indefinitely, and + therefore never time out. */ + if( *pxTicksToWait == portMAX_DELAY ) + { + xReturn = pdFALSE; + } + else /* We are not blocking indefinitely, perform the checks below. */ + #endif + + if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) + { + /* The tick count is greater than the time at which vTaskSetTimeout() + was called, but has also overflowed since vTaskSetTimeOut() was called. + It must have wrapped all the way around and gone past us again. This + passed since vTaskSetTimeout() was called. */ + xReturn = pdTRUE; + } + else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) + { + /* Not a genuine timeout. Adjust parameters for time remaining. */ + *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); + vTaskSetTimeOutState( pxTimeOut ); + xReturn = pdFALSE; + } + else + { + xReturn = pdTRUE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskMissedYield( void ) +{ + xMissedYield = pdTRUE; +} + +/* + * ----------------------------------------------------------- + * The Idle task. + * ---------------------------------------------------------- + * + * The portTASK_FUNCTION() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION( prvIdleTask, pvParameters ) +{ + /* Stop warnings. */ + ( void ) pvParameters; + + for( ;; ) + { + /* See if any tasks have been deleted. */ + prvCheckTasksWaitingTermination(); + + #if ( configUSE_PREEMPTION == 0 ) + { + /* If we are not using preemption we keep forcing a task switch to + see if any other task has become available. If we are using + preemption we don't need to do this as any task becoming available + will automatically get the processor anyway. */ + taskYIELD(); + } + #endif + + #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) + { + /* When using preemption tasks of equal priority will be + timesliced. If a task that is sharing the idle priority is ready + to run then the idle task should yield before the end of the + timeslice. + + A critical region is not required here as we are just reading from + the list, and an occasional incorrect value will not matter. If + the ready list at the idle priority contains more than one task + then a task other than the idle task is ready to execute. */ + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) + { + taskYIELD(); + } + } + #endif + + #if ( configUSE_IDLE_HOOK == 1 ) + { + extern void vApplicationIdleHook( void ); + + /* Call the user defined function from within the idle task. This + allows the application designer to add background functionality + without the overhead of a separate task. + NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, + CALL A FUNCTION THAT MIGHT BLOCK. */ + vApplicationIdleHook(); + } + #endif + } +} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ + + + + + + + +/*----------------------------------------------------------- + * File private functions documented at the top of the file. + *----------------------------------------------------------*/ + + + +static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) +{ + /* Store the function name in the TCB. */ + #if configMAX_TASK_NAME_LEN > 1 + { + /* Don't bring strncpy into the build unnecessarily. */ + strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); + } + #endif + pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = ( signed char ) '\0'; + + /* This is used as an array index so must ensure it's not too large. First + remove the privilege bit if one is present. */ + if( uxPriority >= configMAX_PRIORITIES ) + { + uxPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; + } + + pxTCB->uxPriority = uxPriority; + #if ( configUSE_MUTEXES == 1 ) + { + pxTCB->uxBasePriority = uxPriority; + } + #endif + + vListInitialiseItem( &( pxTCB->xGenericListItem ) ); + vListInitialiseItem( &( pxTCB->xEventListItem ) ); + + /* Set the pxTCB as a link back from the xListItem. This is so we can get + back to the containing TCB from a generic item in a list. */ + listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); + listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + { + pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0U; + } + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + { + pxTCB->pxTaskTag = NULL; + } + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + pxTCB->ulRunTimeCounter = 0UL; + } + #endif + + #if ( portUSING_MPU_WRAPPERS == 1 ) + { + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); + } + #else + { + ( void ) xRegions; + ( void ) usStackDepth; + } + #endif +} +/*-----------------------------------------------------------*/ + +#if ( portUSING_MPU_WRAPPERS == 1 ) + + void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) + { + tskTCB *pxTCB; + + if( xTaskToModify == pxCurrentTCB ) + { + xTaskToModify = NULL; + } + + /* If null is passed in here then we are deleting ourselves. */ + pxTCB = prvGetTCBFromHandle( xTaskToModify ); + + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); + } + /*-----------------------------------------------------------*/ +#endif + +static void prvInitialiseTaskLists( void ) +{ +unsigned portBASE_TYPE uxPriority; + + for( uxPriority = ( unsigned portBASE_TYPE ) 0U; uxPriority < configMAX_PRIORITIES; uxPriority++ ) + { + vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); + } + + vListInitialise( ( xList * ) &xDelayedTaskList1 ); + vListInitialise( ( xList * ) &xDelayedTaskList2 ); + vListInitialise( ( xList * ) &xPendingReadyList ); + + #if ( INCLUDE_vTaskDelete == 1 ) + { + vListInitialise( ( xList * ) &xTasksWaitingTermination ); + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + vListInitialise( ( xList * ) &xSuspendedTaskList ); + } + #endif + + /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList + using list2. */ + pxDelayedTaskList = &xDelayedTaskList1; + pxOverflowDelayedTaskList = &xDelayedTaskList2; +} +/*-----------------------------------------------------------*/ + +static void prvCheckTasksWaitingTermination( void ) +{ + #if ( INCLUDE_vTaskDelete == 1 ) + { + portBASE_TYPE xListIsEmpty; + + /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called + too often in the idle task. */ + if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0U ) + { + vTaskSuspendAll(); + xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); + xTaskResumeAll(); + + if( xListIsEmpty == pdFALSE ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); + vListRemove( &( pxTCB->xGenericListItem ) ); + --uxCurrentNumberOfTasks; + --uxTasksDeleted; + } + taskEXIT_CRITICAL(); + + prvDeleteTCB( pxTCB ); + } + } + } + #endif +} +/*-----------------------------------------------------------*/ + +static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) +{ + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xTickCount ) + { + /* Wake time has overflowed. Place this item in the overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the current block list. */ + vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + /* If the task entering the blocked state was placed at the head of the + list of blocked tasks then xNextTaskUnblockTime needs to be updated + too. */ + if( xTimeToWake < xNextTaskUnblockTime ) + { + xNextTaskUnblockTime = xTimeToWake; + } + } +} +/*-----------------------------------------------------------*/ + +static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) +{ +tskTCB *pxNewTCB; + + /* Allocate space for the TCB. Where the memory comes from depends on + the implementation of the port malloc function. */ + pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); + + if( pxNewTCB != NULL ) + { + /* Allocate space for the stack used by the task being created. + The base of the stack memory stored in the TCB so the task can + be deleted later if required. */ + pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); + + if( pxNewTCB->pxStack == NULL ) + { + /* Could not allocate the stack. Delete the allocated TCB. */ + vPortFree( pxNewTCB ); + pxNewTCB = NULL; + } + else + { + /* Just to help debugging. */ + memset( pxNewTCB->pxStack, ( int ) tskSTACK_FILL_BYTE, ( size_t ) usStackDepth * sizeof( portSTACK_TYPE ) ); + } + } + + return pxNewTCB; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) + { + volatile tskTCB *pxNextTCB, *pxFirstTCB; + unsigned short usStackRemaining; + + /* Write the details of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + #if ( portSTACK_GROWTH > 0 ) + { + usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); + } + #else + { + usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); + } + #endif + + sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); + + } while( pxNextTCB != pxFirstTCB ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) + { + volatile tskTCB *pxNextTCB, *pxFirstTCB; + unsigned long ulStatsAsPercentage; + + /* Write the run time stats of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + /* Get next TCB in from the list. */ + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + + /* Divide by zero check. */ + if( ulTotalRunTime > 0UL ) + { + /* Has the task run at all? */ + if( pxNextTCB->ulRunTimeCounter == 0UL ) + { + /* The task has used no CPU time at all. */ + sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); + } + else + { + /* What percentage of the total run time has the task used? + This will always be rounded down to the nearest integer. + ulTotalRunTime has already been divided by 100. */ + ulStatsAsPercentage = pxNextTCB->ulRunTimeCounter / ulTotalRunTime; + + if( ulStatsAsPercentage > 0UL ) + { + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t%lu%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter, ulStatsAsPercentage ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); + } + #endif + } + else + { + /* If the percentage is zero here then the task has + consumed less than 1% of the total run time. */ + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t<1%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); + } + #endif + } + } + + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); + } + + } while( pxNextTCB != pxFirstTCB ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetRunTime == 1 ) + + unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) + { + unsigned long runTime; + + tskTCB *pxTCB; + pxTCB = prvGetTCBFromHandle( xTask ); + runTime = pxTCB->ulRunTimeCounter; + pxTCB->ulRunTimeCounter = 0; + return runTime; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) + + static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) + { + register unsigned short usCount = 0U; + + while( *pucStackByte == tskSTACK_FILL_BYTE ) + { + pucStackByte -= portSTACK_GROWTH; + usCount++; + } + + usCount /= sizeof( portSTACK_TYPE ); + + return usCount; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) + + unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) + { + tskTCB *pxTCB; + unsigned char *pcEndOfStack; + unsigned portBASE_TYPE uxReturn; + + pxTCB = prvGetTCBFromHandle( xTask ); + + #if portSTACK_GROWTH < 0 + { + pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; + } + #else + { + pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; + } + #endif + + uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); + + return uxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + static void prvDeleteTCB( tskTCB *pxTCB ) + { + /* Free up the memory allocated by the scheduler for the task. It is up to + the task to free any memory allocated at the application level. */ + vPortFreeAligned( pxTCB->pxStack ); + vPortFree( pxTCB ); + } + +#endif + + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) + + xTaskHandle xTaskGetCurrentTaskHandle( void ) + { + xTaskHandle xReturn; + + /* A critical section is not required as this is not called from + an interrupt and the current TCB will always be the same for any + individual execution thread. */ + xReturn = pxCurrentTCB; + + return xReturn; + } + +#endif + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + + portBASE_TYPE xTaskGetSchedulerState( void ) + { + portBASE_TYPE xReturn; + + if( xSchedulerRunning == pdFALSE ) + { + xReturn = taskSCHEDULER_NOT_STARTED; + } + else + { + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xReturn = taskSCHEDULER_RUNNING; + } + else + { + xReturn = taskSCHEDULER_SUSPENDED; + } + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) + { + tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; + + configASSERT( pxMutexHolder ); + + if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) + { + /* Adjust the mutex holder state to account for its new priority. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); + + /* If the task being modified is in the ready state it will need to + be moved in to a new list. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) != pdFALSE ) + { + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Inherit the priority before being moved into the new list. */ + pxTCB->uxPriority = pxCurrentTCB->uxPriority; + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* Just inherit the priority. */ + pxTCB->uxPriority = pxCurrentTCB->uxPriority; + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) + { + tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; + + if( pxMutexHolder != NULL ) + { + if( pxTCB->uxPriority != pxTCB->uxBasePriority ) + { + /* We must be the running task to be able to give the mutex back. + Remove ourselves from the ready list we currently appear in. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Disinherit the priority before adding ourselves into the new + ready list. */ + pxTCB->uxPriority = pxTCB->uxBasePriority; + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); + prvAddTaskToReadyQueue( pxTCB ); + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + + void vTaskEnterCritical( void ) + { + portDISABLE_INTERRUPTS(); + + if( xSchedulerRunning != pdFALSE ) + { + ( pxCurrentTCB->uxCriticalNesting )++; + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + +void vTaskExitCritical( void ) +{ + if( xSchedulerRunning != pdFALSE ) + { + if( pxCurrentTCB->uxCriticalNesting > 0U ) + { + ( pxCurrentTCB->uxCriticalNesting )--; + + if( pxCurrentTCB->uxCriticalNesting == 0U ) + { + portENABLE_INTERRUPTS(); + } + } + } +} + +#endif +/*-----------------------------------------------------------*/ + + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c new file mode 100644 index 000000000..2d8ce293b --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c @@ -0,0 +1,673 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "timers.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. This #if is closed at the very bottom +of this file. If you want to include software timer functionality then ensure +configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#if ( configUSE_TIMERS == 1 ) + +/* Misc definitions. */ +#define tmrNO_DELAY ( portTickType ) 0U + +/* The definition of the timers themselves. */ +typedef struct tmrTimerControl +{ + const signed char *pcTimerName; /*<< Text name. This is not used by the kernel, it is included simply to make debugging easier. */ + xListItem xTimerListItem; /*<< Standard linked list item as used by all kernel features for event management. */ + portTickType xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */ + unsigned portBASE_TYPE uxAutoReload; /*<< Set to pdTRUE if the timer should be automatically restarted once expired. Set to pdFALSE if the timer is, in effect, a one shot timer. */ + void *pvTimerID; /*<< An ID to identify the timer. This allows the timer to be identified when the same callback is used for multiple timers. */ + tmrTIMER_CALLBACK pxCallbackFunction; /*<< The function that will be called when the timer expires. */ +} xTIMER; + +/* The definition of messages that can be sent and received on the timer +queue. */ +typedef struct tmrTimerQueueMessage +{ + portBASE_TYPE xMessageID; /*<< The command being sent to the timer service task. */ + portTickType xMessageValue; /*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */ + xTIMER * pxTimer; /*<< The timer to which the command will be applied. */ +} xTIMER_MESSAGE; + + +/* The list in which active timers are stored. Timers are referenced in expire +time order, with the nearest expiry time at the front of the list. Only the +timer service task is allowed to access xActiveTimerList. */ +PRIVILEGED_DATA static xList xActiveTimerList1; +PRIVILEGED_DATA static xList xActiveTimerList2; +PRIVILEGED_DATA static xList *pxCurrentTimerList; +PRIVILEGED_DATA static xList *pxOverflowTimerList; + +/* A queue that is used to send commands to the timer service task. */ +PRIVILEGED_DATA static xQueueHandle xTimerQueue = NULL; + +#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + + PRIVILEGED_DATA static xTaskHandle xTimerTaskHandle = NULL; + +#endif + +/*-----------------------------------------------------------*/ + +/* + * Initialise the infrastructure used by the timer service task if it has not + * been initialised already. + */ +static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION; + +/* + * The timer service task (daemon). Timer functionality is controlled by this + * task. Other tasks communicate with the timer service task using the + * xTimerQueue queue. + */ +static void prvTimerTask( void *pvParameters ) PRIVILEGED_FUNCTION; + +/* + * Called by the timer service task to interpret and process a command it + * received on the timer queue. + */ +static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION; + +/* + * Insert the timer into either xActiveTimerList1, or xActiveTimerList2, + * depending on if the expire time causes a timer counter overflow. + */ +static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) PRIVILEGED_FUNCTION; + +/* + * An active timer has reached its expire time. Reload the timer if it is an + * auto reload timer, then call its callback. + */ +static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) PRIVILEGED_FUNCTION; + +/* + * The tick count has overflowed. Switch the timer lists after ensuring the + * current timer list does not still reference some timers. + */ +static void prvSwitchTimerLists( portTickType xLastTime ) PRIVILEGED_FUNCTION; + +/* + * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE + * if a tick count overflow occurred since prvSampleTimeNow() was last called. + */ +static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION; + +/* + * If the timer list contains any active timers then return the expire time of + * the timer that will expire first and set *pxListWasEmpty to false. If the + * timer list does not contain any timers then return 0 and set *pxListWasEmpty + * to pdTRUE. + */ +static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) PRIVILEGED_FUNCTION; + +/* + * If a timer has expired, process it. Otherwise, block the timer service task + * until either a timer does expire or a command is received. + */ +static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) PRIVILEGED_FUNCTION; + +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerCreateTimerTask( void ) +{ +portBASE_TYPE xReturn = pdFAIL; + + /* This function is called when the scheduler is started if + configUSE_TIMERS is set to 1. Check that the infrastructure used by the + timer service task has been created/initialised. If timers have already + been created then the initialisation will already have been performed. */ + prvCheckForValidListAndQueue(); + + if( xTimerQueue != NULL ) + { + #if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + { + /* Create the timer task, storing its handle in xTimerTaskHandle so + it can be returned by the xTimerGetTimerDaemonTaskHandle() function. */ + xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY, &xTimerTaskHandle ); + } + #else + { + /* Create the timer task without storing its handle. */ + xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY, NULL); + } + #endif + } + + configASSERT( xReturn ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void *pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) +{ +xTIMER *pxNewTimer; + + /* Allocate the timer structure. */ + if( xTimerPeriodInTicks == ( portTickType ) 0U ) + { + pxNewTimer = NULL; + configASSERT( ( xTimerPeriodInTicks > 0 ) ); + } + else + { + pxNewTimer = ( xTIMER * ) pvPortMalloc( sizeof( xTIMER ) ); + if( pxNewTimer != NULL ) + { + /* Ensure the infrastructure used by the timer service task has been + created/initialised. */ + prvCheckForValidListAndQueue(); + + /* Initialise the timer structure members using the function parameters. */ + pxNewTimer->pcTimerName = pcTimerName; + pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks; + pxNewTimer->uxAutoReload = uxAutoReload; + pxNewTimer->pvTimerID = pvTimerID; + pxNewTimer->pxCallbackFunction = pxCallbackFunction; + vListInitialiseItem( &( pxNewTimer->xTimerListItem ) ); + + traceTIMER_CREATE( pxNewTimer ); + } + else + { + traceTIMER_CREATE_FAILED(); + } + } + + return ( xTimerHandle ) pxNewTimer; +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) +{ +portBASE_TYPE xReturn = pdFAIL; +xTIMER_MESSAGE xMessage; + + /* Send a message to the timer service task to perform a particular action + on a particular timer definition. */ + if( xTimerQueue != NULL ) + { + /* Send a command to the timer service task to start the xTimer timer. */ + xMessage.xMessageID = xCommandID; + xMessage.xMessageValue = xOptionalValue; + xMessage.pxTimer = ( xTIMER * ) xTimer; + + if( pxHigherPriorityTaskWoken == NULL ) + { + if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING ) + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xBlockTime ); + } + else + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY ); + } + } + else + { + xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); + } + + traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn ); + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + + xTaskHandle xTimerGetTimerDaemonTaskHandle( void ) + { + /* If xTimerGetTimerDaemonTaskHandle() is called before the scheduler has been + started, then xTimerTaskHandle will be NULL. */ + configASSERT( ( xTimerTaskHandle != NULL ) ); + return xTimerTaskHandle; + } + +#endif +/*-----------------------------------------------------------*/ + +static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) +{ +xTIMER *pxTimer; +portBASE_TYPE xResult; + + /* Remove the timer from the list of active timers. A check has already + been performed to ensure the list is not empty. */ + pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); + vListRemove( &( pxTimer->xTimerListItem ) ); + traceTIMER_EXPIRED( pxTimer ); + + /* If the timer is an auto reload timer then calculate the next + expiry time and re-insert the timer in the list of active timers. */ + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + /* This is the only time a timer is inserted into a list using + a time relative to anything other than the current time. It + will therefore be inserted into the correct list relative to + the time this task thinks it is now, even if a command to + switch lists due to a tick count overflow is already waiting in + the timer queue. */ + if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) == pdTRUE ) + { + /* The timer expired before it was added to the active timer + list. Reload it now. */ + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + + /* Call the timer callback. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); +} +/*-----------------------------------------------------------*/ + +static void prvTimerTask( void *pvParameters ) +{ +portTickType xNextExpireTime; +portBASE_TYPE xListWasEmpty; + + /* Just to avoid compiler warnings. */ + ( void ) pvParameters; + + for( ;; ) + { + /* Query the timers list to see if it contains any timers, and if so, + obtain the time at which the next timer will expire. */ + xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty ); + + /* If a timer has expired, process it. Otherwise, block this task + until either a timer does expire, or a command is received. */ + prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty ); + + /* Empty the command queue. */ + prvProcessReceivedCommands(); + } +} +/*-----------------------------------------------------------*/ + +static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) +{ +portTickType xTimeNow; +portBASE_TYPE xTimerListsWereSwitched; + + vTaskSuspendAll(); + { + /* Obtain the time now to make an assessment as to whether the timer + has expired or not. If obtaining the time causes the lists to switch + then don't process this timer as any timers that remained in the list + when the lists were switched will have been processed within the + prvSampelTimeNow() function. */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + if( xTimerListsWereSwitched == pdFALSE ) + { + /* The tick count has not overflowed, has the timer expired? */ + if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) ) + { + xTaskResumeAll(); + prvProcessExpiredTimer( xNextExpireTime, xTimeNow ); + } + else + { + /* The tick count has not overflowed, and the next expire + time has not been reached yet. This task should therefore + block to wait for the next expire time or a command to be + received - whichever comes first. The following line cannot + be reached unless xNextExpireTime > xTimeNow, except in the + case when the current timer list is empty. */ + vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ) ); + + if( xTaskResumeAll() == pdFALSE ) + { + /* Yield to wait for either a command to arrive, or the block time + to expire. If a command arrived between the critical section being + exited and this yield then the yield will not cause the task + to block. */ + portYIELD_WITHIN_API(); + } + } + } + else + { + xTaskResumeAll(); + } + } +} +/*-----------------------------------------------------------*/ + +static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) +{ +portTickType xNextExpireTime; + + /* Timers are listed in expiry time order, with the head of the list + referencing the task that will expire first. Obtain the time at which + the timer with the nearest expiry time will expire. If there are no + active timers then just set the next expire time to 0. That will cause + this task to unblock when the tick count overflows, at which point the + timer lists will be switched and the next expiry time can be + re-assessed. */ + *pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList ); + if( *pxListWasEmpty == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + } + else + { + /* Ensure the task unblocks when the tick count rolls over. */ + xNextExpireTime = ( portTickType ) 0U; + } + + return xNextExpireTime; +} +/*-----------------------------------------------------------*/ + +static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) +{ +portTickType xTimeNow; +static portTickType xLastTime = ( portTickType ) 0U; + + xTimeNow = xTaskGetTickCount(); + + if( xTimeNow < xLastTime ) + { + prvSwitchTimerLists( xLastTime ); + *pxTimerListsWereSwitched = pdTRUE; + } + else + { + *pxTimerListsWereSwitched = pdFALSE; + } + + xLastTime = xTimeNow; + + return xTimeNow; +} +/*-----------------------------------------------------------*/ + +static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) +{ +portBASE_TYPE xProcessTimerNow = pdFALSE; + + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + + if( xNextExpiryTime <= xTimeNow ) + { + /* Has the expiry time elapsed between the command to start/reset a + timer was issued, and the time the command was processed? */ + if( ( ( portTickType ) ( xTimeNow - xCommandTime ) ) >= pxTimer->xTimerPeriodInTicks ) + { + /* The time between a command being issued and the command being + processed actually exceeds the timers period. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) ); + } + } + else + { + if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) ) + { + /* If, since the command was issued, the tick count has overflowed + but the expiry time has not, then the timer must have already passed + its expiry time and should be processed immediately. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + } + + return xProcessTimerNow; +} +/*-----------------------------------------------------------*/ + +static void prvProcessReceivedCommands( void ) +{ +xTIMER_MESSAGE xMessage; +xTIMER *pxTimer; +portBASE_TYPE xTimerListsWereSwitched, xResult; +portTickType xTimeNow; + + /* In this case the xTimerListsWereSwitched parameter is not used, but it + must be present in the function call. */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + + while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) + { + pxTimer = xMessage.pxTimer; + + /* Is the timer already in a list of active timers? When the command + is trmCOMMAND_PROCESS_TIMER_OVERFLOW, the timer will be NULL as the + command is to the task rather than to an individual timer. */ + if( pxTimer != NULL ) + { + if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE ) + { + /* The timer is in a list, remove it. */ + vListRemove( &( pxTimer->xTimerListItem ) ); + } + } + + traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.xMessageValue ); + + switch( xMessage.xMessageID ) + { + case tmrCOMMAND_START : + /* Start or restart a timer. */ + if( prvInsertTimerInActiveList( pxTimer, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.xMessageValue ) == pdTRUE ) + { + /* The timer expired before it was added to the active timer + list. Process it now. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); + + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + break; + + case tmrCOMMAND_STOP : + /* The timer has already been removed from the active list. + There is nothing to do here. */ + break; + + case tmrCOMMAND_CHANGE_PERIOD : + pxTimer->xTimerPeriodInTicks = xMessage.xMessageValue; + configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) ); + prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow ); + break; + + case tmrCOMMAND_DELETE : + /* The timer has already been removed from the active list, + just free up the memory. */ + vPortFree( pxTimer ); + break; + + default : + /* Don't expect to get here. */ + break; + } + } +} +/*-----------------------------------------------------------*/ + +static void prvSwitchTimerLists( portTickType xLastTime ) +{ +portTickType xNextExpireTime, xReloadTime; +xList *pxTemp; +xTIMER *pxTimer; +portBASE_TYPE xResult; + + /* Remove compiler warnings if configASSERT() is not defined. */ + ( void ) xLastTime; + + /* The tick count has overflowed. The timer lists must be switched. + If there are any timers still referenced from the current timer list + then they must have expired and should be processed before the lists + are switched. */ + while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + + /* Remove the timer from the list. */ + pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); + vListRemove( &( pxTimer->xTimerListItem ) ); + + /* Execute its callback, then send a command to restart the timer if + it is an auto-reload timer. It cannot be restarted here as the lists + have not yet been switched. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); + + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + /* Calculate the reload value, and if the reload value results in + the timer going into the same timer list then it has already expired + and the timer should be re-inserted into the current list so it is + processed again within this loop. Otherwise a command should be sent + to restart the timer to ensure it is only inserted into a list after + the lists have been swapped. */ + xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ); + if( xReloadTime > xNextExpireTime ) + { + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + else + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + } + + pxTemp = pxCurrentTimerList; + pxCurrentTimerList = pxOverflowTimerList; + pxOverflowTimerList = pxTemp; +} +/*-----------------------------------------------------------*/ + +static void prvCheckForValidListAndQueue( void ) +{ + /* Check that the list from which active timers are referenced, and the + queue used to communicate with the timer service, have been + initialised. */ + taskENTER_CRITICAL(); + { + if( xTimerQueue == NULL ) + { + vListInitialise( &xActiveTimerList1 ); + vListInitialise( &xActiveTimerList2 ); + pxCurrentTimerList = &xActiveTimerList1; + pxOverflowTimerList = &xActiveTimerList2; + xTimerQueue = xQueueCreate( ( unsigned portBASE_TYPE ) configTIMER_QUEUE_LENGTH, sizeof( xTIMER_MESSAGE ) ); + } + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) +{ +portBASE_TYPE xTimerIsInActiveList; +xTIMER *pxTimer = ( xTIMER * ) xTimer; + + /* Is the timer in the list of active timers? */ + taskENTER_CRITICAL(); + { + /* Checking to see if it is in the NULL list in effect checks to see if + it is referenced from either the current or the overflow timer lists in + one go, but the logic has to be reversed, hence the '!'. */ + xTimerIsInActiveList = !( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) ); + } + taskEXIT_CRITICAL(); + + return xTimerIsInActiveList; +} +/*-----------------------------------------------------------*/ + +void *pvTimerGetTimerID( xTimerHandle xTimer ) +{ +xTIMER *pxTimer = ( xTIMER * ) xTimer; + + return pxTimer->pvTimerID; +} +/*-----------------------------------------------------------*/ + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. If you want to include software timer +functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#endif /* configUSE_TIMERS == 1 */ diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/library.mk b/flight/PiOS/Common/Libraries/FreeRTOS/library.mk new file mode 100644 index 000000000..ae65aff82 --- /dev/null +++ b/flight/PiOS/Common/Libraries/FreeRTOS/library.mk @@ -0,0 +1,11 @@ +# +# Rules to add FreeRTOS to a PiOS target +# +# Note that the PIOS target-specific makefile will detect that FREERTOS_DIR +# has been defined and add in the target-specific pieces separately. +# + +FREERTOS_DIR := $(dir $(lastword $(MAKEFILE_LIST)))/Source +SRC += $(wildcard $(FREERTOS_DIR)/*.c) +EXTRAINCDIRS += $(FREERTOS_DIR)/include + diff --git a/flight/PiOS/Common/Libraries/dosfs/README.txt b/flight/PiOS/Common/Libraries/dosfs/README.txt new file mode 100644 index 000000000..9aeabdcbe --- /dev/null +++ b/flight/PiOS/Common/Libraries/dosfs/README.txt @@ -0,0 +1,368 @@ +README.TXT (C) Copyright 2006 +DOSFS Level 1 Version 1.02 Lewin A.R.W. Edwards (sysadm@zws.com) +===================================================================== + +Abstract +======== +DOSFS is a FAT-compatible filesystem intended for fairly low-end +embedded applications. It is not the leanest possible implementation +(the leanest FAT implementations operate in << 512 bytes of RAM, with +heavy restrictions). This code strikes a good balance between size +and functionality, with an emphasis on RAM footprint. + +Intended target systems would be in the ballpark of 1K RAM, 4K ROM +or more. + +Features: +* Supports FAT12, FAT16 and FAT32 volumes +* Supports storage devices up to 2048Gbytes in size (LBA32) +* Supports devices with or without MBRs (hard disks vs. floppy disks + or ZIP drives formatted as "big floppies") +* Supports multiple partitions on disks with MBRs +* Supports subdirectories +* Can be operated with a single global 512-byte sector buffer +* Fully reentrant code (assuming the underlying physical device driver + is reentrant and global sector buffers are not used). There are no + global variables in the filesystem +* Does not perform any memory allocation +* Partial support for random-access files + +Applications: +* Firmware upgrades +* Failsafe IPL +* Media playback +* Data logging +* Configuration storage + +There is no technical support for this free product; however, if you +have questions or suggestions, you are encouraged to email Lewin +Edwards at sysadm@zws.com. If you need custom additions to the code, +or if you have other projects for which you need engineering +assistance, please feel free to email or call (646) 549-3715. + +License +======= +The license for DOSFS is very simple but verbose to state. + +1. DOSFS is (C) Copyright 2006 by Lewin A.R.W. Edwards ("Author"). + All rights not explicitly granted herein are reserved. The DOSFS + code is the permanent property of the Author and no transfer of + ownership is implied by this license. + +2. DOSFS is an educational project, provided as-is. No guarantee of + performance or suitability for any application is stated or + implied. You use this product entirely at your own risk. Use of + this product in any manner automatically waives any right to seek + compensation or damages of any sort from the Author. Since the + products you might make are entirely out of the Author's control, + use of this product also constitutes an agreement by you to take + full responsibility for and indemnify the Author against any + action for any loss or damage (including economic loss of any + type, and specifically including patent litigation) that arises + from a product made by you that incorporates any portion of + the DOSFS code. + +3. If you live under the jurisdiction of any legislation that would + prohibit or limit any condition in this license, you cannot be + licensed to use this product. + +4. If you do not fall into the excluded category in point 3, you are + hereby licensed to use the DOSFS code in any application that you + see fit. You are not required to pay any fee or notify the Author + that you are using DOSFS. Any modifications made by you to the + DOSFS code are your property and you may distribute the modified + version in any manner that you wish. You are not required to + disclose sourcecode to such modifications, either to the Author or + to any third party. Any such disclosure made to the Author will + irrevocably become the property of the Author in the absence of a + formal agreement to the contrary, established prior to such + disclosure being made. + +To summarize the intent of the above: DOSFS is free. You can do what +you want with it. Anything that happens as a result is entirely your +responsibility. You can't take ownership of my code and stop me from +doing whatever I want with it. If you do something nifty with DOSFS +and send me the sourcecode, I may include your changes in the next +distribution and it will be released to the world as free software. +If someone sues you because your DOSFS-containing product causes +any sort of legal, financial or other problem, it's your lawsuit, +not mine, and you'll exclude me from the proceedings. + +User-Supplied Functions +======================= +You must provide functions to read sectors into memory and write +them back to the target media. The demo suite includes an emulation +module that reads/writes a disk image file (#define HOSTVER pulls +in hostemu.h which wraps the prototypes for these functions). +There are various tools for UNIX, DOS, Windows et al, to create +images from storage media; my preferred utility is dd. + +The functions you must supply in your embedded app are: + +DFS_ReadSector(unit,buffer,sector,count) +DFS_WriteSector(unit,buffer,sector,count) + +These two functions read and write, respectively, "count" sectors of +size SECTOR_SIZE (512 bytes; see below) from/to physical sector +#"sector" of device "unit", to/from the scratch buffer "buffer". They +should return 0 for success or nonzero for failure. In the current +implementation of DOSFS, count will always be 1. + +The "unit" argument is designed to permit implementation of multiple +storage devices, for example multiple media slots on a single device, +or to differentiate between master and slave devices on an ATAPI bus. + +This code is designed for 512-byte sectors. Although the sector size +is a #define, you should not tinker with it because the vast majority +of FAT filesystems use 512-byte sectors, and the DOSFS code doesn't +support runtime determination of sector size. This will not affect the +vast majority of users. + +Example Code +============ +Refer to the tests in main.c to see how to call DOSFS functions. +(These tests are all commented out). Note that the only two files +you need to add to your project are dosfs.c and dosfs.h. + + +Mounting Volumes +================ +--If the device has a partition table (practically all removable flash + media are formatted this way), call DFS_GetPtnStart to get the + starting sector# of the desired partition. You can optionally also + retrieve the active state, partition type byte and partition size + in this step. The reason this step is broken out separately is so + you can support devices that are formatted like a floppy disk, i.e. + the volume starts directly at physical sector 0 of the media. + +--Call DFS_GetVolInfo to read filesystem info into a VOLINFO structure. + DFS_GetVolInfo needs to know the unit number and partition starting + sector (as returned by DFS_GetPtnStart, or 0 if this is a "floppy- + format" volume without an MBR). + +From this point on, the VOLINFO structure is all you'll need - you can +forget the unit and partition start sector numbers. + +Enumerating Directory Contents +============================== +--Call DFS_Opendir and supply a path, populated VOLINFO and a + DIRINFO structure to receive the results. Note - you must PREPOPULATE + the DIRINFO.scratch field with a pointer to a sector scratch buffer. + This buffer must remain unmolested while you have the directory open + for searching. +--Call DFS_GetNext to receive the DIRENT contents for the next directory + item. This function returns DFS_OK for no error, and DFS_EOF if there + are no more entries in the directory being searched. + Before using the DIRENT, check the first character of the name. If it + is NULL, then this is an unusable entry - call DFS_GetNext again to + keep searching. LFN directory entries are automatically tagged this way + so your application will not be pestered by them. + + Note: A designed side-effect of this code is that when you locate the + file of interest, the DIRINFO.currentcluster, DIRINFO.currentsector + and DIRINFO.currententry-1 fields will identify the directory entry of + interest. + +Reading a File +============== +--Call DFS_OpenFile with mode = DFS_READ and supply a path and the relevant + VOLINFO structure. DFS_OpenFile will populate a FILEINFO that can be used + to refer to the file. +--Optionally call DFS_Seek to set the file pointer. If you attempt to set + the file pointer past the end of file, the file will NOT be extended. Check + the FILEINFO.pointer value after DFS_Seek to verify that the pointer is + where you expect it to be. +--Observe that functionality similar to the "whence" parameter of fseek() can + be obtained by using simple arithmetic on the FILEINFO.pointer and + FILEINFO.filelen members. +--Call DFS_ReadFile with the FILEINFO you obtained from OpenFile, and a + pointer to a buffer plus the desired number of bytes to read, and a + pointer to a sector-sized scratch buffer. The reason a scratch sector is + required is because the underlying sector read function doesn't know + about partial reads. +--Note that a file opened for reading cannot be written. If you need r/w + access, open with mode = DFS_WRITE (see below). + +Writing a file +============== +--Call DFS_OpenFile with mode = DFS_WRITE and supply a path and the relevant + VOLINFO structure. DFS_OpenFile will populate a FILEINFO that can be used to + refer to the file. +--Optionally call DFS_Seek to set the file pointer. Refer to the notes on + this topic in the section on reading files, above. +--Call DFS_WriteFile with the FILEINFO you obtained from OpenFile, and a + pointer to the source buffer, and a pointer to a sector-sized scratch + buffer. +--Note that a file open for writing can also be read. +--Files are created automatically if they do not exist. Subdirectories are + NOT automatically created. +--If you open an existing file for writing, the file pointer will start at + the beginning of the data; if you want to append, seek to the end before + writing new data. +--If you perform random-access writes to a file, the length will NOT change + unless you exceed the file's original length. There is currently no + function to truncate a file at the current pointer position. +--On-disk consistency is guaranteed when DFS_WriteFile exits, unless your + physical layer has a writeback cache in it. + +Deleting a file +=============== +--Call DFS_UnlinkFile +--WARNING: This call will delete a subdirectory (correctly) but will NOT + first recurse the directory to delete the contents - so you will end up + with lost clusters. + +Notes +===== +Some platforms may require explicit pragmas or attributes to the structures +and unions. For example, arm-gcc will require __attribute__ ((__packed__)) +otherwise it will try to be "smart" and place the uint8_t members on 4-byte +boundaries. There is no truly elegant compiler-independent method to get +around this sort of problem. + +The code assumes either a von Neumann architecture, or a compiler that +is smart enough to understand where your pointers are aimed and emit +the right kind of memory read and write instructions. The implications +of this statement depend on your target processor and the compiler you +are using. Be very careful not to straddle bank boundaries on bank- +switched memory systems. + +Physical 32-bit sector numbers are used throughout. Therefore, the +CHS geometry (if any) of the storage media is not known to DOSFS. Your +sector r/w functions may need to query the CHS geometry and perform +mapping. + +File timestamps set by DOSFS are always 1:01:00am on Jan 1, 2006. If +your system has a concept of real time, you can enhance this. + +FILEINFO structures contain a pointer to the corresponding VOLINFO +used to open the file, mainly in order to avoid mixups but also to +obviate the need for an extra parameter to every file read/write. DOSFS +assumes that the VOLINFO won't move around. If you need to move or +destroy VOLINFOs pertaining to open files, you'll have to fix up the +pointer in the FILEINFO structure yourself. + +The subdirectory delimiter is a forward slash ( '/' ) by default. The +reason for this is to avoid the common programming error of forgetting +that backslash is an escape character in C strings; i.e. "\MYDIR\FILE" +is NOT what you want; "\\MYDIR\\FILE" is what you wanted to type. If you +are porting DOS code into an embedded environment, feel free to change +this #define. + +DOSFS does not have a concept of "current directory". A current directory +is owned by a process, and a process is an operating system concept. +DOSFS is a filesystem library, not an operating system. Therefore, any +path you provide to a DOSFS call is assumed to be relative to the root of +the volume. + +There is no call to close a file or directory that is open for reading or +writing. You can simply destroy or reuse the data structures allocated for +that operation; there is no internal state in DOSFS so no cleanup is +necessary. Similarly, there is no call to close a file that is open for +writing. (Observe that dosfs.c has no global variables. All state information +is stored in data structures provided by the caller). + +MAX_PATH is defined as 64. MS-type DOS filesystems support 128 characters +or more in paths. You can increase this define, but it may GREATLY +increase memory requirements. + +VFAT long filenames are not supported. There is a certain amount of +patent controversy about them, but more importantly they don't really +belong in the scope of a "minimalist embedded filesystem". + +Improving Performance +===================== +Read performance is fairly good, but can be improved by implementing read +caching on the FAT (see below) and, depending on your hardware platform, +possibly by implementing multi-sector reads. + +Write performance may benefit ENORMOUSLY from platform-specific +optimization, especially if you are working with a flash media type that +has a large erase block size. While it is not possible to offer detailed +platform-independent advice, my general advice is to implement writeback +caching on the FAT area. One method for doing this would be to have a +cache system that lives in the DFS_ReadSector/WriteSector functions (on +top of the physical sector r/w functions) and is initially switched off. +Once you have called DFS_GetVolInfo, you then extract the VOLINFO.fat1 +and VOLINFO.rootdir parameters and pass them to your caching layer. +Sectors >= fat1 and < rootdir should be cached. The cache strategy is +determined by the physical storage medium underlying the filesystem. + +CACHING HINT: +Observe that there will be numerous read-modify-write operations in the +region from VOLINFO.fat1 through VOLINFO.fat1+VOLINFO.secperfat-1, but +in the region from VOLINFO.fat1+VOLINFO.secperfat through VOLINFO.rootdir +there will ONLY be write operations. + +Platform Compatibility +====================== +DOSFS was derived from code originally written for ARM7TDMI but +designed to be portable. It has been tested on AVR (using avrgcc), +MSP430 (using Rowley's CrossWorks) and PPC603e (using gcc); the host +test suite has also been validated on x86 using gcc under both Cygwin +and 32-bit Fedora Core 4 Linux. + +TODO list +========= +* Add function to create subdirectory +* Make DFS_UnlinkFile recognize non-empty subdirectories +* Support "fast write" files where the FAT is not updated, for + logging applications where latency is important. + +Test cases for V1.02 +==================== +Version 1.02 has NOT been through full regression testing. However the +bugs fixed in this version are important, and people have been asking +about them. + +Test cases for V1.01 +==================== +See below. + +Test cases for V1.00 +==================== +These are the test cases that were used to validate the correct +functionality of the DOSFS suite. Each test was performed on FAT12, +FAT16 and FAT32 volumes. P=Pass, F=Fail. + +Case F12 F16 F32 +--------------------------------------------------------------------- +Get volume information P P P +Open root directory P P P +List contents of root directory (fully populated) P P P +Open subdirectory P P P +List contents of subdirectory (<= 1 cluster) P P P +List contents of large subdirectory (> 1 cluster) P P P +Open 5-level nested subdirectory P P P +Open existing file for reading P P P +Open nonexistent file for reading P P P +Seek past EOF, file open for reading P P P +Seek to cluster boundary P P P +Seek past cluster boundary P P P +Seek backwards to nonzero offset, pointer > cluster size P P P +Block-read entire file >1 cluster in size, odd size P P P +Seek to odd location in file P P P +Perform <1 sector reads from random file locations P P P +Open nonexistent file for writing in root dir P P P +Open nonexistent file for writing in subdir P P P +Repeat prev. 2 tests on volume with 0 free clusters P P P +Seek past EOF, file open for writing P P P +Open existing file for writing in root dir P P P +Write random-length records to file, 20 clusters total P P P +MS-DOS 6.0 SCANDISK cross-check P P P + +Revision History +================ +Jan-06-2005 larwe Initial release (1.0) +Jan-29-2006 larwe Bugfix release (1.01) + - Fixed error in FAT12 FAT read on boundary of sector + - Improved compilability under avrgcc +Sep-16-2006 larwe Bugfix release (1.02) + - DFS_Seek would not correctly rewind to start of file + - DFS_Seek would not correctly seek to a position not on a cluster + boundary + - DFS_OpenFile fencepost error caused memory access at [start of + string-1] with a local variable + - DFS_OpenFile could not open a file in the root directory + + \ No newline at end of file diff --git a/flight/PiOS/Common/Libraries/dosfs/README_1st.txt b/flight/PiOS/Common/Libraries/dosfs/README_1st.txt new file mode 100644 index 000000000..51916ce18 --- /dev/null +++ b/flight/PiOS/Common/Libraries/dosfs/README_1st.txt @@ -0,0 +1,42 @@ +DOSFS has been developed by Lewin Edwards, and is provided as freeware. + +See README.txt for details. + +This package has been downloaded from: + http://www.larwe.com/zws/products/dosfs/ + +Version 1.03 from 9/30/06 is used. + + +dfs_sdcard has been added as access layer between DFS functions and PIOS_SDCARD functions + +The original usage examples can be found under unused/main.c + +Addendum: + +TK 2008-12-18: +DFS_Seek was running endless, applied a patch which has been posted at +http://reza.net/wordpress/?p=110 + +TK 2008-12-18: +patched the patch: endcluster wasn't calculated correctly + +TK 2008-12-18: +added 'DFS_CachingEnabledSet(uint8_t enable)' function to enable a simple +caching mechanism. This feature has to be explicitely enabled, as it isn't +reentrant and requires to use the same buffer pointer whenever reading a file! + +TK 2008-18-12 +added missing pendant to DFS_CanonicalToDir; +char *DFS_DirToCanonical(char *dest, char *src) +expects a 13 byte buffer in *dest + +TK 2009-02-12 +added dummy "DFS_Close" function +It has no effect if writing to SD Card, it's only used by the DosFS wrapper +in emulation + +TK 2009-07-04 +fixed bug in DFS_GetNext() in conjunction with the DFS_GetFreeDirEnt() function +New files where not added correctly to subdirectories + diff --git a/flight/PiOS/Common/Libraries/dosfs/dfs_sdcard.c b/flight/PiOS/Common/Libraries/dosfs/dfs_sdcard.c new file mode 100644 index 000000000..e23fe4c42 --- /dev/null +++ b/flight/PiOS/Common/Libraries/dosfs/dfs_sdcard.c @@ -0,0 +1,145 @@ +/** + ****************************************************************************** + * + * @file pios.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Access layer between DOSFS and PIOS + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Include files */ + + +#include + +#include "dosfs.h" + + +/* Local variables */ + +/* For caching - this feature has to be explicitly enabled, as it isn't reentrant */ +/* and requires to use the same buffer pointer whenever reading a file. */ +static uint32_t last_sector; +static uint8_t caching_enabled = 0; + +void DFS_CachingEnabledSet(uint8_t enable) +{ + caching_enabled = enable; + last_sector = 0xffffffff; +} + + +/** +* Converts directory name to canonical name +* (missing pendant to DFS_anonicalToDir) +* dest must point to a 13-byte buffer +*/ +char *DFS_DirToCanonical(char *dest, char *src) +{ + uint8_t pos = 0; + + while( pos < 8 && src[pos] != ' ' ) { + *dest++ = src[pos++]; + } + + if( src[8] != ' ' ) { + *dest++ = '.'; + + pos = 8; + while( pos < 11 && src[pos] != ' ' ) { + *dest++ = src[pos++]; + } + } + + /* Terminate string */ + *dest = 0; + + return dest; +} + + + +/** +* Read sector from SD Card +* Returns 0 OK, nonzero for any error +*/ +uint32_t DFS_ReadSector(uint8_t unit, uint8_t *buffer, uint32_t sector, uint32_t count) +{ + /* Only allow access to single unit */ + if(unit != 0) { + return 1; + } + + /* According to README.txt, count is always 1 - check this! */ + if(count != 1) { + return 2; + } + + /* Cache: */ + if(caching_enabled && sector == last_sector) { + /* we assume that sector is already in *buffer */ + /* since the user has to take care that the same buffer is used for file reads, this */ + /* feature has to be explicitly enabled with DFS_CachingEnabledSet(uint8_t enable) */ + return 0; + } + + last_sector = sector; + + /* Forward to PIOS */ + int32_t status; + if((status = PIOS_SDCARD_SectorRead(sector, buffer)) != 0) { + /* Cannot access SD Card */ + return 3; + } + + /* Success */ + return 0; +} + +/** +* Write sector to SD Card +* Returns 0 OK, nonzero for any error +*/ +uint32_t DFS_WriteSector(uint8_t unit, uint8_t *buffer, uint32_t sector, uint32_t count) +{ + /* Only allow access to single unit */ + if(unit != 0) { + return 1; + } + + /* According to README.txt, count is always 1 - check this! */ + if(count != 1) { + return 2; + } + + /* Invalidate cache */ + last_sector = 0xffffffff; + + /* Forward to PIOS */ + int32_t status; + if((status = PIOS_SDCARD_SectorWrite(sector, buffer)) < 0) { + /* Cannot access SD Card */ + return 3; + } + + /* Success */ + return 0; +} + diff --git a/flight/PiOS/Common/Libraries/dosfs/dosfs.c b/flight/PiOS/Common/Libraries/dosfs/dosfs.c new file mode 100644 index 000000000..4c35f5e77 --- /dev/null +++ b/flight/PiOS/Common/Libraries/dosfs/dosfs.c @@ -0,0 +1,1337 @@ +/* + DOSFS Embedded FAT-Compatible Filesystem + (C) 2005 Lewin A.R.W. Edwards (sysadm@zws.com) + + You are permitted to modify and/or use this code in your own projects without + payment of royalty, regardless of the license(s) you choose for those projects. + + You cannot re-copyright or restrict use of the code as released by Lewin Edwards. +*/ + + +//#include "common.h" +#include +#include +//#include "fat.h" + +#define div(a,b) ldiv(a,b) + +#include "dosfs.h" + +/* + Get starting sector# of specified partition on drive #unit + NOTE: This code ASSUMES an MBR on the disk. + scratchsector should point to a SECTOR_SIZE scratch area + Returns 0xffffffff for any error. + If pactive is non-NULL, this function also returns the partition active flag. + If pptype is non-NULL, this function also returns the partition type. + If psize is non-NULL, this function also returns the partition size. +*/ +uint32_t DFS_GetPtnStart(uint8_t unit, uint8_t *scratchsector, uint8_t pnum, uint8_t *pactive, uint8_t *pptype, uint32_t *psize) +{ + uint32_t result=0; + PMBR mbr = (PMBR) scratchsector; + + // DOS ptable supports maximum 4 partitions + if (pnum > 3) + return DFS_ERRMISC; + + // Read MBR from target media + if (DFS_ReadSector(unit,scratchsector,0,1)) { + return DFS_ERRMISC; + } + + // check if jump to boot, VBR + if(mbr->bootcode[0]==0xEB || mbr->bootcode[0]==0xE9){ + // MBR is actually VBR + return 0; + } + + result = (uint32_t) mbr->ptable[pnum].start_0 | + (((uint32_t) mbr->ptable[pnum].start_1) << 8) | + (((uint32_t) mbr->ptable[pnum].start_2) << 16) | + (((uint32_t) mbr->ptable[pnum].start_3) << 24); + + if (pactive) + *pactive = mbr->ptable[pnum].active; + + if (pptype) + *pptype = mbr->ptable[pnum].type; + + if (psize) + *psize = (uint32_t) mbr->ptable[pnum].size_0 | + (((uint32_t) mbr->ptable[pnum].size_1) << 8) | + (((uint32_t) mbr->ptable[pnum].size_2) << 16) | + (((uint32_t) mbr->ptable[pnum].size_3) << 24); + + return result; +} + + +/* + Retrieve volume info from BPB and store it in a VOLINFO structure + You must provide the unit and starting sector of the filesystem, and + a pointer to a sector buffer for scratch + Attempts to read BPB and glean information about the FS from that. + Returns 0 OK, nonzero for any error. +*/ +uint32_t DFS_GetVolInfo(uint8_t unit, uint8_t *scratchsector, uint32_t startsector, PVOLINFO volinfo) +{ + PLBR lbr = (PLBR) scratchsector; + volinfo->unit = unit; + volinfo->startsector = startsector; +#ifdef DEBUG_DOSFS + printf("DFS_GetVolInfo\r\n"); +#endif + + if(DFS_ReadSector(unit,scratchsector,startsector,1)) + return DFS_ERRMISC; + +// tag: OEMID, refer dosfs.h +// strncpy(volinfo->oemid, lbr->oemid, 8); +// volinfo->oemid[8] = 0; + + volinfo->secperclus = lbr->bpb.secperclus; + volinfo->reservedsecs = (uint16_t) lbr->bpb.reserved_l | + (((uint16_t) lbr->bpb.reserved_h) << 8); + + volinfo->numsecs = (uint16_t) lbr->bpb.sectors_s_l | + (((uint16_t) lbr->bpb.sectors_s_h) << 8); + + if (!volinfo->numsecs) + volinfo->numsecs = (uint32_t) lbr->bpb.sectors_l_0 | + (((uint32_t) lbr->bpb.sectors_l_1) << 8) | + (((uint32_t) lbr->bpb.sectors_l_2) << 16) | + (((uint32_t) lbr->bpb.sectors_l_3) << 24); + + // If secperfat is 0, we must be in a FAT32 volume; get secperfat + // from the FAT32 EBPB. The volume label and system ID string are also + // in different locations for FAT12/16 vs FAT32. + volinfo->secperfat = (uint16_t) lbr->bpb.secperfat_l | + (((uint16_t) lbr->bpb.secperfat_h) << 8); + if (!volinfo->secperfat) { + volinfo->secperfat = (uint32_t) lbr->ebpb.ebpb32.fatsize_0 | + (((uint32_t) lbr->ebpb.ebpb32.fatsize_1) << 8) | + (((uint32_t) lbr->ebpb.ebpb32.fatsize_2) << 16) | + (((uint32_t) lbr->ebpb.ebpb32.fatsize_3) << 24); + + memcpy(volinfo->label, lbr->ebpb.ebpb32.label, 11); + volinfo->label[11] = 0; + +// tag: OEMID, refer dosfs.h +// memcpy(volinfo->system, lbr->ebpb.ebpb32.system, 8); +// volinfo->system[8] = 0; + } + else { + memcpy(volinfo->label, lbr->ebpb.ebpb.label, 11); + volinfo->label[11] = 0; + +// tag: OEMID, refer dosfs.h +// memcpy(volinfo->system, lbr->ebpb.ebpb.system, 8); +// volinfo->system[8] = 0; + } + + // note: if rootentries is 0, we must be in a FAT32 volume. + volinfo->rootentries = (uint16_t) lbr->bpb.rootentries_l | + (((uint16_t) lbr->bpb.rootentries_h) << 8); + + // after extracting raw info we perform some useful precalculations + volinfo->fat1 = startsector + volinfo->reservedsecs; + + // The calculation below is designed to round up the root directory size for FAT12/16 + // and to simply ignore the root directory for FAT32, since it's a normal, expandable + // file in that situation. + if (volinfo->rootentries) { + volinfo->rootdir = volinfo->fat1 + (volinfo->secperfat * 2); + volinfo->dataarea = volinfo->rootdir + (((volinfo->rootentries * 32) + (SECTOR_SIZE - 1)) / SECTOR_SIZE); + } + else { + volinfo->dataarea = volinfo->fat1 + (volinfo->secperfat * 2); + volinfo->rootdir = (uint32_t) lbr->ebpb.ebpb32.root_0 | + (((uint32_t) lbr->ebpb.ebpb32.root_1) << 8) | + (((uint32_t) lbr->ebpb.ebpb32.root_2) << 16) | + (((uint32_t) lbr->ebpb.ebpb32.root_3) << 24); + } + + // Calculate number of clusters in data area and infer FAT type from this information. + volinfo->numclusters = (volinfo->numsecs - volinfo->dataarea) / volinfo->secperclus; + if (volinfo->numclusters < 4085) + volinfo->filesystem = FAT12; + else if (volinfo->numclusters < 65525) + volinfo->filesystem = FAT16; + else + volinfo->filesystem = FAT32; + + return DFS_OK; +} + +/* + Fetch FAT entry for specified cluster number + You must provide a scratch buffer for one sector (SECTOR_SIZE) and a populated VOLINFO + Returns a FAT32 BAD_CLUSTER value for any error, otherwise the contents of the desired + FAT entry. + scratchcache should point to a UINT32. This variable caches the physical sector number + last read into the scratch buffer for performance enhancement reasons. +*/ +uint32_t DFS_GetFAT(PVOLINFO volinfo, uint8_t *scratch, uint32_t *scratchcache, uint32_t cluster) +{ + uint32_t offset=0, sector=0, result=0; + +#ifdef DEBUG_DOSFS + printf("DFS_GetFAT\r\n"); +#endif + + if (volinfo->filesystem == FAT12) { + offset = cluster + (cluster / 2); + } + else if (volinfo->filesystem == FAT16) { + offset = cluster * 2; + } + else if (volinfo->filesystem == FAT32) { + offset = cluster * 4; + } + else + return 0x0ffffff7; // FAT32 bad cluster + + // at this point, offset is the BYTE offset of the desired sector from the start + // of the FAT. Calculate the physical sector containing this FAT entry. + sector = ldiv(offset, SECTOR_SIZE).quot + volinfo->fat1; + + // If this is not the same sector we last read, then read it into RAM + if (sector != *scratchcache) { + if(DFS_ReadSector(volinfo->unit, scratch, sector, 1)) { + // avoid anyone assuming that this cache value is still valid, which + // might cause disk corruption + *scratchcache = 0; + return 0x0ffffff7; // FAT32 bad cluster + } + *scratchcache = sector; + } + + // At this point, we "merely" need to extract the relevant entry. + // This is easy for FAT16 and FAT32, but a royal PITA for FAT12 as a single entry + // may span a sector boundary. The normal way around this is always to read two + // FAT sectors, but that luxury is (by design intent) unavailable to DOSFS. + offset = ldiv(offset, SECTOR_SIZE).rem; + + if (volinfo->filesystem == FAT12) { + // Special case for sector boundary - Store last byte of current sector. + // Then read in the next sector and put the first byte of that sector into + // the high byte of result. + if (offset == SECTOR_SIZE - 1) { + result = (uint32_t) scratch[offset]; + sector++; + if(DFS_ReadSector(volinfo->unit, scratch, sector, 1)) { + // avoid anyone assuming that this cache value is still valid, which + // might cause disk corruption + *scratchcache = 0; + return 0x0ffffff7; // FAT32 bad cluster + } + *scratchcache = sector; + // Thanks to Claudio Leonel for pointing out this missing line. + result |= ((uint32_t) scratch[0]) << 8; + } + else { + result = (uint32_t) scratch[offset] | + ((uint32_t) scratch[offset+1]) << 8; + } + if (cluster & 1) + result = result >> 4; + else + result = result & 0xfff; + } + else if (volinfo->filesystem == FAT16) { + result = (uint32_t) scratch[offset] | + ((uint32_t) scratch[offset+1]) << 8; + } + else if (volinfo->filesystem == FAT32) { + result = ((uint32_t) scratch[offset] | + ((uint32_t) scratch[offset+1]) << 8 | + ((uint32_t) scratch[offset+2]) << 16 | + ((uint32_t) scratch[offset+3]) << 24) & 0x0fffffff; + } + else + result = 0x0ffffff7; // FAT32 bad cluster + return result; +} + + +/* + Set FAT entry for specified cluster number + You must provide a scratch buffer for one sector (SECTOR_SIZE) and a populated VOLINFO + Returns DFS_ERRMISC for any error, otherwise DFS_OK + scratchcache should point to a UINT32. This variable caches the physical sector number + last read into the scratch buffer for performance enhancement reasons. + + NOTE: This code is HIGHLY WRITE-INEFFICIENT, particularly for flash media. Considerable + performance gains can be realized by caching the sector. However this is difficult to + achieve on FAT12 without requiring 2 sector buffers of scratch space, and it is a design + requirement of this code to operate on a single 512-byte scratch. + + If you are operating DOSFS over flash, you are strongly advised to implement a writeback + cache in your physical I/O driver. This will speed up your code significantly and will + also conserve power and flash write life. +*/ +uint32_t DFS_SetFAT(PVOLINFO volinfo, uint8_t *scratch, uint32_t *scratchcache, uint32_t cluster, uint32_t new_contents) +{ + uint32_t offset=0, sector=0, result=0; +#ifdef DEBUG_DOSFS + printf("DFS_SetFAT (%lu->%lu)\r\n",cluster,new_contents); +#endif + + if (volinfo->filesystem == FAT12) { + offset = cluster + (cluster / 2); + new_contents &=0xfff; + } + else if (volinfo->filesystem == FAT16) { + offset = cluster * 2; + new_contents &=0xffff; + } + else if (volinfo->filesystem == FAT32) { + offset = cluster * 4; + new_contents &=0x0fffffff; // FAT32 is really "FAT28" + } + else + return DFS_ERRMISC; + + // at this point, offset is the BYTE offset of the desired sector from the start + // of the FAT. Calculate the physical sector containing this FAT entry. + sector = ldiv(offset, SECTOR_SIZE).quot + volinfo->fat1; + + // If this is not the same sector we last read, then read it into RAM + if (sector != *scratchcache) { + if(DFS_ReadSector(volinfo->unit, scratch, sector, 1)) { + // avoid anyone assuming that this cache value is still valid, which + // might cause disk corruption + *scratchcache = 0; + return DFS_ERRMISC; + } + *scratchcache = sector; + } + + // At this point, we "merely" need to extract the relevant entry. + // This is easy for FAT16 and FAT32, but a royal PITA for FAT12 as a single entry + // may span a sector boundary. The normal way around this is always to read two + // FAT sectors, but that luxury is (by design intent) unavailable to DOSFS. + offset = ldiv(offset, SECTOR_SIZE).rem; + + if (volinfo->filesystem == FAT12) { + + // If this is an odd cluster, pre-shift the desired new contents 4 bits to + // make the calculations below simpler + if (cluster & 1) + new_contents = new_contents << 4; + + // Special case for sector boundary + if (offset == SECTOR_SIZE - 1) { + + // Odd cluster: High 12 bits being set + if (cluster & 1) { + scratch[offset] = (scratch[offset] & 0x0f) | (new_contents & 0xf0); + } + // Even cluster: Low 12 bits being set + else { + scratch[offset] = new_contents & 0xff; + } + result = DFS_WriteSector(volinfo->unit, scratch, *scratchcache, 1); + // mirror the FAT into copy 2 + if (DFS_OK == result) + result = DFS_WriteSector(volinfo->unit, scratch, (*scratchcache)+volinfo->secperfat, 1); + + // If we wrote that sector OK, then read in the subsequent sector + // and poke the first byte with the remainder of this FAT entry. + if (DFS_OK == result) { + // *scratchcache++; + ++*scratchcache; // TK: to avoid warning "value computed is not used" + result = DFS_ReadSector(volinfo->unit, scratch, *scratchcache, 1); + if (DFS_OK == result) { + // Odd cluster: High 12 bits being set + if (cluster & 1) { + scratch[0] = new_contents & 0xff00; + } + // Even cluster: Low 12 bits being set + else { + scratch[0] = (scratch[0] & 0xf0) | (new_contents & 0x0f); + } + result = DFS_WriteSector(volinfo->unit, scratch, *scratchcache, 1); + // mirror the FAT into copy 2 + if (DFS_OK == result) + result = DFS_WriteSector(volinfo->unit, scratch, (*scratchcache)+volinfo->secperfat, 1); + } + else { + // avoid anyone assuming that this cache value is still valid, which + // might cause disk corruption + *scratchcache = 0; + } + } + } // if (offset == SECTOR_SIZE - 1) + + // Not a sector boundary. But we still have to worry about if it's an odd + // or even cluster number. + else { + // Odd cluster: High 12 bits being set + if (cluster & 1) { + scratch[offset] = (scratch[offset] & 0x0f) | (new_contents & 0xf0); + scratch[offset+1] = new_contents & 0xff00; + } + // Even cluster: Low 12 bits being set + else { + scratch[offset] = new_contents & 0xff; + scratch[offset+1] = (scratch[offset+1] & 0xf0) | (new_contents & 0x0f); + } + result = DFS_WriteSector(volinfo->unit, scratch, *scratchcache, 1); + // mirror the FAT into copy 2 + if (DFS_OK == result) + result = DFS_WriteSector(volinfo->unit, scratch, (*scratchcache)+volinfo->secperfat, 1); + } + } + else if (volinfo->filesystem == FAT16) { + scratch[offset] = (new_contents & 0xff); + scratch[offset+1] = (new_contents & 0xff00) >> 8; + result = DFS_WriteSector(volinfo->unit, scratch, *scratchcache, 1); + // mirror the FAT into copy 2 - XXX + if (DFS_OK == result) + result = DFS_WriteSector(volinfo->unit, scratch, (*scratchcache)+volinfo->secperfat, 1); + } + else if (volinfo->filesystem == FAT32) { + scratch[offset] = (new_contents & 0xff); + scratch[offset+1] = (new_contents & 0xff00) >> 8; + scratch[offset+2] = (new_contents & 0xff0000) >> 16; + scratch[offset+3] = (scratch[offset+3] & 0xf0) | ((new_contents & 0x0f000000) >> 24); + // Note well from the above: Per Microsoft's guidelines we preserve the upper + // 4 bits of the FAT32 cluster value. It's unclear what these bits will be used + // for; in every example I've encountered they are always zero. + result = DFS_WriteSector(volinfo->unit, scratch, *scratchcache, 1); + // mirror the FAT into copy 2 + if (DFS_OK == result) + result = DFS_WriteSector(volinfo->unit, scratch, (*scratchcache)+volinfo->secperfat, 1); + } + else + result = DFS_ERRMISC; + + return result; +} + +/* + Convert a filename element from canonical (8.3) to directory entry (11) form + src must point to the first non-separator character. + dest must point to a 12-byte buffer. +*/ +uint8_t *DFS_CanonicalToDir(uint8_t *dest, uint8_t *src) +{ + uint8_t *destptr = dest; + + memset(dest, ' ', 11); + dest[11] = 0; + + while (*src && (*src != DIR_SEPARATOR) && (destptr - dest < 11)) { + if (*src >= 'a' && *src <='z') { + *destptr++ = (*src - 'a') + 'A'; + src++; + } + else if (*src == '.') { + src++; + destptr = dest + 8; + } + else { + *destptr++ = *src++; + } + } + + return dest; +} + +/* + Find the first unused FAT entry + You must provide a scratch buffer for one sector (SECTOR_SIZE) and a populated VOLINFO + Returns a FAT32 BAD_CLUSTER value for any error, otherwise the contents of the desired + FAT entry. + Returns FAT32 bad_sector (0x0ffffff7) if there is no free cluster available +*/ +uint32_t DFS_GetFreeFAT(PVOLINFO volinfo, uint8_t *scratch) +{ + uint32_t i, result = 0xffffffff, scratchcache = 0; + + +#ifdef DEBUG_DOSFS + printf("DFS_GetFreeFAT\r\n"); +#endif + + // Search starts at cluster 2, which is the first usable cluster + // NOTE: This search can't terminate at a bad cluster, because there might + // legitimately be bad clusters on the disk. + for (i=2; i < volinfo->numclusters; i++) { + result = DFS_GetFAT(volinfo, scratch, &scratchcache, i); + if (!result) { + return i; + } + } + return 0x0ffffff7; // Can't find a free cluster +} + + +/* + Open a directory for enumeration by DFS_GetNextDirEnt + You must supply a populated VOLINFO (see DFS_GetVolInfo) + ** you must also make sure dirinfo->scratch is valid in the dirinfo you pass it** //reza + The empty string or a string containing only the directory separator are + considered to be the root directory. + Returns 0 OK, nonzero for any error. +*/ +uint32_t DFS_OpenDir(PVOLINFO volinfo, uint8_t *dirname, PDIRINFO dirinfo) +{ + // Default behavior is a regular search for existing entries + dirinfo->flags = 0; +#ifdef DEBUG_DOSFS + printf("DFS_OpenDir\r\n"); +#endif + + if (!strlen((char *) dirname) || (strlen((char *) dirname) == 1 && dirname[0] == DIR_SEPARATOR)) { + if (volinfo->filesystem == FAT32) { + dirinfo->currentcluster = volinfo->rootdir; + dirinfo->currentsector = 0; + dirinfo->currententry = 0; + + // read first sector of directory + return DFS_ReadSector(volinfo->unit, dirinfo->scratch, volinfo->dataarea + ((volinfo->rootdir - 2) * volinfo->secperclus), 1); + } + else { + dirinfo->currentcluster = 0; + dirinfo->currentsector = 0; + dirinfo->currententry = 0; + + // read first sector of directory + return DFS_ReadSector(volinfo->unit, dirinfo->scratch, volinfo->rootdir, 1); + } + } + + // This is not the root directory. We need to find the start of this subdirectory. + // We do this by devious means, using our own companion function DFS_GetNext. + else { + uint8_t tmpfn[12]; + uint8_t *ptr = dirname; + uint32_t result; + DIRENT de; + + if (volinfo->filesystem == FAT32) { + dirinfo->currentcluster = volinfo->rootdir; + dirinfo->currentsector = 0; + dirinfo->currententry = 0; + + // read first sector of directory + if (DFS_ReadSector(volinfo->unit, dirinfo->scratch, volinfo->dataarea + ((volinfo->rootdir - 2) * volinfo->secperclus), 1)) + return DFS_ERRMISC; + } + else { + dirinfo->currentcluster = 0; + dirinfo->currentsector = 0; + dirinfo->currententry = 0; + + // read first sector of directory + if (DFS_ReadSector(volinfo->unit, dirinfo->scratch, volinfo->rootdir, 1)) + return DFS_ERRMISC; + } + + // skip leading path separators + while (*ptr == DIR_SEPARATOR && *ptr) + ptr++; + + // Scan the path from left to right, finding the start cluster of each entry + // Observe that this code is inelegant, but obviates the need for recursion. + while (*ptr) { + DFS_CanonicalToDir(tmpfn, ptr); + + de.name[0] = 0; + + do { + result = DFS_GetNext(volinfo, dirinfo, &de); + } while (!result && memcmp(de.name, tmpfn, 11)); + + if (!memcmp(de.name, tmpfn, 11) && ((de.attr & ATTR_DIRECTORY) == ATTR_DIRECTORY)) { + if (volinfo->filesystem == FAT32) { + dirinfo->currentcluster = (uint32_t) de.startclus_l_l | + ((uint32_t) de.startclus_l_h) << 8 | + ((uint32_t) de.startclus_h_l) << 16 | + ((uint32_t) de.startclus_h_h) << 24; + } + else { + dirinfo->currentcluster = (uint32_t) de.startclus_l_l | + ((uint32_t) de.startclus_l_h) << 8; + } + dirinfo->currentsector = 0; + dirinfo->currententry = 0; + + if (DFS_ReadSector(volinfo->unit, dirinfo->scratch, volinfo->dataarea + ((dirinfo->currentcluster - 2) * volinfo->secperclus), 1)) + return DFS_ERRMISC; + } + else if (!memcmp(de.name, tmpfn, 11) && !(de.attr & ATTR_DIRECTORY)) + return DFS_NOTFOUND; + + // seek to next item in list + while (*ptr != DIR_SEPARATOR && *ptr) + ptr++; + if (*ptr == DIR_SEPARATOR) + ptr++; + } + + if (!dirinfo->currentcluster) + return DFS_NOTFOUND; + } + return DFS_OK; +} + +/* + Get next entry in opened directory structure. Copies fields into the dirent + structure, updates dirinfo. Note that it is the _caller's_ responsibility to + handle the '.' and '..' entries. + A deleted file will be returned as a NULL entry (first char of filename=0) + by this code. Filenames beginning with 0x05 will be translated to 0xE5 + automatically. Long file name entries will be returned as NULL. + returns DFS_EOF if there are no more entries, DFS_OK if this entry is valid, + or DFS_ERRMISC for a media error +*/ +uint32_t DFS_GetNext(PVOLINFO volinfo, PDIRINFO dirinfo, PDIRENT dirent) +{ + uint32_t tempint; // required by DFS_GetFAT + +#ifdef DEBUG_DOSFS + printf("DFS_GetNext\r\n"); +#endif + + // Do we need to read the next sector of the directory? + if (dirinfo->currententry >= SECTOR_SIZE / sizeof(DIRENT)) { + dirinfo->currententry = 0; + dirinfo->currentsector++; + + // Root directory; special case handling + // Note that currentcluster will only ever be zero if both: + // (a) this is the root directory, and + // (b) we are on a FAT12/16 volume, where the root dir can't be expanded + if (dirinfo->currentcluster == 0) { + // Trying to read past end of root directory? + if (dirinfo->currentsector * (SECTOR_SIZE / sizeof(DIRENT)) >= volinfo->rootentries) + return DFS_EOF; + + // Otherwise try to read the next sector + if (DFS_ReadSector(volinfo->unit, dirinfo->scratch, volinfo->rootdir + dirinfo->currentsector, 1)) + return DFS_ERRMISC; + } + + // Normal handling + else { + if (dirinfo->currentsector >= volinfo->secperclus) { + dirinfo->currentsector = 0; + if ((dirinfo->currentcluster >= 0xff7 && volinfo->filesystem == FAT12) || + (dirinfo->currentcluster >= 0xfff7 && volinfo->filesystem == FAT16) || + (dirinfo->currentcluster >= 0x0ffffff7 && volinfo->filesystem == FAT32)) { + + // We are at the end of the directory chain. If this is a normal + // find operation, we should indicate that there is nothing more + // to see. + if (!(dirinfo->flags & DFS_DI_BLANKENT)) + return DFS_EOF; + + // On the other hand, if this is a "find free entry" search, + // we need to tell the caller to allocate a new cluster + else + return DFS_ALLOCNEW; + } + dirinfo->currentcluster = DFS_GetFAT(volinfo, dirinfo->scratch, &tempint, dirinfo->currentcluster); + } + if (DFS_ReadSector(volinfo->unit, dirinfo->scratch, volinfo->dataarea + ((dirinfo->currentcluster - 2) * volinfo->secperclus) + dirinfo->currentsector, 1)) + return DFS_ERRMISC; + } + } + + memcpy(dirent, &(((PDIRENT) dirinfo->scratch)[dirinfo->currententry]), sizeof(DIRENT)); + + if (dirent->name[0] == 0) { // no more files in this directory + // If this is a "find blank" then we can reuse this name. +#if 0 + if (dirinfo->flags & DFS_DI_BLANKENT) + return DFS_OK; +#else + + // TK: DFS_GetFreeDirEnt() expects that currententry has been incremented by 1 + if (dirinfo->flags & DFS_DI_BLANKENT) { + dirinfo->currententry++; + return DFS_OK; + } +#endif + + else + return DFS_EOF; + } + + if (dirent->name[0] == 0xe5) // handle deleted file entries + dirent->name[0] = 0; +#if 1 + // TK: ensure that DFS_GetFreeDirEnt() doesn't return entries with long name + else if( dirinfo->flags & DFS_DI_BLANKENT ) + {} // do nothing.. +#endif + + else if ((dirent->attr & ATTR_LONG_NAME) == ATTR_LONG_NAME) + dirent->name[0] = 0; + else if (dirent->name[0] == 0x05) // handle kanji filenames beginning with 0xE5 + dirent->name[0] = 0xe5; + + dirinfo->currententry++; + + return DFS_OK; +} + +/* + INTERNAL + Find a free directory entry in the directory specified by path + This function MAY cause a disk write if it is necessary to extend the directory + size. + Note - di.scratch must be preinitialized to point to a sector scratch buffer + de is a scratch structure + Returns DFS_ERRMISC if a new entry could not be located or created + de is updated with the same return information you would expect from DFS_GetNext +*/ +uint32_t DFS_GetFreeDirEnt(PVOLINFO volinfo, uint8_t *path, PDIRINFO di, PDIRENT de) +{ + uint32_t tempclus=0,i=0; +#ifdef DEBUG_DOSFS + printf("DFS_GetFreeDirEnt\r\n"); +#endif + + if (DFS_OpenDir(volinfo, path, di)) + return DFS_NOTFOUND; + + // Set "search for empty" flag so DFS_GetNext knows what we're doing + di->flags |= DFS_DI_BLANKENT; + + // We seek through the directory looking for an empty entry + // Note we are reusing tempclus as a temporary result holder. + tempclus = 0; + do { + tempclus = DFS_GetNext(volinfo, di, de); + + // Empty entry found + if (tempclus == DFS_OK && (!de->name[0])) { + return DFS_OK; + } + + // End of root directory reached + else if (tempclus == DFS_EOF) + return DFS_ERRMISC; + + else if (tempclus == DFS_ALLOCNEW) { + tempclus = DFS_GetFreeFAT(volinfo, di->scratch); + if (tempclus == 0x0ffffff7) + return DFS_ERRMISC; + + // write out zeroed sectors to the new cluster + memset(di->scratch, 0, SECTOR_SIZE); + for (i=0;isecperclus;i++) { + if (DFS_WriteSector(volinfo->unit, di->scratch, volinfo->dataarea + ((tempclus - 2) * volinfo->secperclus) + i, 1)) + return DFS_ERRMISC; + } + // Point old end cluster to newly allocated cluster + i = 0; + DFS_SetFAT(volinfo, di->scratch, &i, di->currentcluster, tempclus); + + // Update DIRINFO so caller knows where to place the new file + di->currentcluster = tempclus; + di->currentsector = 0; + di->currententry = 1; // since the code coming after this expects to subtract 1 + + // Mark newly allocated cluster as end of chain + switch(volinfo->filesystem) { + case FAT12: tempclus = 0xff8; break; + case FAT16: tempclus = 0xfff8; break; + case FAT32: tempclus = 0x0ffffff8; break; + default: return DFS_ERRMISC; + } + DFS_SetFAT(volinfo, di->scratch, &i, di->currentcluster, tempclus); + } + } while (!tempclus); + + // We shouldn't get here + return DFS_ERRMISC; +} + +/* + Open a file for reading or writing. You supply populated VOLINFO, a path to the file, + mode (DFS_READ or DFS_WRITE) and an empty fileinfo structure. You also need to + provide a pointer to a sector-sized scratch buffer. + Returns various DFS_* error states. If the result is DFS_OK, fileinfo can be used + to access the file from this point on. +*/ +uint32_t DFS_OpenFile(PVOLINFO volinfo, uint8_t *path, uint8_t mode, uint8_t *scratch, PFILEINFO fileinfo) +{ + uint8_t tmppath[MAX_PATH]; + uint8_t filename[12]; + uint8_t *p; + DIRINFO di; + DIRENT de; + uint32_t temp; +#ifdef DEBUG_DOSFS + printf("DFS_OpenFile\r\n"); +#endif + + // larwe 2006-09-16 +1 zero out file structure + memset(fileinfo, 0, sizeof(FILEINFO)); + + // save access mode + fileinfo->mode = mode; + + // Get a local copy of the path. If it's longer than MAX_PATH, abort. + strncpy((char *) tmppath, (char *) path, MAX_PATH); + tmppath[MAX_PATH - 1] = 0; + if (strcmp((char *) path,(char *) tmppath)) { + return DFS_PATHLEN; + } + + // strip leading path separators + while (tmppath[0] == DIR_SEPARATOR) + strcpy((char *) tmppath, (char *) tmppath + 1); + + // Parse filename off the end of the supplied path + p = tmppath; + while (*(p++)); + + p--; + while (p > tmppath && *p != DIR_SEPARATOR) // larwe 9/16/06 ">=" to ">" bugfix + p--; + if (*p == DIR_SEPARATOR) + p++; + + DFS_CanonicalToDir(filename, p); + + if (p > tmppath) + p--; + if (*p == DIR_SEPARATOR || p == tmppath) // larwe 9/16/06 +"|| p == tmppath" bugfix + *p = 0; + + // At this point, if our path was MYDIR/MYDIR2/FILE.EXT, filename = "FILE EXT" and + // tmppath = "MYDIR/MYDIR2". + di.scratch = scratch; + if (DFS_OpenDir(volinfo, tmppath, &di)) + return DFS_NOTFOUND; + + while (!DFS_GetNext(volinfo, &di, &de)) { + if (!memcmp(de.name, filename, 11)) { + // You can't use this function call to open a directory. + if (de.attr & ATTR_DIRECTORY) + return DFS_NOTFOUND; + + fileinfo->volinfo = volinfo; + fileinfo->pointer = 0; + // The reason we store this extra info about the file is so that we can + // speedily update the file size, modification date, etc. on a file that is + // opened for writing. + if (di.currentcluster == 0) + fileinfo->dirsector = volinfo->rootdir + di.currentsector; + else + fileinfo->dirsector = volinfo->dataarea + ((di.currentcluster - 2) * volinfo->secperclus) + di.currentsector; + fileinfo->diroffset = di.currententry - 1; + if (volinfo->filesystem == FAT32) { + fileinfo->cluster = (uint32_t) de.startclus_l_l | + ((uint32_t) de.startclus_l_h) << 8 | + ((uint32_t) de.startclus_h_l) << 16 | + ((uint32_t) de.startclus_h_h) << 24; + } + else { + fileinfo->cluster = (uint32_t) de.startclus_l_l | + ((uint32_t) de.startclus_l_h) << 8; + } + fileinfo->firstcluster = fileinfo->cluster; + fileinfo->filelen = (uint32_t) de.filesize_0 | + ((uint32_t) de.filesize_1) << 8 | + ((uint32_t) de.filesize_2) << 16 | + ((uint32_t) de.filesize_3) << 24; + + return DFS_OK; + } + } + + // At this point, we KNOW the file does not exist. If the file was opened + // with write access, we can create it. + if (mode & DFS_WRITE) { + uint32_t cluster; + + // Locate or create a directory entry for this file + if (DFS_OK != DFS_GetFreeDirEnt(volinfo, tmppath, &di, &de)) + return DFS_ERRMISC; + + // put sane values in the directory entry + memset(&de, 0, sizeof(de)); + memcpy(de.name, filename, 11); + de.crttime_l = 0x20; // 01:01:00am, Jan 1, 2006. + de.crttime_h = 0x08; + de.crtdate_l = 0x11; + de.crtdate_h = 0x34; + de.lstaccdate_l = 0x11; + de.lstaccdate_h = 0x34; + de.wrttime_l = 0x20; + de.wrttime_h = 0x08; + de.wrtdate_l = 0x11; + de.wrtdate_h = 0x34; + + // allocate a starting cluster for the directory entry + cluster = DFS_GetFreeFAT(volinfo, scratch); + + de.startclus_l_l = cluster & 0xff; + de.startclus_l_h = (cluster & 0xff00) >> 8; + de.startclus_h_l = (cluster & 0xff0000) >> 16; + de.startclus_h_h = (cluster & 0xff000000) >> 24; + + // update FILEINFO for our caller's sake + fileinfo->volinfo = volinfo; + fileinfo->pointer = 0; + // The reason we store this extra info about the file is so that we can + // speedily update the file size, modification date, etc. on a file that is + // opened for writing. + if (di.currentcluster == 0) + fileinfo->dirsector = volinfo->rootdir + di.currentsector; + else + fileinfo->dirsector = volinfo->dataarea + ((di.currentcluster - 2) * volinfo->secperclus) + di.currentsector; + fileinfo->diroffset = di.currententry - 1; + fileinfo->cluster = cluster; + fileinfo->firstcluster = cluster; + fileinfo->filelen = 0; + + // write the directory entry + // note that we no longer have the sector containing the directory entry, + // tragically, so we have to re-read it + if (DFS_ReadSector(volinfo->unit, scratch, fileinfo->dirsector, 1)) + return DFS_ERRMISC; + memcpy(&(((PDIRENT) scratch)[di.currententry-1]), &de, sizeof(DIRENT)); + if (DFS_WriteSector(volinfo->unit, scratch, fileinfo->dirsector, 1)) + return DFS_ERRMISC; + + // Mark newly allocated cluster as end of chain + switch(volinfo->filesystem) { + case FAT12: cluster = 0xff8; break; + case FAT16: cluster = 0xfff8; break; + case FAT32: cluster = 0x0ffffff8; break; + default: return DFS_ERRMISC; + } + temp = 0; + DFS_SetFAT(volinfo, scratch, &temp, fileinfo->cluster, cluster); + + return DFS_OK; + } + + return DFS_NOTFOUND; +} + +/* + Read an open file + You must supply a prepopulated FILEINFO as provided by DFS_OpenFile, and a + pointer to a SECTOR_SIZE scratch buffer. + Note that returning DFS_EOF is not an error condition. This function updates the + successcount field with the number of bytes actually read. +*/ +uint32_t DFS_ReadFile(PFILEINFO fileinfo, uint8_t *scratch, uint8_t *buffer, uint32_t *successcount, uint32_t len) +{ + uint32_t remain=0; + uint32_t result = DFS_OK; + uint32_t sector=0; + uint32_t bytesread=0; +#ifdef DEBUG_DOSFS + printf("DFS_ReadFile\r\n"); +#endif + + // Don't try to read past EOF + if (len > fileinfo->filelen - fileinfo->pointer) + len = fileinfo->filelen - fileinfo->pointer; + + remain = len; + *successcount = 0; + + while (remain && result == DFS_OK) { + // This is a bit complicated. The sector we want to read is addressed at a cluster + // granularity by the fileinfo->cluster member. The file pointer tells us how many + // extra sectors to add to that number. + sector = fileinfo->volinfo->dataarea + + ((fileinfo->cluster - 2) * fileinfo->volinfo->secperclus) + + div(div(fileinfo->pointer,fileinfo->volinfo->secperclus * SECTOR_SIZE).rem, SECTOR_SIZE).quot; + + // Case 1 - File pointer is not on a sector boundary + if (div(fileinfo->pointer, SECTOR_SIZE).rem) { + uint16_t tempreadsize; + + // We always have to go through scratch in this case + result = DFS_ReadSector(fileinfo->volinfo->unit, scratch, sector, 1); + + // This is the number of bytes that we actually care about in the sector + // just read. + tempreadsize = SECTOR_SIZE - (div(fileinfo->pointer, SECTOR_SIZE).rem); + + // Case 1A - We want the entire remainder of the sector. After this + // point, all passes through the read loop will be aligned on a sector + // boundary, which allows us to go through the optimal path 2A below. + if (remain >= tempreadsize) { + memcpy(buffer, scratch + (SECTOR_SIZE - tempreadsize), tempreadsize); + bytesread = tempreadsize; + buffer += tempreadsize; + fileinfo->pointer += tempreadsize; + remain -= tempreadsize; + } + // Case 1B - This read concludes the file read operation + else { + memcpy(buffer, scratch + (SECTOR_SIZE - tempreadsize), remain); + + buffer += remain; + fileinfo->pointer += remain; + bytesread = remain; + remain = 0; + } + } + // Case 2 - File pointer is on sector boundary + else { + // Case 2A - We have at least one more full sector to read and don't have + // to go through the scratch buffer. You could insert optimizations here to + // read multiple sectors at a time, if you were thus inclined (note that + // the maximum multi-read you could perform is a single cluster, so it would + // be advantageous to have code similar to case 1A above that would round the + // pointer to a cluster boundary the first pass through, so all subsequent + // [large] read requests would be able to go a cluster at a time). + if (remain >= SECTOR_SIZE) { + result = DFS_ReadSector(fileinfo->volinfo->unit, buffer, sector, 1); + remain -= SECTOR_SIZE; + buffer += SECTOR_SIZE; + fileinfo->pointer += SECTOR_SIZE; + bytesread = SECTOR_SIZE; + } + // Case 2B - We are only reading a partial sector + else { + result = DFS_ReadSector(fileinfo->volinfo->unit, scratch, sector, 1); + memcpy(buffer, scratch, remain); + buffer += remain; + fileinfo->pointer += remain; + bytesread = remain; + remain = 0; + } + } + + *successcount += bytesread; + + // check to see if we stepped over a cluster boundary + if (div(fileinfo->pointer - bytesread, fileinfo->volinfo->secperclus * SECTOR_SIZE).quot != + div(fileinfo->pointer, fileinfo->volinfo->secperclus * SECTOR_SIZE).quot) { + // An act of minor evil - we use bytesread as a scratch integer, knowing that + // its value is not used after updating *successcount above + bytesread = 0; + if (((fileinfo->volinfo->filesystem == FAT12) && (fileinfo->cluster >= 0xff8)) || + ((fileinfo->volinfo->filesystem == FAT16) && (fileinfo->cluster >= 0xfff8)) || + ((fileinfo->volinfo->filesystem == FAT32) && (fileinfo->cluster >= 0x0ffffff8))) + result = DFS_EOF; + else + fileinfo->cluster = DFS_GetFAT(fileinfo->volinfo, scratch, &bytesread, fileinfo->cluster); + } + } + + return result; +} + +/* + Seek file pointer to a given position + This function does not return status - refer to the fileinfo->pointer value + to see where the pointer wound up. + Requires a SECTOR_SIZE scratch buffer +*/ +void DFS_Seek(PFILEINFO fileinfo, uint32_t offset, uint8_t *scratch) +{ + uint32_t tempint; + uint16_t endcluster=0; //canny/reza 5/7 fixed +#ifdef DEBUG_DOSFS + printf("DFS_Seek\r\n"); +#endif + + // larwe 9/16/06 bugfix split case 0a/0b and changed fallthrough handling + // Case 0a - Return immediately for degenerate case + if (offset == fileinfo->pointer) { + return; + } + + // Case 0b - Don't allow the user to seek past the end of the file + if (offset > fileinfo->filelen) { + offset = fileinfo->filelen; + // NOTE NO RETURN HERE! + } + + // Case 1 - Simple rewind to start + // Note _intentional_ fallthrough from Case 0b above + if (offset == 0) { + fileinfo->cluster = fileinfo->firstcluster; + fileinfo->pointer = 0; + return; // larwe 9/16/06 +1 bugfix + } + // Case 2 - Seeking backwards. Need to reset and seek forwards + else if (offset < fileinfo->pointer) { + fileinfo->cluster = fileinfo->firstcluster; + fileinfo->pointer = 0; + // NOTE NO RETURN HERE! + } + + // Case 3 - Seeking forwards + // Note _intentional_ fallthrough from Case 2 above + // Case 3a - Seek size does not cross cluster boundary - + // very simple case + // larwe 9/16/06 changed .rem to .quot in both div calls, bugfix + if (div(fileinfo->pointer, fileinfo->volinfo->secperclus * SECTOR_SIZE).quot == + div(fileinfo->pointer + offset, fileinfo->volinfo->secperclus * SECTOR_SIZE).quot) { + fileinfo->pointer = offset; + } + // Case 3b - Seeking across cluster boundary(ies) + else { + // round file pointer down to cluster boundary + fileinfo->pointer = div(fileinfo->pointer, fileinfo->volinfo->secperclus * SECTOR_SIZE).quot * + fileinfo->volinfo->secperclus * SECTOR_SIZE; + + // seek by clusters + // larwe 9/30/06 bugfix changed .rem to .quot in both div calls + // canny/reza 5/7 added endcluster related code + // TK 2008-12-18: fixed endcluster calculation + // old: endcluster = div(fileinfo->pointer + offset, fileinfo->volinfo->secperclus * SECTOR_SIZE).quot; + endcluster = div(offset, fileinfo->volinfo->secperclus * SECTOR_SIZE).quot; + while (div(fileinfo->pointer, fileinfo->volinfo->secperclus * SECTOR_SIZE).quot !=endcluster) { + fileinfo->cluster = DFS_GetFAT(fileinfo->volinfo, scratch, &tempint, fileinfo->cluster); + // Abort if there was an error + if (fileinfo->cluster == 0x0ffffff7) { + fileinfo->pointer = 0; + fileinfo->cluster = fileinfo->firstcluster; + return; + } + fileinfo->pointer += SECTOR_SIZE * fileinfo->volinfo->secperclus; + } + + // since we know the cluster is right, we have no more work to do + fileinfo->pointer = offset; + } +} + +/* + Delete a file + scratch must point to a sector-sized buffer +*/ +uint32_t DFS_UnlinkFile(PVOLINFO volinfo, uint8_t *path, uint8_t *scratch) +{ + // PDIRENT de = (PDIRENT) scratch; + FILEINFO fi; + uint32_t cache = 0; + uint32_t tempclus = 0; + +#ifdef DEBUG_DOSFS + printf("DFS_UnlinkFile\r\n"); +#endif + + // DFS_OpenFile gives us all the information we need to delete it + if (DFS_OK != DFS_OpenFile(volinfo, path, DFS_READ, scratch, &fi)) + return DFS_NOTFOUND; + + // First, read the directory sector and delete that entry + if (DFS_ReadSector(volinfo->unit, scratch, fi.dirsector, 1)) + return DFS_ERRMISC; + ((PDIRENT) scratch)[fi.diroffset].name[0] = 0xe5; + if (DFS_WriteSector(volinfo->unit, scratch, fi.dirsector, 1)) + return DFS_ERRMISC; + + // Now follow the cluster chain to free the file space + while (!((volinfo->filesystem == FAT12 && fi.firstcluster >= 0x0ff7) || + (volinfo->filesystem == FAT16 && fi.firstcluster >= 0xfff7) || + (volinfo->filesystem == FAT32 && fi.firstcluster >= 0x0ffffff7))) { + tempclus = fi.firstcluster; + + fi.firstcluster = DFS_GetFAT(volinfo, scratch, &cache, fi.firstcluster); + DFS_SetFAT(volinfo, scratch, &cache, tempclus, 0); + + } + return DFS_OK; +} + + +/* + Write an open file + You must supply a prepopulated FILEINFO as provided by DFS_OpenFile, and a + pointer to a SECTOR_SIZE scratch buffer. + This function updates the successcount field with the number of bytes actually written. +*/ +uint32_t DFS_WriteFile(PFILEINFO fileinfo, uint8_t *scratch, uint8_t *buffer, uint32_t *successcount, uint32_t len) +{ + uint32_t remain=0; + uint32_t result = DFS_OK; + uint32_t sector=0; + uint32_t byteswritten=0; +#ifdef DEBUG_DOSFS + printf("DFS_WriteFile\r\n"); +#endif + + + // Don't allow writes to a file that's open as readonly + if (!(fileinfo->mode & DFS_WRITE)) + return DFS_ERRMISC; + + remain = len; + *successcount = 0; + + while (remain && result == DFS_OK) { + // This is a bit complicated. The sector we want to read is addressed at a cluster + // granularity by the fileinfo->cluster member. The file pointer tells us how many + // extra sectors to add to that number. + sector = fileinfo->volinfo->dataarea + + ((fileinfo->cluster - 2) * fileinfo->volinfo->secperclus) + + div(div(fileinfo->pointer,fileinfo->volinfo->secperclus * SECTOR_SIZE).rem, SECTOR_SIZE).quot; + + // Case 1 - File pointer is not on a sector boundary + if (div(fileinfo->pointer, SECTOR_SIZE).rem) { + uint16_t tempsize; + + // We always have to go through scratch in this case + result = DFS_ReadSector(fileinfo->volinfo->unit, scratch, sector, 1); + + // This is the number of bytes that we don't want to molest in the + // scratch sector just read. + tempsize = div(fileinfo->pointer, SECTOR_SIZE).rem; + + // Case 1A - We are writing the entire remainder of the sector. After + // this point, all passes through the read loop will be aligned on a + // sector boundary, which allows us to go through the optimal path + // 2A below. + if (remain >= SECTOR_SIZE - tempsize) { + memcpy(scratch + tempsize, buffer, SECTOR_SIZE - tempsize); + if (!result) + result = DFS_WriteSector(fileinfo->volinfo->unit, scratch, sector, 1); + + byteswritten = SECTOR_SIZE - tempsize; + buffer += SECTOR_SIZE - tempsize; + fileinfo->pointer += SECTOR_SIZE - tempsize; + if (fileinfo->filelen < fileinfo->pointer) { + fileinfo->filelen = fileinfo->pointer; + } + remain -= SECTOR_SIZE - tempsize; + } + // Case 1B - This concludes the file write operation + else { + memcpy(scratch + tempsize, buffer, remain); + if (!result) + result = DFS_WriteSector(fileinfo->volinfo->unit, scratch, sector, 1); + + buffer += remain; + fileinfo->pointer += remain; + if (fileinfo->filelen < fileinfo->pointer) { + fileinfo->filelen = fileinfo->pointer; + } + byteswritten = remain; + remain = 0; + } + } // case 1 + // Case 2 - File pointer is on sector boundary + else { + // Case 2A - We have at least one more full sector to write and don't have + // to go through the scratch buffer. You could insert optimizations here to + // write multiple sectors at a time, if you were thus inclined. Refer to + // similar notes in DFS_ReadFile. + if (remain >= SECTOR_SIZE) { + result = DFS_WriteSector(fileinfo->volinfo->unit, buffer, sector, 1); + remain -= SECTOR_SIZE; + buffer += SECTOR_SIZE; + fileinfo->pointer += SECTOR_SIZE; + if (fileinfo->filelen < fileinfo->pointer) { + fileinfo->filelen = fileinfo->pointer; + } + byteswritten = SECTOR_SIZE; + } + // Case 2B - We are only writing a partial sector and potentially need to + // go through the scratch buffer. + else { + // If the current file pointer is not yet at or beyond the file + // length, we are writing somewhere in the middle of the file and + // need to load the original sector to do a read-modify-write. + if (fileinfo->pointer < fileinfo->filelen) { + result = DFS_ReadSector(fileinfo->volinfo->unit, scratch, sector, 1); + if (!result) { + memcpy(scratch, buffer, remain); + result = DFS_WriteSector(fileinfo->volinfo->unit, scratch, sector, 1); + } + } + else { + result = DFS_WriteSector(fileinfo->volinfo->unit, buffer, sector, 1); + } + + buffer += remain; + fileinfo->pointer += remain; + if (fileinfo->filelen < fileinfo->pointer) { + fileinfo->filelen = fileinfo->pointer; + } + byteswritten = remain; + remain = 0; + } + } + + *successcount += byteswritten; + + // check to see if we stepped over a cluster boundary + if (div(fileinfo->pointer - byteswritten, fileinfo->volinfo->secperclus * SECTOR_SIZE).quot != + div(fileinfo->pointer, fileinfo->volinfo->secperclus * SECTOR_SIZE).quot) { + uint32_t lastcluster; + + // We've transgressed into another cluster. If we were already at EOF, + // we need to allocate a new cluster. + // An act of minor evil - we use byteswritten as a scratch integer, knowing + // that its value is not used after updating *successcount above + byteswritten = 0; + + lastcluster = fileinfo->cluster; + fileinfo->cluster = DFS_GetFAT(fileinfo->volinfo, scratch, &byteswritten, fileinfo->cluster); + + // Allocate a new cluster? + if (((fileinfo->volinfo->filesystem == FAT12) && (fileinfo->cluster >= 0xff8)) || + ((fileinfo->volinfo->filesystem == FAT16) && (fileinfo->cluster >= 0xfff8)) || + ((fileinfo->volinfo->filesystem == FAT32) && (fileinfo->cluster >= 0x0ffffff8))) { + uint32_t tempclus; + + tempclus = DFS_GetFreeFAT(fileinfo->volinfo, scratch); + byteswritten = 0; // invalidate cache + if (tempclus == 0x0ffffff7) + return DFS_ERRMISC; + + // Link new cluster onto file + DFS_SetFAT(fileinfo->volinfo, scratch, &byteswritten, lastcluster, tempclus); + fileinfo->cluster = tempclus; + + // Mark newly allocated cluster as end of chain + switch(fileinfo->volinfo->filesystem) { + case FAT12: tempclus = 0xff8; break; + case FAT16: tempclus = 0xfff8; break; + case FAT32: tempclus = 0x0ffffff8; break; + default: return DFS_ERRMISC; + } + DFS_SetFAT(fileinfo->volinfo, scratch, &byteswritten, fileinfo->cluster, tempclus); + + result = DFS_OK; + } + // No else clause is required. + } + } + + // Update directory entry + if (DFS_ReadSector(fileinfo->volinfo->unit, scratch, fileinfo->dirsector, 1)) + return DFS_ERRMISC; + ((PDIRENT) scratch)[fileinfo->diroffset].filesize_0 = fileinfo->filelen & 0xff; + ((PDIRENT) scratch)[fileinfo->diroffset].filesize_1 = (fileinfo->filelen & 0xff00) >> 8; + ((PDIRENT) scratch)[fileinfo->diroffset].filesize_2 = (fileinfo->filelen & 0xff0000) >> 16; + ((PDIRENT) scratch)[fileinfo->diroffset].filesize_3 = (fileinfo->filelen & 0xff000000) >> 24; + if (DFS_WriteSector(fileinfo->volinfo->unit, scratch, fileinfo->dirsector, 1)) + return DFS_ERRMISC; + return result; +} + + +/* +// TK: added 2009-02-12 + Close a file + No original function of DosFS driver + It has no effect if writing to SD Card, it's only used by the DosFS wrapper in emulation +*/ +uint32_t DFS_Close(PFILEINFO fileinfo) +{ + return DFS_OK; +} + diff --git a/flight/PiOS/Common/Libraries/dosfs/dosfs.h b/flight/PiOS/Common/Libraries/dosfs/dosfs.h new file mode 100644 index 000000000..dfea6c374 --- /dev/null +++ b/flight/PiOS/Common/Libraries/dosfs/dosfs.h @@ -0,0 +1,405 @@ +/* + DOSFS Embedded FAT-Compatible Filesystem + (C) 2005 Lewin A.R.W. Edwards (sysadm@zws.com) +*/ + +#ifndef _DOSFS_H +#define _DOSFS_H + + +#include + +//=================================================================== +// User-supplied functions +uint32_t DFS_ReadSector(uint8_t unit, uint8_t *buffer, uint32_t sector, uint32_t count); +uint32_t DFS_WriteSector(uint8_t unit, uint8_t *buffer, uint32_t sector, uint32_t count); + + +//=================================================================== +// Configurable items +#define MAX_PATH 64 // Maximum path length (increasing this will + // GREATLY increase stack requirements!) +#define DIR_SEPARATOR '/' // character separating directory components + +// End of configurable items +//=================================================================== + +//=================================================================== +// 32-bit error codes +#define DFS_OK 0 // no error +#define DFS_EOF 1 // end of file (not an error) +#define DFS_WRITEPROT 2 // volume is write protected +#define DFS_NOTFOUND 3 // path or file not found +#define DFS_PATHLEN 4 // path too long +#define DFS_ALLOCNEW 5 // must allocate new directory cluster +#define DFS_ERRMISC 0xffffffff // generic error + +//=================================================================== +// File access modes +#define DFS_READ 1 // read-only +#define DFS_WRITE 2 // write-only + +//=================================================================== +// Miscellaneous constants +#define SECTOR_SIZE 512 // sector size in bytes + +//=================================================================== +// Internal subformat identifiers +#define FAT12 0 +#define FAT16 1 +#define FAT32 2 + +//=================================================================== +// DOS attribute bits +#define ATTR_READ_ONLY 0x01 +#define ATTR_HIDDEN 0x02 +#define ATTR_SYSTEM 0x04 +#define ATTR_VOLUME_ID 0x08 +#define ATTR_DIRECTORY 0x10 +#define ATTR_ARCHIVE 0x20 +#define ATTR_LONG_NAME (ATTR_READ_ONLY | ATTR_HIDDEN | ATTR_SYSTEM | ATTR_VOLUME_ID) + + +/* + Directory entry structure + note: if name[0] == 0xe5, this is a free dir entry + if name[0] == 0x00, this is a free entry and all subsequent entries are free + if name[0] == 0x05, the first character of the name is 0xe5 [a kanji nicety] + + Date format: bit 0-4 = day of month (1-31) + bit 5-8 = month, 1=Jan..12=Dec + bit 9-15 = count of years since 1980 (0-127) + Time format: bit 0-4 = 2-second count, (0-29) + bit 5-10 = minutes (0-59) + bit 11-15= hours (0-23) +*/ +typedef struct _tagDIRENT { + uint8_t name[11]; // filename + uint8_t attr; // attributes (see ATTR_* constant definitions) + uint8_t reserved; // reserved, must be 0 + uint8_t crttimetenth; // create time, 10ths of a second (0-199 are valid) + uint8_t crttime_l; // creation time low byte + uint8_t crttime_h; // creation time high byte + uint8_t crtdate_l; // creation date low byte + uint8_t crtdate_h; // creation date high byte + uint8_t lstaccdate_l; // last access date low byte + uint8_t lstaccdate_h; // last access date high byte + uint8_t startclus_h_l; // high word of first cluster, low byte (FAT32) + uint8_t startclus_h_h; // high word of first cluster, high byte (FAT32) + uint8_t wrttime_l; // last write time low byte + uint8_t wrttime_h; // last write time high byte + uint8_t wrtdate_l; // last write date low byte + uint8_t wrtdate_h; // last write date high byte + uint8_t startclus_l_l; // low word of first cluster, low byte + uint8_t startclus_l_h; // low word of first cluster, high byte + uint8_t filesize_0; // file size, low byte + uint8_t filesize_1; // + uint8_t filesize_2; // + uint8_t filesize_3; // file size, high byte +} DIRENT, *PDIRENT; + +/* + Partition table entry structure +*/ +typedef struct _tagPTINFO { + uint8_t active; // 0x80 if partition active + uint8_t start_h; // starting head + uint8_t start_cs_l; // starting cylinder and sector (low byte) + uint8_t start_cs_h; // starting cylinder and sector (high byte) + uint8_t type; // type ID byte + uint8_t end_h; // ending head + uint8_t end_cs_l; // ending cylinder and sector (low byte) + uint8_t end_cs_h; // ending cylinder and sector (high byte) + uint8_t start_0; // starting sector# (low byte) + uint8_t start_1; // + uint8_t start_2; // + uint8_t start_3; // starting sector# (high byte) + uint8_t size_0; // size of partition (low byte) + uint8_t size_1; // + uint8_t size_2; // + uint8_t size_3; // size of partition (high byte) +} PTINFO, *PPTINFO; + +/* + Master Boot Record structure +*/ +typedef struct _tagMBR { + uint8_t bootcode[0x1be]; // boot sector + PTINFO ptable[4]; // four partition table structures + uint8_t sig_55; // 0x55 signature byte + uint8_t sig_aa; // 0xaa signature byte +} MBR, *PMBR; + +/* + BIOS Parameter Block structure (FAT12/16) +*/ +typedef struct _tagBPB { + uint8_t bytepersec_l; // bytes per sector low byte (0x00) + uint8_t bytepersec_h; // bytes per sector high byte (0x02) + uint8_t secperclus; // sectors per cluster (1,2,4,8,16,32,64,128 are valid) + uint8_t reserved_l; // reserved sectors low byte + uint8_t reserved_h; // reserved sectors high byte + uint8_t numfats; // number of FAT copies (2) + uint8_t rootentries_l; // number of root dir entries low byte (0x00 normally) + uint8_t rootentries_h; // number of root dir entries high byte (0x02 normally) + uint8_t sectors_s_l; // small num sectors low byte + uint8_t sectors_s_h; // small num sectors high byte + uint8_t mediatype; // media descriptor byte + uint8_t secperfat_l; // sectors per FAT low byte + uint8_t secperfat_h; // sectors per FAT high byte + uint8_t secpertrk_l; // sectors per track low byte + uint8_t secpertrk_h; // sectors per track high byte + uint8_t heads_l; // heads low byte + uint8_t heads_h; // heads high byte + uint8_t hidden_0; // hidden sectors low byte + uint8_t hidden_1; // (note - this is the number of MEDIA sectors before + uint8_t hidden_2; // first sector of VOLUME - we rely on the MBR instead) + uint8_t hidden_3; // hidden sectors high byte + uint8_t sectors_l_0; // large num sectors low byte + uint8_t sectors_l_1; // + uint8_t sectors_l_2; // + uint8_t sectors_l_3; // large num sectors high byte +} BPB, *PBPB; + +/* + Extended BIOS Parameter Block structure (FAT12/16) +*/ +typedef struct _tagEBPB { + uint8_t unit; // int 13h drive# + uint8_t head; // archaic, used by Windows NT-class OSes for flags + uint8_t signature; // 0x28 or 0x29 + uint8_t serial_0; // serial# + uint8_t serial_1; // serial# + uint8_t serial_2; // serial# + uint8_t serial_3; // serial# + uint8_t label[11]; // volume label + uint8_t system[8]; // filesystem ID +} EBPB, *PEBPB; + +/* + Extended BIOS Parameter Block structure (FAT32) +*/ +typedef struct _tagEBPB32 { + uint8_t fatsize_0; // big FAT size in sectors low byte + uint8_t fatsize_1; // + uint8_t fatsize_2; // + uint8_t fatsize_3; // big FAT size in sectors high byte + uint8_t extflags_l; // extended flags low byte + uint8_t extflags_h; // extended flags high byte + uint8_t fsver_l; // filesystem version (0x00) low byte + uint8_t fsver_h; // filesystem version (0x00) high byte + uint8_t root_0; // cluster of root dir, low byte + uint8_t root_1; // + uint8_t root_2; // + uint8_t root_3; // cluster of root dir, high byte + uint8_t fsinfo_l; // sector pointer to FSINFO within reserved area, low byte (2) + uint8_t fsinfo_h; // sector pointer to FSINFO within reserved area, high byte (0) + uint8_t bkboot_l; // sector pointer to backup boot sector within reserved area, low byte (6) + uint8_t bkboot_h; // sector pointer to backup boot sector within reserved area, high byte (0) + uint8_t reserved[12]; // reserved, should be 0 + + uint8_t unit; // int 13h drive# + uint8_t head; // archaic, used by Windows NT-class OSes for flags + uint8_t signature; // 0x28 or 0x29 + uint8_t serial_0; // serial# + uint8_t serial_1; // serial# + uint8_t serial_2; // serial# + uint8_t serial_3; // serial# + uint8_t label[11]; // volume label + uint8_t system[8]; // filesystem ID +} EBPB32, *PEBPB32; + +/* + Logical Boot Record structure (volume boot sector) +*/ +typedef struct _tagLBR { + uint8_t jump[3]; // JMP instruction + uint8_t oemid[8]; // OEM ID, space-padded + BPB bpb; // BIOS Parameter Block + union { + EBPB ebpb; // FAT12/16 Extended BIOS Parameter Block + EBPB32 ebpb32; // FAT32 Extended BIOS Parameter Block + } ebpb; + uint8_t code[420]; // boot sector code + uint8_t sig_55; // 0x55 signature byte + uint8_t sig_aa; // 0xaa signature byte +} LBR, *PLBR; + +/* + Volume information structure (Internal to DOSFS) +*/ +typedef struct _tagVOLINFO { + uint8_t unit; // unit on which this volume resides + uint8_t filesystem; // formatted filesystem + +// These two fields aren't very useful, so support for them has been commented out to +// save memory. (Note that the "system" tag is not actually used by DOS to determine +// filesystem type - that decision is made entirely on the basis of how many clusters +// the drive contains. DOSFS works the same way). +// See tag: OEMID in dosfs.c +// uint8_t oemid[9]; // OEM ID ASCIIZ +// uint8_t system[9]; // system ID ASCIIZ + uint8_t label[12]; // volume label ASCIIZ + uint32_t startsector; // starting sector of filesystem + uint8_t secperclus; // sectors per cluster + uint16_t reservedsecs; // reserved sectors + uint32_t numsecs; // number of sectors in volume + uint32_t secperfat; // sectors per FAT + uint16_t rootentries; // number of root dir entries + + uint32_t numclusters; // number of clusters on drive + + // The fields below are PHYSICAL SECTOR NUMBERS. + uint32_t fat1; // starting sector# of FAT copy 1 + uint32_t rootdir; // starting sector# of root directory (FAT12/FAT16) or cluster (FAT32) + uint32_t dataarea; // starting sector# of data area (cluster #2) +} VOLINFO, *PVOLINFO; + +/* + Flags in DIRINFO.flags +*/ +#define DFS_DI_BLANKENT 0x01 // Searching for blank entry + +/* + Directory search structure (Internal to DOSFS) +*/ +typedef struct _tagDIRINFO { + uint32_t currentcluster; // current cluster in dir + uint8_t currentsector; // current sector in cluster + uint8_t currententry; // current dir entry in sector + uint8_t *scratch; // ptr to user-supplied scratch buffer (one sector) + uint8_t flags; // internal DOSFS flags +} DIRINFO, *PDIRINFO; + +/* + File handle structure (Internal to DOSFS) +*/ +typedef struct _tagFILEINFO { + PVOLINFO volinfo; // VOLINFO used to open this file + uint32_t dirsector; // physical sector containing dir entry of this file + uint8_t diroffset; // # of this entry within the dir sector + uint8_t mode; // mode in which this file was opened + uint32_t firstcluster; // first cluster of file + uint32_t filelen; // byte length of file + + uint32_t cluster; // current cluster + uint32_t pointer; // current (BYTE) pointer +} FILEINFO, *PFILEINFO; + +/* + Get starting sector# of specified partition on drive #unit + NOTE: This code ASSUMES an MBR on the disk. + scratchsector should point to a SECTOR_SIZE scratch area + Returns 0xffffffff for any error. + If pactive is non-NULL, this function also returns the partition active flag. + If pptype is non-NULL, this function also returns the partition type. + If psize is non-NULL, this function also returns the partition size. +*/ +uint32_t DFS_GetPtnStart(uint8_t unit, uint8_t *scratchsector, uint8_t pnum, uint8_t *pactive, uint8_t *pptype, uint32_t *psize); + +/* + Retrieve volume info from BPB and store it in a VOLINFO structure + You must provide the unit and starting sector of the filesystem, and + a pointer to a sector buffer for scratch + Attempts to read BPB and glean information about the FS from that. + Returns 0 OK, nonzero for any error. +*/ +uint32_t DFS_GetVolInfo(uint8_t unit, uint8_t *scratchsector, uint32_t startsector, PVOLINFO volinfo); + +/* + Open a directory for enumeration by DFS_GetNextDirEnt + You must supply a populated VOLINFO (see DFS_GetVolInfo) + The empty string or a string containing only the directory separator are + considered to be the root directory. + Returns 0 OK, nonzero for any error. +*/ +uint32_t DFS_OpenDir(PVOLINFO volinfo, uint8_t *dirname, PDIRINFO dirinfo); + +/* + Get next entry in opened directory structure. Copies fields into the dirent + structure, updates dirinfo. Note that it is the _caller's_ responsibility to + handle the '.' and '..' entries. + A deleted file will be returned as a NULL entry (first char of filename=0) + by this code. Filenames beginning with 0x05 will be translated to 0xE5 + automatically. Long file name entries will be returned as NULL. + returns DFS_EOF if there are no more entries, DFS_OK if this entry is valid, + or DFS_ERRMISC for a media error +*/ +uint32_t DFS_GetNext(PVOLINFO volinfo, PDIRINFO dirinfo, PDIRENT dirent); + +/* + Open a file for reading or writing. You supply populated VOLINFO, a path to the file, + mode (DFS_READ or DFS_WRITE) and an empty fileinfo structure. You also need to + provide a pointer to a sector-sized scratch buffer. + Returns various DFS_* error states. If the result is DFS_OK, fileinfo can be used + to access the file from this point on. +*/ +uint32_t DFS_OpenFile(PVOLINFO volinfo, uint8_t *path, uint8_t mode, uint8_t *scratch, PFILEINFO fileinfo); + +/* + Read an open file + You must supply a prepopulated FILEINFO as provided by DFS_OpenFile, and a + pointer to a SECTOR_SIZE scratch buffer. + Note that returning DFS_EOF is not an error condition. This function updates the + successcount field with the number of bytes actually read. +*/ +uint32_t DFS_ReadFile(PFILEINFO fileinfo, uint8_t *scratch, uint8_t *buffer, uint32_t *successcount, uint32_t len); + +/* + Write an open file + You must supply a prepopulated FILEINFO as provided by DFS_OpenFile, and a + pointer to a SECTOR_SIZE scratch buffer. + This function updates the successcount field with the number of bytes actually written. +*/ +uint32_t DFS_WriteFile(PFILEINFO fileinfo, uint8_t *scratch, uint8_t *buffer, uint32_t *successcount, uint32_t len); + +/* + Seek file pointer to a given position + This function does not return status - refer to the fileinfo->pointer value + to see where the pointer wound up. + Requires a SECTOR_SIZE scratch buffer +*/ +void DFS_Seek(PFILEINFO fileinfo, uint32_t offset, uint8_t *scratch); + +/* + Delete a file + scratch must point to a sector-sized buffer +*/ +uint32_t DFS_UnlinkFile(PVOLINFO volinfo, uint8_t *path, uint8_t *scratch); + +/* + Fetch FAT entry for specified cluster number + You must provide a scratch buffer for one sector (SECTOR_SIZE) and a populated VOLINFO + Returns a FAT32 BAD_CLUSTER value for any error, otherwise the contents of the desired + FAT entry. + scratchcache should point to a UINT32. This variable caches the physical sector number + last read into the scratch buffer for performance enhancement reasons. +*/ +uint32_t DFS_GetFAT(PVOLINFO volinfo, uint8_t *scratch, uint32_t *scratchcache, uint32_t cluster); + +/* +// TK: added 2009-02-12 + Close a file + No original function of DosFS driver + It has no effect if writing to SD Card, it's only used by the DosFS wrapper in emulation +*/ +uint32_t DFS_Close(PFILEINFO fileinfo); + + + +// TK: added 2008-18-12 +// for caching - this feature has to be explicitely enabled, as it isn't reentrant +// and requires to use the same buffer pointer whenever reading a file +void DFS_CachingEnabledSet(uint8_t enable); + +// TK: added 2008-18-12 +// missing pendant to DFS_CanonicalToDir +char *DFS_DirToCanonical(char *dest, char *src); + + +// If we are building a host-emulation version, include host support +#ifdef HOSTVER +#include "hostemu.h" +#endif + +#endif // _DOSFS_H diff --git a/flight/PiOS/Common/Libraries/dosfs/library.mk b/flight/PiOS/Common/Libraries/dosfs/library.mk new file mode 100644 index 000000000..83e618cb5 --- /dev/null +++ b/flight/PiOS/Common/Libraries/dosfs/library.mk @@ -0,0 +1,8 @@ +# +# Rules to add DOSFS to a PiOS target +# + +DOSFS_DIR := $(dir $(lastword $(MAKEFILE_LIST))) +SRC += $(wildcard $(DOSFS_DIR)/*.c) +EXTRAINCDIRS += $(DOSFS_DIR) + diff --git a/flight/PiOS/Common/Libraries/msheap/library.mk b/flight/PiOS/Common/Libraries/msheap/library.mk new file mode 100644 index 000000000..de7ca06f6 --- /dev/null +++ b/flight/PiOS/Common/Libraries/msheap/library.mk @@ -0,0 +1,8 @@ +# +# Rules to add the MSHeap allocator to a PiOS target +# + +MSHEAP_DIR := $(dir $(lastword $(MAKEFILE_LIST))) +SRC += $(wildcard $(MSHEAP_DIR)*.c) +EXTRAINCDIRS += $(MSHEAP_DIR) + diff --git a/flight/PiOS/Common/Libraries/msheap/msheap.c b/flight/PiOS/Common/Libraries/msheap/msheap.c new file mode 100644 index 000000000..8c86eb45f --- /dev/null +++ b/flight/PiOS/Common/Libraries/msheap/msheap.c @@ -0,0 +1,578 @@ +/* -*- Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- */ +/*- + * MSHEAP + * + * A compact, low-overhead heap implementation with configurable + * integrity checking. + * + * Copyright 2011 Michael Smith. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above + * copyright notice, this list of conditions and the following + * disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials + * provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDER ''AS IS'' AND ANY + * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT + * OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + */ + +#include "msheap.h" + +/* + * Integrity checking. + * + * The HEAP_CHECK_LEVEL define determines the level of heap and + * argument integrity checking that will be performed. + * + * Higher checking levels include all the checks from lower levels. + * + * 0 : Pointers passed to msheap_free are checked; this will + * detect overflowing of the freed region and overflows from + * adjacent regions into the freed region. + * msheap_panic() is called if an overflow is detected. + * + * 1 : Heap elements are checked during msheap_alloc(); this will + * detect overflowing of any region that is seen during the + * allocation. + * msheap_panic() is called if an overflow is detected. + * + * 2 : msheap_panic() is called with more informative diagnostics + * including the test that failed. + * + * 3 : The entire heap is checked on every call to msheap_alloc() + * and msheap_free(). This will detect overflowing of any + * region. + * Every argument is checked before use. + * Regions are checked after operations. + * + * -1: No integrity checking of any sort is performed. + * + * HEAP_CHECK_LEVEL defaults to 2 if DEBUG is defined, or 0 + * otherwise. + */ +#ifndef HEAP_CHECK_LEVEL +# ifdef DEBUG +# define HEAP_CHECK_LEVEL 2 +# else +# define HEAP_CHECK_LEVEL 0 +# endif +#endif + +/** + * Utility debug/checking macro. + * + * @param _expr Expression to evaluate. Calls msheap_panic if the + * evaluation returns false. + * @param _str String to pass to msheap_panic. + * @return Zero, but only if _expr evaluates true. + */ +#define __ASSERT(_expr, _str) \ + ({ \ + int _a __attribute__((unused)) = 0; \ + if (!(_expr)) \ + msheap_panic(_str); \ + _a; \ + }) + +/** canonical macro weirdness */ +#define __STR(_x) # _x + +/* at level 2+, add the expression string and line number */ +#if HEAP_CHECK_LEVEL >= 2 +# define __ASSERT_FMT(_expr, _line, _str) __ASSERT(_expr, "heap assertion failed @" __STR(_line) ": " _str) +#else +# define __ASSERT_FMT(_expr, _line, _str) __ASSERT(_expr, "heap assertion failed") +#endif + +/** + * Assert if HEAP_CHECK_LEVEL >= _level and _expr evaluates false + * + * @param _level The lowest HEAP_CHECK_LEVEL at which this assertion should be tested. + * @param _expr The expression to test. + */ +#define ASSERT(_level, _expr) (void)((HEAP_CHECK_LEVEL < _level) || __ASSERT_FMT(_expr, __LINE__, #_expr)) + +/** + * Assert if HEAP_CHECK_LEVEL >= _level and _expr evaluates false, return test result otherwise. + * + * @param _level The lowest HEAP_CHECK_LEVEL at which to assert. + * @param _expr The expression to test. + * @return 1 if _expr evaluates false, 0 otherwise. + */ +#define ASSERT_TEST(_level, _expr) \ + ({ \ + ASSERT(_level, _expr); \ + (_expr) ? 0 : 1; \ + }) + + +/* + * The heap consists of ranges (free or allocated) separated and + * bounded by markers. + * + * For maximum space efficiency, the default is to use 4-byte + * 'compact' markers, which limits the heap to a maxium of 128KiB. + * For larger heaps define HEAP_SUPPORT_LARGE, which doubles markers + * to 8 bytes each, but allows heaps up to 2^^33 bytes in size. + * + * Each marker contains two structures, one describing the previous + * region and one describing the next. Thus, markers form a + * doubly-linked list chaining each region together. + * + * Each region is described by two identical structures, providing + * a measure of referential integrity that can be used to detect + * overflows out of the region without the use of separate magic + * numbers. + * + * The region descriptor size includes the size of the marker at its + * head. This means that zero is not a legal marker value. + * + * Free regions are always coalesced, and a pointer is kept to the + * most recently-created free region to accelerate allocation in the + * common case where a large number of free objects are allocated + * early. + * + * The heap is bounded by markers pointing to zero-sized allocated + * ranges, so they can never be merged. + */ +#ifdef HEAP_SUPPORT_LARGE + +struct region_descriptor { + uint32_t size:31; /* size of the region (including marker) in multiples of the marker size */ + uint32_t free:1; /* if nonzero, region is free */ +}; +static const uint32_t max_free = 0x7fffffff; + +#else /* !HEAP_SUPPORT_LARGE */ + +struct region_descriptor { + uint16_t size:15; /* size of the region (including marker) in multiples of the marker size */ + uint16_t free:1; /* if nonzero, region is free */ +}; +static const uint32_t max_free = 0x7fff; + +#endif /* HEAP_SUPPORT_LARGE */ + +/** + * The marker placed between regions. + * + * Allocations are aligned and rounded to the size of this structure. + */ +struct marker { + struct region_descriptor prev; + struct region_descriptor next; +}; + +typedef struct marker *marker_t; +static const uintptr_t marker_size = sizeof(struct marker); + +/* heap boundaries */ +static marker_t heap_base; +static marker_t heap_limit; +static uint32_t heap_free; +static marker_t free_hint; /* likely free region, or heap_base if no free region hint */ + +/* rounding macros for powers of 2 */ +#define round_down(_val, _boundary) ((_val) & ~(_boundary - 1)) +#define round_up(_val, _boundary) round_down((_val) + (_boundary) - 1, _boundary) + +/* default panic handler */ +void msheap_panic(const char *reason) __attribute__((weak, noreturn)); + +static int region_check(marker_t marker); +static void split_region(marker_t marker, uint32_t size); +static void merge_region(marker_t marker); + +/** + * Initialise the heap. + * + * @param base The lower boundary of the heap. + * @param limit The upper boundary of the heap. + */ +void +msheap_init(void *base, void *limit) +{ + heap_base = (marker_t)round_up((uintptr_t)base, marker_size); + heap_limit = (marker_t)round_down((uintptr_t)limit, marker_size) - 1; + + ASSERT(3, heap_base); /* must not be NULL */ + ASSERT(3, heap_limit); /* must not be NULL */ + ASSERT(3, heap_limit > heap_base); /* limit must be above base */ + + /* Initial size of the free region (includes the heap_base marker) */ + heap_free = heap_limit - heap_base; + ASSERT(0, heap_free <= max_free); /* heap must not be too large */ + ASSERT(3, heap_free > 1); /* heap must be at least 1 marker in size */ + + /* + * Initialise the base and limit markers. + */ + heap_base->prev.size = 0; + heap_base->prev.free = 0; + heap_base->next.size = heap_free; + heap_base->next.free = 1; + heap_limit->prev.size = heap_free; + heap_limit->prev.free = 1; + heap_limit->next.size = 0; + heap_limit->next.free = 0; + + free_hint = heap_base; /* a good place to start ... */ + + region_check(heap_base); + region_check(heap_limit); +} + +void * +msheap_alloc(uint32_t size) +{ + marker_t cursor; + marker_t best; + + ASSERT(3, msheap_check()); + + /* convert the passed-in size to the number of marker-size units we need to allocate */ + size += marker_size; + size = round_up(size, marker_size); + size /= marker_size; + + /* cannot possibly satisfy this allocation */ + if (size > heap_free) + return 0; + + /* simple single-pass best-fit search */ +restart: + cursor = free_hint; + best = 0; + while (cursor != heap_limit) { + + ASSERT(1, region_check(cursor)); + + /* if the region is free and large enough */ + if ((cursor->next.free) && (cursor->next.size >= size)) { + + /* if we have no candidate, or the new one is smaller, take it */ + if (!best || (cursor->next.size < best->next.size)) + best = cursor; + } + + cursor += cursor->next.size; + } + + if (!best) { + /* + * If we were working from the hint and found nothing, reset + * the hint and try again + */ + if (free_hint != heap_base) { + free_hint = heap_base; + goto restart; + } + + /* no space */ + return 0; + } + + /* split the free region to make space */ + split_region(best, size); + + /* update free space counter */ + heap_free -= size; + + /* and return a pointer to the allocated region */ + return (void *)(best + 1); +} + +void +msheap_free(void *ptr) +{ + marker_t marker; + + marker = (marker_t)ptr - 1; + + ASSERT(0, region_check(marker)); + ASSERT(3, msheap_check()); + + /* this region is free, mark it accordingly */ + marker->next.free = 1; + (marker + marker->next.size)->prev.free = 1; + + /* account for space we are freeing */ + heap_free += marker->next.size; + + /* possibly merge this region and the following */ + merge_region(marker); + + /* possibly merge this region and the preceeding */ + if (marker->prev.free) { + marker -= marker->prev.size; + merge_region(marker); + } + + /* + * Marker now points to the new free region, so update + * the free hint if this has opened space earlier in the heap. + */ + if (marker < free_hint) + free_hint = marker; +} + +int +msheap_check(void) +{ + marker_t cursor; + uint32_t free_space = 0; + + cursor = heap_base; /* start at the base of the heap */ + + for (;;) { + if (ASSERT_TEST(2, region_check(cursor))) /* check the current region */ + return 0; + if (cursor->next.free) /* if the region is free */ + free_space += cursor->next.size; /* count it as free space */ + if (cursor == heap_limit) /* if this was the last region, stop */ + break; + cursor += cursor->next.size; /* next region */ + } + + if (ASSERT_TEST(2, region_check(free_hint))) + return 0; + if (ASSERT_TEST(2, free_space == heap_free)) + return 0; + + return 1; +} + +void +msheap_walk(void (* callback)(void *ptr, uint32_t size, int free)) +{ + marker_t cursor; + + cursor = heap_base; + for (;;) { + callback(cursor + 1, cursor->next.size * marker_size, cursor->next.free); + if (cursor == heap_limit) + break; + cursor += cursor->next.size; + } +} + +uint32_t +msheap_free_space(void) +{ + return heap_free * marker_size; +} + +void +msheap_extend(uint32_t size) +{ + marker_t new_free; + + /* convert to marker-sized units (and implicitly round down) */ + size /= marker_size; + if (size < 1) + return; + + /* + * We can either extend a free region immediately prior to + * the heap limit, or we can turn the heap limit marker + * into the marker for a free region. + */ + if (heap_limit->prev.free) { + new_free = heap_limit - heap_limit->prev.size; + } else { + new_free = heap_limit; + } + + /* update new free region */ + new_free->next.size += size; + new_free->next.free = 1; + + /* new end marker */ + heap_limit = new_free + new_free->next.size; + heap_limit->prev.size = new_free->next.size; + heap_limit->prev.free = 1; + heap_limit->next.size = 0; + heap_limit->next.free = 0; + + ASSERT(3, msheap_check()); +} + +/** + * Local heap panic implementation. + * + * Just sits and spins - should normally be overridden by the wrapper. + * + * @param reason The reason we are panicking. + */ +void +msheap_panic(const char *reason) +{ + for (;;) + ; +} + +/** + * Check that a region is sane. + * + * If HEAP_CHECK_LEVEL is >= 2, assert at the point where the test fails, otherwise + * expect that we are being called from inside an ASSERT wrapper at an appropriate + * but lower level. + * + * @param marker The region to test. + * @return 0 if the region fails checking, 1 otherwise. + */ +static int +region_check(marker_t marker) +{ + marker_t other; + + if (ASSERT_TEST(2, marker) | /* not NULL */ + ASSERT_TEST(2, !((uintptr_t)marker % marker_size)) | /* properly aligned */ + ASSERT_TEST(2, marker >= heap_base) | /* within the heap */ + ASSERT_TEST(2, marker <= heap_limit)) + return 0; + + /* validate link to next marker & return link from that marker */ + if (marker->next.size > 0) { + other = marker + marker->next.size; + + if (ASSERT_TEST(2, other > marker) | /* must be after */ + ASSERT_TEST(2, other <= heap_limit) | /* must be inside the heap */ + ASSERT_TEST(2, marker->next.size == other->prev.size) | /* sizes must match */ + ASSERT_TEST(2, marker->next.free == other->prev.free)) /* free state must match */ + return 0; + } else { + if (ASSERT_TEST(2, marker == heap_limit)) /* or it's the end of the heap */ + return 0; + } + + /* validate link to previous marker & return link from that marker */ + if (marker->prev.size > 0) { + other = marker - marker->prev.size; + + if (ASSERT_TEST(2, other < marker) | /* must be before */ + ASSERT_TEST(2, other >= heap_base) | /* must be inside the heap */ + ASSERT_TEST(2, marker->prev.size == other->next.size) | /* sizes must match */ + ASSERT_TEST(2, marker->prev.free == other->next.free)) /* free state must match */ + return 0; + } else { + if (ASSERT_TEST(2, marker == heap_base)) /* or it's the end of the heap */ + return 0; + } + + /* must never be two free regions adjacent */ + if (ASSERT_TEST(2, !(marker->prev.free && marker->next.free))) + return 0; + + return 1; +} + +/** + * Split a free region into two and allocate the first portion. + * + * @param marker Marker at the head of the region to be split. + * @param size Size of the portion to be allocated. + */ +static void +split_region(marker_t marker, uint32_t size) +{ + marker_t split, tail; + + ASSERT(1, marker->next.free); /* must be splitting a free region */ + ASSERT(1, !marker->prev.free); /* free region must never follow a free region */ + ASSERT(1, marker->next.size >= size); /* size must fit in region */ + + ASSERT(3, size); /* split result must be at least one marker in size */ + + tail = marker + marker->next.size; + ASSERT(1, region_check(tail)); /* validate the following region */ + + /* + * The split marker is at the end of the allocated region; it may actually + * be at the end of the previous free region as well. + */ + split = marker + size; + + /* describe the now-allocated region */ + split->prev.size = size; + split->prev.free = 0; + + /* if there is a real split, then describe the free region */ + if (split != tail) { + split->next.size = marker->next.size - size; + split->next.free = 1; + tail->prev.size = split->next.size; + tail->prev.free = 1; + + /* + * Update the allocation speedup hint to + * point to the new free region if we just used it. + */ + if (free_hint == marker) + free_hint = split; + } else { + + /* + * If we just allocated all of what the free hint + * pointed to, reset it to the base of the heap. + */ + if (free_hint == marker) + free_hint = heap_base; + } + + /* and update the allocated region */ + marker->next.size = size; + marker->next.free = 0; + + ASSERT(3, region_check(marker)); + ASSERT(3, region_check(split)); + ASSERT(3, region_check(tail)); +} + +/** + * Merge a free region with the following region, if possible. + * + * @param marker Marker preceeding the region to be merged. + */ +static void +merge_region(marker_t marker) +{ + marker_t other; + + /* + * note - cannot region_check(marker) here as we are + * actively fixing adjacent free regions. + */ + + other = marker + marker->next.size; + + /* if this region and the next region are both free, merge */ + if (marker->next.free && other->next.free) { + + /* update region size */ + marker->next.size += other->next.size; + + /* update the marker following the end of the merged regions */ + other = marker + marker->next.size; + other->prev.size = marker->next.size; + } +} + diff --git a/flight/PiOS/Common/Libraries/msheap/msheap.h b/flight/PiOS/Common/Libraries/msheap/msheap.h new file mode 100644 index 000000000..2f5f2ab73 --- /dev/null +++ b/flight/PiOS/Common/Libraries/msheap/msheap.h @@ -0,0 +1,91 @@ +/* -*- Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- */ +/*- + * MSHEAP + * + * A compact, low-overhead heap implementation with configurable + * integrity checking. + * + * Copyright 2011 Michael Smith. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above + * copyright notice, this list of conditions and the following + * disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials + * provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDER ''AS IS'' AND ANY + * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT + * OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + */ + +#include + +/** + * Initialise the heap. + * + * @param base The lower boundary of the heap. + * @param limit The upper boundary of the heap. + */ +extern void msheap_init(void *base, void *limit); + +/** + * Allocate memory from the heap. + * + * @param size The number of bytes required (more may be allocated). + */ +extern void *msheap_alloc(uint32_t size); + +/** + * Free memory back to the heap. + * + * @param ptr Pointer being freed to the heap. + */ +extern void msheap_free(void *ptr); + +/** + * Validate the heap. + * + * @return Zero if the heap integrity checks pass, nonzero + * otherwise. + */ +extern int msheap_check(void); + +/** + * Walk the heap. + * + * @param callback Called for each allocation in the heap. + * The ptr argument gives the allocated address or + * the free region address, size is the region size + * in bytes and free is nonzero if the region is free. + */ +extern void msheap_walk(void (* callback)(void *ptr, uint32_t size, int free)); + +/** + * Return the amount of free space in the heap. + * + * @return The total number of bytes available for allocation. + */ +extern uint32_t msheap_free_space(void); + +/** + * Extend the heap. + * + * @param size The size of the extension in bytes. + */ +extern void msheap_extend(uint32_t size); diff --git a/flight/PiOS/Common/Libraries/msheap/pios_msheap.c b/flight/PiOS/Common/Libraries/msheap/pios_msheap.c new file mode 100644 index 000000000..7fca3a8b5 --- /dev/null +++ b/flight/PiOS/Common/Libraries/msheap/pios_msheap.c @@ -0,0 +1,140 @@ +/* -*- Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- */ +/*- + * PIOS interface shims for MSHEAP + * + * Copyright 2011 Michael Smith. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above + * copyright notice, this list of conditions and the following + * disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials + * provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDER ''AS IS'' AND ANY + * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT + * OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + */ + +#include "msheap.h" +#include "pios_config.h" +#include "pios.h" + +/* + * Symbols exported by the linker script telling us where the heap is. + */ +extern char _sheap; +extern char _eheap; + +#if defined(PIOS_INCLUDE_FREERTOS) +/* + * Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining + * all the API functions to use the MPU wrappers. That should only be done when + * task.h is included from an application file. + * */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE +# include "FreeRTOS.h" +# include "task.h" +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* + * Optional callback for allocation failures. + */ +extern void vApplicationMallocFailedHook(void) __attribute__((weak)); + +void * +pvPortMalloc(size_t s) +{ + void *p; + + vPortEnterCritical(); + p = msheap_alloc(s); + vPortExitCritical(); + + if (p == NULL && &vApplicationMallocFailedHook != NULL) + vApplicationMallocFailedHook(); + + return p; +} + +void +vPortFree(void *p) +{ + vPortEnterCritical(); + msheap_free(p); + vPortExitCritical(); +} + +size_t +xPortGetFreeHeapSize(void) +{ + return msheap_free_space(); +} + +void +vPortInitialiseBlocks(void) +{ + msheap_init(&_sheap, &_eheap); +} + +void +xPortIncreaseHeapSize(size_t bytes) +{ + msheap_extend(bytes); +} + +void * +malloc(size_t size) +{ + return pvPortMalloc(size); +} + +void +free(void *p) +{ + return vPortFree(p); +} + +#else /* !PIOS_INCLUDE_FREERTOS */ +int heap_init_done; +void * +malloc(size_t size) +{ +// static + + if (!heap_init_done) { + msheap_init(&_sheap, &_eheap); + heap_init_done = 1; + } + + return msheap_alloc(size); +} + +void +free(void *p) +{ + return msheap_free(p); +} + +#endif /* PIOS_INCLUDE_FREERTOS */ + +void +msheap_panic(const char *reason) +{ + //PIOS_DEBUG_Panic(reason); +} diff --git a/flight/PiOS/Common/pios_adxl345.c b/flight/PiOS/Common/pios_adxl345.c index 91fb3f91f..248c985b2 100644 --- a/flight/PiOS/Common/pios_adxl345.c +++ b/flight/PiOS/Common/pios_adxl345.c @@ -1,32 +1,116 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_ADXL345 ADXL345 Functions + * @brief Deals with the hardware interface to the BMA180 3-axis accelerometer + * @{ + * + * @file pios_adxl345.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief PiOS ADXL345 digital accelerometer driver. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ /* - * pios_adxl345.c - * OpenPilotOSX + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. * - * Created by James Cotton on 1/16/11. - * Copyright 2011 OpenPilot. All rights reserved. + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "pios.h" -static uint32_t PIOS_SPI_ACCEL; +enum pios_adxl345_dev_magic { + PIOS_ADXL345_DEV_MAGIC = 0xcb55aa55, +}; + +struct adxl345_dev { + uint32_t spi_id; + uint32_t slave_num; + enum pios_adxl345_dev_magic magic; +}; + +//! Global structure for this device device +static struct adxl345_dev * dev; + +//! Private functions +static struct adxl345_dev * PIOS_ADXL345_alloc(void); +static int32_t PIOS_ADXL345_Validate(struct adxl345_dev * dev); +static int32_t PIOS_ADXL345_ClaimBus(); +static int32_t PIOS_ADXL345_ReleaseBus(); +static int32_t PIOS_ADXL345_FifoDepth(uint8_t depth); + +/** + * @brief Allocate a new device + */ +static struct adxl345_dev * PIOS_ADXL345_alloc(void) +{ + struct adxl345_dev * adxl345_dev; + + adxl345_dev = (struct adxl345_dev *)pvPortMalloc(sizeof(*adxl345_dev)); + if (!adxl345_dev) return (NULL); + + adxl345_dev->magic = PIOS_ADXL345_DEV_MAGIC; + return(adxl345_dev); +} + +/** + * @brief Validate the handle to the spi device + * @returns 0 for valid device or -1 otherwise + */ +static int32_t PIOS_ADXL345_Validate(struct adxl345_dev * dev) +{ + if (dev == NULL) + return -1; + if (dev->magic != PIOS_ADXL345_DEV_MAGIC) + return -2; + if (dev->spi_id == 0) + return -3; + return 0; +} /** * @brief Claim the SPI bus for the accel communications and select this chip + * @return 0 for succesful claiming of bus or -1 otherwise */ -void PIOS_ADXL345_ClaimBus() +static int32_t PIOS_ADXL345_ClaimBus() { - PIOS_SPI_ClaimBus(PIOS_SPI_ACCEL); - PIOS_ADXL_ENABLE; + if(PIOS_ADXL345_Validate(dev) != 0) + return -1; + + if(PIOS_SPI_ClaimBus(dev->spi_id) != 0) + return -2; + + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0); + + return 0; } /** * @brief Release the SPI bus for the accel communications and end the transaction + * @return 0 if success or <0 for failure */ -void PIOS_ADXL345_ReleaseBus() +static int32_t PIOS_ADXL345_ReleaseBus() { - PIOS_ADXL_DISABLE; - PIOS_SPI_ReleaseBus(PIOS_SPI_ACCEL); + if(PIOS_ADXL345_Validate(dev) != 0) + return -1; + + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); + + if(PIOS_SPI_ReleaseBus(dev->spi_id) != 0) + return -2; + + return 0; } /** @@ -34,80 +118,159 @@ void PIOS_ADXL345_ReleaseBus() * * This also puts it into high power mode */ -void PIOS_ADXL345_SelectRate(uint8_t rate) +int32_t PIOS_ADXL345_SelectRate(uint8_t rate) { + if(PIOS_ADXL345_Validate(dev) != 0) + return -1; + + if(PIOS_ADXL345_ClaimBus() != 0) + return -2; + uint8_t out[2] = {ADXL_RATE_ADDR, rate & 0x0F}; - PIOS_ADXL345_ClaimBus(); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,out,NULL,sizeof(out),NULL); - PIOS_ADXL345_ReleaseBus(); + if(PIOS_SPI_TransferBlock(dev->spi_id,out,NULL,sizeof(out),NULL) < 0) { + PIOS_ADXL345_ReleaseBus(); + return -3; + } + + PIOS_ADXL345_ReleaseBus(); + + return 0; } /** * @brief Set the range of the accelerometer and set the data to be right justified * with sign extension. Also keep device in 4 wire mode. */ -void PIOS_ADXL345_SetRange(uint8_t range) +int32_t PIOS_ADXL345_SetRange(uint8_t range) { + if(PIOS_ADXL345_Validate(dev) != 0) + return -1; + + if(PIOS_ADXL345_ClaimBus() != 0) + return -2; + uint8_t out[2] = {ADXL_FORMAT_ADDR, (range & 0x03) | ADXL_FULL_RES | ADXL_4WIRE}; - PIOS_ADXL345_ClaimBus(); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,out,NULL,sizeof(out),NULL); - PIOS_ADXL345_ReleaseBus(); + if(PIOS_SPI_TransferBlock(dev->spi_id,out,NULL,sizeof(out),NULL) < 0) { + PIOS_ADXL345_ReleaseBus(); + return -3; + } + + PIOS_ADXL345_ReleaseBus(); + + return 0; } /** * @brief Set the fifo depth that triggers an interrupt. This will be matched to the oversampling */ -void PIOS_ADXL345_FifoDepth(uint8_t depth) +static int32_t PIOS_ADXL345_FifoDepth(uint8_t depth) { + if(PIOS_ADXL345_Validate(dev) != 0) + return -1; + + if(PIOS_ADXL345_ClaimBus() != 0) + return -2; + uint8_t out[2] = {ADXL_FIFO_ADDR, (depth & 0x1f) | ADXL_FIFO_STREAM}; - PIOS_ADXL345_ClaimBus(); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,out,NULL,sizeof(out),NULL); - PIOS_ADXL345_ReleaseBus(); + if(PIOS_SPI_TransferBlock(dev->spi_id,out,NULL,sizeof(out),NULL) < 0) { + PIOS_ADXL345_ReleaseBus(); + return -3; + } + + PIOS_ADXL345_ReleaseBus(); + + return 0; } /** * @brief Enable measuring. This also disables the activity sensors (tap or free fall) */ -void PIOS_ADXL345_SetMeasure(uint8_t enable) +static int32_t PIOS_ADXL345_SetMeasure(uint8_t enable) { + if(PIOS_ADXL345_Validate(dev) != 0) + return -1; + + if(PIOS_ADXL345_ClaimBus() != 0) + return -2; + uint8_t out[2] = {ADXL_POWER_ADDR, ADXL_MEAURE}; - PIOS_ADXL345_ClaimBus(); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,out,NULL,sizeof(out),NULL); - PIOS_ADXL345_ReleaseBus(); -} + if(PIOS_SPI_TransferBlock(dev->spi_id,out,NULL,sizeof(out),NULL) < 0) { + PIOS_ADXL345_ReleaseBus(); + return -3; + } -/** - * @brief Connect to the correct SPI bus - */ -void PIOS_ADXL345_Attach(uint32_t spi_id) -{ - PIOS_SPI_ACCEL = spi_id; + PIOS_ADXL345_ReleaseBus(); + + return 0; } /** * @brief Initialize with good default settings */ -void PIOS_ADXL345_Init() +int32_t PIOS_ADXL345_Init(uint32_t spi_id, uint32_t slave_num) { + dev = PIOS_ADXL345_alloc(); + if(dev == NULL) + return -1; + + dev->spi_id = spi_id; + dev->slave_num = slave_num; + PIOS_ADXL345_ReleaseBus(); PIOS_ADXL345_SelectRate(ADXL_RATE_3200); PIOS_ADXL345_SetRange(ADXL_RANGE_8G); PIOS_ADXL345_FifoDepth(16); - PIOS_ADXL345_SetMeasure(1); + PIOS_ADXL345_SetMeasure(1); + + return 0; } /** * @brief Return number of entries in the fifo */ -uint8_t PIOS_ADXL345_FifoElements() +int32_t PIOS_ADXL345_Test() { + if(PIOS_ADXL345_Validate(dev) != 0) + return -1; + + if(PIOS_ADXL345_ClaimBus() != 0) + return -2; + + uint8_t buf[2] = {0,0}; + uint8_t rec[2] = {0,0}; + buf[0] = ADXL_WHOAMI | ADXL_READ_BIT; + + if(PIOS_SPI_TransferBlock(dev->spi_id,&buf[0],&rec[0],sizeof(buf),NULL) < 0) { + PIOS_ADXL345_ReleaseBus(); + return -3; + } + + PIOS_ADXL345_ReleaseBus(); + + return (rec[1] == ADXL_DEVICE_ID) ? 0 : -4; +} + +/** + * @brief Return number of entries in the fifo + */ +int32_t PIOS_ADXL345_FifoElements() +{ + if(PIOS_ADXL345_Validate(dev) != 0) + return -1; + + if(PIOS_ADXL345_ClaimBus() != 0) + return -2; + uint8_t buf[2] = {0,0}; uint8_t rec[2] = {0,0}; buf[0] = ADXL_FIFOSTATUS_ADDR | ADXL_READ_BIT ; // Read fifo status - PIOS_ADXL345_ClaimBus(); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,&buf[0],&rec[0],sizeof(buf),NULL); - PIOS_ADXL345_ReleaseBus(); + if(PIOS_SPI_TransferBlock(dev->spi_id,&buf[0],&rec[0],sizeof(buf),NULL) < 0) { + PIOS_ADXL345_ReleaseBus(); + return -3; + } + + PIOS_ADXL345_ReleaseBus(); return rec[1] & 0x3f; } @@ -118,14 +281,23 @@ uint8_t PIOS_ADXL345_FifoElements() */ uint8_t PIOS_ADXL345_Read(struct pios_adxl345_data * data) { + if(PIOS_ADXL345_Validate(dev) != 0) + return -1; + + if(PIOS_ADXL345_ClaimBus() != 0) + return -2; + // To save memory use same buffer for in and out but offset by // a byte uint8_t buf[9] = {0,0,0,0,0,0,0,0}; uint8_t rec[9] = {0,0,0,0,0,0,0,0}; buf[0] = ADXL_X0_ADDR | ADXL_MULTI_BIT | ADXL_READ_BIT ; // Multibyte read starting at X0 - PIOS_ADXL345_ClaimBus(); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,&buf[0],&rec[0],9,NULL); + if(PIOS_SPI_TransferBlock(dev->spi_id,&buf[0],&rec[0],9,NULL) < 0) { + PIOS_ADXL345_ReleaseBus(); + return -3; + } + PIOS_ADXL345_ReleaseBus(); data->x = rec[1] + (rec[2] << 8); diff --git a/flight/PiOS/Common/pios_bma180.c b/flight/PiOS/Common/pios_bma180.c index 866be1220..2a578dd5d 100644 --- a/flight/PiOS/Common/pios_bma180.c +++ b/flight/PiOS/Common/pios_bma180.c @@ -7,8 +7,7 @@ * @{ * * @file pios_bma180.h - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief PiOS BMA180 digital accelerometer driver. * - Driver for the BMA180 digital accelerometer on the SPI bus. * @see The GNU Public License (GPL) Version 3 @@ -32,58 +31,166 @@ #include "pios.h" -static uint32_t PIOS_SPI_ACCEL; -static uint8_t EEPROM_WRITEABLE=0; +#if defined(PIOS_INCLUDE_BMA180) +#include "fifo_buffer.h" + +enum pios_bma180_dev_magic { + PIOS_BMA180_DEV_MAGIC = 0xcbb93755, +}; + +#define PIOS_BMA180_MAX_DOWNSAMPLE 10 +struct bma180_dev { + uint32_t spi_id; + uint32_t slave_num; + int16_t buffer[PIOS_BMA180_MAX_DOWNSAMPLE * sizeof(struct pios_bma180_data)]; + t_fifo_buffer fifo; + const struct pios_bma180_cfg * cfg; + enum bma180_bandwidth bandwidth; + enum bma180_range range; + enum pios_bma180_dev_magic magic; +}; + +//! Global structure for this device device +static struct bma180_dev * dev; + +//! Private functions +static struct bma180_dev * PIOS_BMA180_alloc(void); +static int32_t PIOS_BMA180_Validate(struct bma180_dev * dev); +static int32_t PIOS_BMA180_GetReg(uint8_t reg); +static int32_t PIOS_BMA180_SetReg(uint8_t reg, uint8_t data); +static int32_t PIOS_BMA180_SelectBW(enum bma180_bandwidth bw); +static int32_t PIOS_BMA180_SetRange(enum bma180_range range); +static int32_t PIOS_BMA180_Config(); +static int32_t PIOS_BMA180_EnableIrq(); + +#define GRAV 9.81f + +/** + * @brief Allocate a new device + */ +static struct bma180_dev * PIOS_BMA180_alloc(void) +{ + struct bma180_dev * bma180_dev; + + bma180_dev = (struct bma180_dev *)pvPortMalloc(sizeof(*bma180_dev)); + if (!bma180_dev) return (NULL); + + fifoBuf_init(&bma180_dev->fifo, (uint8_t *) bma180_dev->buffer, sizeof(bma180_dev->buffer)); + + bma180_dev->magic = PIOS_BMA180_DEV_MAGIC; + return(bma180_dev); +} + +/** + * @brief Validate the handle to the spi device + * @returns 0 for valid device or -1 otherwise + */ +static int32_t PIOS_BMA180_Validate(struct bma180_dev * dev) +{ + if (dev == NULL) + return -1; + if (dev->magic != PIOS_BMA180_DEV_MAGIC) + return -2; + if (dev->spi_id == 0) + return -3; + return 0; +} + +/** + * @brief Initialize with good default settings + * @returns 0 for success, -1 for failure + */ +int32_t PIOS_BMA180_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_bma180_cfg * cfg) +{ + dev = PIOS_BMA180_alloc(); + if(dev == NULL) + return -1; + + dev->spi_id = spi_id; + dev->slave_num = slave_num; + dev->cfg = cfg; + + if(PIOS_BMA180_Config() < 0) + return -1; + PIOS_DELAY_WaituS(50); + + PIOS_EXTI_Init(dev->cfg->exti_cfg); + + while(PIOS_BMA180_EnableIrq() != 0); + + return 0; +} /** * @brief Claim the SPI bus for the accel communications and select this chip + * @return 0 if successful, -1 if unable to claim bus */ -void PIOS_BMA180_ClaimBus() +int32_t PIOS_BMA180_ClaimBus() { - PIOS_SPI_ClaimBus(PIOS_SPI_ACCEL); - PIOS_BMA_ENABLE; + if(PIOS_BMA180_Validate(dev) != 0) + return -1; + + if(PIOS_SPI_ClaimBus(dev->spi_id) != 0) { + return -1; + } + + PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + + return 0; +} + +/** + * @brief Claim the SPI bus for the accel communications and select this chip + * @return 0 if successful, -1 if unable to claim bus + */ +int32_t PIOS_BMA180_ClaimBusISR() +{ + if(PIOS_BMA180_Validate(dev) != 0) + return -1; + + if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) { + return -1; + } + + PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + return 0; } /** * @brief Release the SPI bus for the accel communications and end the transaction + * @return 0 if successful */ -void PIOS_BMA180_ReleaseBus() +int32_t PIOS_BMA180_ReleaseBus() { - PIOS_BMA_DISABLE; - PIOS_SPI_ReleaseBus(PIOS_SPI_ACCEL); -} + if(PIOS_BMA180_Validate(dev) != 0) + return -1; -/** - * @brief Set the EEPROM write-enable bit. Must be set to 1 (unlocked) before writing control registers. - * @return none - * @param _we[in] bit to set, 1 to enable writes or 0 to disable writes - */ -void PIOS_BMA180_WriteEnable(uint8_t _we) -{ - uint8_t addr_reg[2] = {BMA_WE_ADDR,0}; + PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,1); - PIOS_BMA180_ClaimBus(); - addr_reg[1] = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80 | BMA_WE_ADDR) ); - addr_reg[1] &= 0xEF; - addr_reg[1] |= ( (0x01 & _we) << 4); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,addr_reg,NULL,sizeof(addr_reg),NULL); - PIOS_BMA180_ReleaseBus(); - EEPROM_WRITEABLE=_we; + return PIOS_SPI_ReleaseBus(dev->spi_id); } /** * @brief Read a register from BMA180 - * @returns The register value + * @returns The register value or -1 if failure to get bus * @param reg[in] Register address to be read */ -uint8_t PIOS_BMA180_GetReg(uint8_t reg) +int32_t PIOS_BMA180_GetReg(uint8_t reg) { + if(PIOS_BMA180_Validate(dev) != 0) + return -1; + uint8_t data; - PIOS_BMA180_ClaimBus(); - data = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80 | reg) ); + + if(PIOS_BMA180_ClaimBus() != 0) + return -1; + + PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte + data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response + PIOS_BMA180_ReleaseBus(); - return(data); + return data; } /** @@ -92,120 +199,281 @@ uint8_t PIOS_BMA180_GetReg(uint8_t reg) * @param reg[in] address of register to be written * @param data[in] data that is to be written to register */ -void PIOS_BMA180_SetReg(uint8_t reg, uint8_t data) +int32_t PIOS_BMA180_SetReg(uint8_t reg, uint8_t data) { - uint8_t reg_data[2] = { (0x7F & reg), data}; - PIOS_BMA180_ClaimBus(); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,reg_data,NULL,2,NULL); + if(PIOS_BMA180_ClaimBus() != 0) + return -1; + + PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg); + PIOS_SPI_TransferByte(dev->spi_id, data); + PIOS_BMA180_ReleaseBus(); + + return 0; +} + + +static int32_t PIOS_BMA180_EnableEeprom() { + // Enable EEPROM writing + int32_t byte = PIOS_BMA180_GetReg(BMA_CTRREG0); + if(byte < 0) + return -1; + byte |= 0x10; // Set bit 4 + if(PIOS_BMA180_SetReg(BMA_CTRREG0,(uint8_t) byte) < 0) // Have to set ee_w to + return -1; + return 0; +} + +static int32_t PIOS_BMA180_DisableEeprom() { + // Enable EEPROM writing + int32_t byte = PIOS_BMA180_GetReg(BMA_CTRREG0); + if(byte < 0) + return -1; + byte |= 0x10; // Set bit 4 + if(PIOS_BMA180_SetReg(BMA_CTRREG0,(uint8_t) byte) < 0) // Have to set ee_w to + return -1; + return 0; +} + +/** + * @brief Set the default register settings + * @return 0 if successful, -1 if not + */ +static int32_t PIOS_BMA180_Config() +{ + /* + 0x35 = 0x81 //smp-skip = 1 for less interrupts + 0x33 = 0x81 //shadow-dis = 1, update MSB and LSB synchronously + 0x27 = 0x01 //dis-i2c + 0x21 = 0x02 //new_data_int = 1 + */ + + PIOS_DELAY_WaituS(20); + + if(PIOS_BMA180_Validate(dev) != 0) + return -1; + + while(PIOS_BMA180_EnableEeprom() != 0); + while(PIOS_BMA180_SetReg(BMA_RESET, BMA_RESET_CODE) != 0); + while(PIOS_BMA180_SetReg(BMA_OFFSET_LSB1, 0x81) != 0); + while(PIOS_BMA180_SetReg(BMA_GAIN_Y, 0x81) != 0); + while(PIOS_BMA180_SetReg(BMA_CTRREG3, 0xFF) != 0); + while(PIOS_BMA180_SelectBW(dev->cfg->bandwidth) != 0); + while(PIOS_BMA180_SetRange(dev->cfg->range) != 0); + while(PIOS_BMA180_DisableEeprom() != 0); + + return 0; } /** * @brief Select the bandwidth the digital filter pass allows. - * @return none + * @return 0 if successful, -1 if not * @param rate[in] Bandwidth setting to be used * * EEPROM must be write-enabled before calling this function. */ -void PIOS_BMA180_SelectBW(uint8_t bw) +static int32_t PIOS_BMA180_SelectBW(enum bma180_bandwidth bw) { - uint8_t addr_reg[2] = { BMA_BW_ADDR, 0}; + if(PIOS_BMA180_Validate(dev) != 0) + return -1; - PIOS_BMA180_ClaimBus(); - addr_reg[1] = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80|BMA_BW_ADDR)); - addr_reg[1] &= 0x0F; - addr_reg[1] |= (bw << 4); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,addr_reg,NULL,sizeof(addr_reg),NULL); - PIOS_BMA180_ReleaseBus(); + dev->bandwidth = bw; + + uint8_t reg; + reg = PIOS_BMA180_GetReg(BMA_BW_ADDR); + reg = (reg & ~BMA_BW_MASK) | ((bw << BMA_BW_SHIFT) & BMA_BW_MASK); + return PIOS_BMA180_SetReg(BMA_BW_ADDR, reg); } /** * @brief Select the full scale acceleration range. - * @return none + * @return 0 if successful, -1 if not * @param rate[in] Range setting to be used * */ -void PIOS_BMA180_SetRange(uint8_t range) -{ - uint8_t addr_reg[2] = { BMA_RANGE_ADDR, 0}; +static int32_t PIOS_BMA180_SetRange(enum bma180_range new_range) +{ + if(PIOS_BMA180_Validate(dev) != 0) + return -1; - PIOS_BMA180_ClaimBus(); - addr_reg[1] = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80|BMA_RANGE_ADDR)); - addr_reg[1] &= 0x0F; - addr_reg[1] |= (range << 4); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,addr_reg,NULL,sizeof(addr_reg),NULL); - PIOS_BMA180_ReleaseBus(); + uint8_t reg; + + dev->range = new_range; + reg = PIOS_BMA180_GetReg(BMA_RANGE_ADDR); + reg = (reg & ~BMA_RANGE_MASK) | ((dev->range << BMA_RANGE_SHIFT) & BMA_RANGE_MASK); + return PIOS_BMA180_SetReg(BMA_RANGE_ADDR, reg); } -/** - * @brief Connect to the correct SPI bus - */ -void PIOS_BMA180_Attach(uint32_t spi_id) +static int32_t PIOS_BMA180_EnableIrq() { - PIOS_SPI_ACCEL = spi_id; -} -/** - * @brief Initialize with good default settings - */ -void PIOS_BMA180_Init() -{ -/* - PIOS_BMA180_ReleaseBus(); - PIOS_BMA180_WriteEnable(1); - PIOS_BMA180_SelectRate(BMA_RATE_3200); - PIOS_BMA180_SetRange(BMA_RANGE_8G); - PIOS_BMA180_FifoDepth(16); - PIOS_BMA180_SetMeasure(1); - PIOS_BMA180_WriteEnable(0); -*/ + if(PIOS_BMA180_EnableEeprom() < 0) + return -1; + + if(PIOS_BMA180_SetReg(BMA_CTRREG3, BMA_NEW_DAT_INT) < 0) + return -1; + + if(PIOS_BMA180_DisableEeprom() < 0) + return -1; + + return 0; } /** * @brief Read a single set of values from the x y z channels - * @returns The number of samples remaining in the fifo + * @param[out] data Int16 array of (x,y,z) sensor values + * @returns 0 if successful + * @retval -1 unable to claim bus + * @retval -2 unable to transfer data */ -uint8_t PIOS_BMA180_Read(struct pios_bma180_data * data) +int32_t PIOS_BMA180_ReadAccels(struct pios_bma180_data * data) { // To save memory use same buffer for in and out but offset by // a byte - uint8_t buf[7] = {0,0,0,0,0,0}; + uint8_t buf[7] = {BMA_X_LSB_ADDR | 0x80,0,0,0,0,0}; uint8_t rec[7] = {0,0,0,0,0,0}; - buf[0] = BMA_X_LSB_ADDR | 0x80 ; // Multibyte read starting at X LSB - PIOS_BMA180_ClaimBus(); - PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,&buf[0],&rec[0],7,NULL); + if(PIOS_BMA180_ClaimBus() != 0) + return -1; + if(PIOS_SPI_TransferBlock(dev->spi_id,&buf[0],&rec[0],7,NULL) != 0) + return -2; PIOS_BMA180_ReleaseBus(); // | MSB | LSB | 0 | new_data | - data->x = ( (rec[2] << 8) | rec[1] ) >> 2; - data->y = ( (rec[4] << 8) | rec[3] ) >> 2; - data->z = ( (rec[6] << 8) | rec[5] ) >> 2; + data->x = ((rec[2] << 8) | rec[1]); + data->y = ((rec[4] << 8) | rec[3]); + data->z = ((rec[6] << 8) | rec[5]); + data->x /= 4; + data->y /= 4; + data->z /= 4; return 0; // return number of remaining entries } /** - * @brief Test SPI and chip functionality by reading chip ID register - * @return 0 if test failed, any other value signals test succeeded. - * + * @brief Returns the scale the BMA180 chip is using + * @return Scale (m / s^2) / LSB */ -uint8_t PIOS_BMA180_Test() +float PIOS_BMA180_GetScale() { - uint8_t data = 0; - uint8_t pass = 0; - PIOS_BMA180_ClaimBus(); - data = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80 | BMA_CHIPID_ADDR) ); - data &= 0x07; - if(0x03 == data) - pass = 1; - data = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80 | BMA_VERSION_ADDR) ); - if(0x12 == data) - pass = 1 && pass; // Only passes if first and second test passS - PIOS_BMA180_ReleaseBus(); - return pass; + if(PIOS_BMA180_Validate(dev) != 0) + return -1; + + switch (dev->cfg->range) { + case BMA_RANGE_1G: + return GRAV / 8192.0f; + case BMA_RANGE_1_5G: + return GRAV / 5460.0f; + case BMA_RANGE_2G: + return GRAV / 4096.0f; + case BMA_RANGE_3G: + return GRAV / 2730.0f; + case BMA_RANGE_4G: + return GRAV / 2048.0f; + case BMA_RANGE_8G: + return GRAV / 1024.0f; + case BMA_RANGE_16G: + return GRAV / 512.0f; + } + return 0; } +/** + * @brief Get data from fifo + * @param [out] buffer pointer to a @ref pios_bma180_data structure to receive data + * @return 0 for success, -1 for failure (no data available) + */ +int32_t PIOS_BMA180_ReadFifo(struct pios_bma180_data * buffer) +{ + if(PIOS_BMA180_Validate(dev) != 0) + return -1; + + if(fifoBuf_getUsed(&dev->fifo) < sizeof(*buffer)) + return -1; + + fifoBuf_getData(&dev->fifo, (uint8_t *) buffer, sizeof(*buffer)); + + return 0; +} + + +/** + * @brief Test SPI and chip functionality by reading chip ID register + * @return 0 if success, -1 if failure. + * + */ +int32_t PIOS_BMA180_Test() +{ + // Read chip ID then version ID + uint8_t buf[3] = {0x80 | BMA_CHIPID_ADDR, 0, 0}; + uint8_t rec[3] = {0,0, 0}; + int32_t retval; + + if(PIOS_BMA180_ClaimBus() != 0) + return -1; + retval = PIOS_SPI_TransferBlock(dev->spi_id,&buf[0],&rec[0],sizeof(buf),NULL); + PIOS_BMA180_ReleaseBus(); + + if(retval != 0) + return -2; + + struct pios_bma180_data data; + if(PIOS_BMA180_ReadAccels(&data) != 0) + return -3; + + if(rec[1] != 0x3) + return -4; + + if(rec[2] < 0x12) + return -5; + + return 0; +} + +/** + * @brief IRQ Handler. Read data from the BMA180 FIFO and push onto a local fifo. + */ +int32_t bma180_irqs = 0; +void PIOS_BMA180_IRQHandler(void) +{ + bma180_irqs++; + + const static uint8_t pios_bma180_req_buf[7] = {BMA_X_LSB_ADDR | 0x80,0,0,0,0,0}; + uint8_t pios_bma180_dmabuf[8]; + + // If we can't get the bus then just move on for efficiency + if(PIOS_BMA180_ClaimBusISR() != 0) { + return; // Something else is using bus, miss this data + } + + PIOS_SPI_TransferBlock(dev->spi_id,pios_bma180_req_buf,(uint8_t *) pios_bma180_dmabuf, + sizeof(pios_bma180_dmabuf), NULL); + + // TODO: Make this conversion depend on configuration scale + struct pios_bma180_data data; + + // Don't release bus till data has copied + PIOS_BMA180_ReleaseBus(); + + // Must not return before releasing bus + if(fifoBuf_getFree(&dev->fifo) < sizeof(data)) + return; + + // Bottom two bits indicate new data and are constant zeros. Don't right + // shift because it drops sign bit + data.x = ((pios_bma180_dmabuf[2] << 8) | pios_bma180_dmabuf[1]); + data.y = ((pios_bma180_dmabuf[4] << 8) | pios_bma180_dmabuf[3]); + data.z = ((pios_bma180_dmabuf[6] << 8) | pios_bma180_dmabuf[5]); + data.x /= 4; + data.y /= 4; + data.z /= 4; + data.temperature = pios_bma180_dmabuf[7]; + + fifoBuf_putData(&dev->fifo, (uint8_t *) &data, sizeof(data)); + +} + +#endif /* PIOS_INCLUDE_BMA180 */ /** * @} * @} diff --git a/flight/PiOS/Common/pios_crc.c b/flight/PiOS/Common/pios_crc.c index 548ba2648..dcd8c80c7 100644 --- a/flight/PiOS/Common/pios_crc.c +++ b/flight/PiOS/Common/pios_crc.c @@ -29,6 +29,76 @@ static const uint8_t crc_table[256] = { 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 }; +static const uint16_t CRC_Table16[] = { // HDLC polynomial + 0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf, + 0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5, 0xe97e, 0xf8f7, + 0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e, + 0x9cc9, 0x8d40, 0xbfdb, 0xae52, 0xdaed, 0xcb64, 0xf9ff, 0xe876, + 0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd, + 0xad4a, 0xbcc3, 0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5, + 0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c, + 0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974, + 0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9, 0x2732, 0x36bb, + 0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3, + 0x5285, 0x430c, 0x7197, 0x601e, 0x14a1, 0x0528, 0x37b3, 0x263a, + 0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72, + 0x6306, 0x728f, 0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9, + 0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1, + 0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738, + 0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862, 0x9af9, 0x8b70, + 0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7, + 0x0840, 0x19c9, 0x2b52, 0x3adb, 0x4e64, 0x5fed, 0x6d76, 0x7cff, + 0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036, + 0x18c1, 0x0948, 0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e, + 0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5, + 0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd, + 0xb58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226, 0xd0bd, 0xc134, + 0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c, + 0xc60c, 0xd785, 0xe51e, 0xf497, 0x8028, 0x91a1, 0xa33a, 0xb2b3, + 0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb, + 0xd68d, 0xc704, 0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232, + 0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a, + 0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1, + 0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb, 0x0e70, 0x1ff9, + 0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330, + 0x7bc7, 0x6a4e, 0x58d5, 0x495c, 0x3de3, 0x2c6a, 0x1ef1, 0x0f78 +}; + +static const uint32_t CRC_Table32[] = { + 0x00000000, 0x04c11db7, 0x09823b6e, 0x0d4326d9, 0x130476dc, 0x17c56b6b, 0x1a864db2, 0x1e475005, + 0x2608edb8, 0x22c9f00f, 0x2f8ad6d6, 0x2b4bcb61, 0x350c9b64, 0x31cd86d3, 0x3c8ea00a, 0x384fbdbd, + 0x4c11db70, 0x48d0c6c7, 0x4593e01e, 0x4152fda9, 0x5f15adac, 0x5bd4b01b, 0x569796c2, 0x52568b75, + 0x6a1936c8, 0x6ed82b7f, 0x639b0da6, 0x675a1011, 0x791d4014, 0x7ddc5da3, 0x709f7b7a, 0x745e66cd, + 0x9823b6e0, 0x9ce2ab57, 0x91a18d8e, 0x95609039, 0x8b27c03c, 0x8fe6dd8b, 0x82a5fb52, 0x8664e6e5, + 0xbe2b5b58, 0xbaea46ef, 0xb7a96036, 0xb3687d81, 0xad2f2d84, 0xa9ee3033, 0xa4ad16ea, 0xa06c0b5d, + 0xd4326d90, 0xd0f37027, 0xddb056fe, 0xd9714b49, 0xc7361b4c, 0xc3f706fb, 0xceb42022, 0xca753d95, + 0xf23a8028, 0xf6fb9d9f, 0xfbb8bb46, 0xff79a6f1, 0xe13ef6f4, 0xe5ffeb43, 0xe8bccd9a, 0xec7dd02d, + 0x34867077, 0x30476dc0, 0x3d044b19, 0x39c556ae, 0x278206ab, 0x23431b1c, 0x2e003dc5, 0x2ac12072, + 0x128e9dcf, 0x164f8078, 0x1b0ca6a1, 0x1fcdbb16, 0x018aeb13, 0x054bf6a4, 0x0808d07d, 0x0cc9cdca, + 0x7897ab07, 0x7c56b6b0, 0x71159069, 0x75d48dde, 0x6b93dddb, 0x6f52c06c, 0x6211e6b5, 0x66d0fb02, + 0x5e9f46bf, 0x5a5e5b08, 0x571d7dd1, 0x53dc6066, 0x4d9b3063, 0x495a2dd4, 0x44190b0d, 0x40d816ba, + 0xaca5c697, 0xa864db20, 0xa527fdf9, 0xa1e6e04e, 0xbfa1b04b, 0xbb60adfc, 0xb6238b25, 0xb2e29692, + 0x8aad2b2f, 0x8e6c3698, 0x832f1041, 0x87ee0df6, 0x99a95df3, 0x9d684044, 0x902b669d, 0x94ea7b2a, + 0xe0b41de7, 0xe4750050, 0xe9362689, 0xedf73b3e, 0xf3b06b3b, 0xf771768c, 0xfa325055, 0xfef34de2, + 0xc6bcf05f, 0xc27dede8, 0xcf3ecb31, 0xcbffd686, 0xd5b88683, 0xd1799b34, 0xdc3abded, 0xd8fba05a, + 0x690ce0ee, 0x6dcdfd59, 0x608edb80, 0x644fc637, 0x7a089632, 0x7ec98b85, 0x738aad5c, 0x774bb0eb, + 0x4f040d56, 0x4bc510e1, 0x46863638, 0x42472b8f, 0x5c007b8a, 0x58c1663d, 0x558240e4, 0x51435d53, + 0x251d3b9e, 0x21dc2629, 0x2c9f00f0, 0x285e1d47, 0x36194d42, 0x32d850f5, 0x3f9b762c, 0x3b5a6b9b, + 0x0315d626, 0x07d4cb91, 0x0a97ed48, 0x0e56f0ff, 0x1011a0fa, 0x14d0bd4d, 0x19939b94, 0x1d528623, + 0xf12f560e, 0xf5ee4bb9, 0xf8ad6d60, 0xfc6c70d7, 0xe22b20d2, 0xe6ea3d65, 0xeba91bbc, 0xef68060b, + 0xd727bbb6, 0xd3e6a601, 0xdea580d8, 0xda649d6f, 0xc423cd6a, 0xc0e2d0dd, 0xcda1f604, 0xc960ebb3, + 0xbd3e8d7e, 0xb9ff90c9, 0xb4bcb610, 0xb07daba7, 0xae3afba2, 0xaafbe615, 0xa7b8c0cc, 0xa379dd7b, + 0x9b3660c6, 0x9ff77d71, 0x92b45ba8, 0x9675461f, 0x8832161a, 0x8cf30bad, 0x81b02d74, 0x857130c3, + 0x5d8a9099, 0x594b8d2e, 0x5408abf7, 0x50c9b640, 0x4e8ee645, 0x4a4ffbf2, 0x470cdd2b, 0x43cdc09c, + 0x7b827d21, 0x7f436096, 0x7200464f, 0x76c15bf8, 0x68860bfd, 0x6c47164a, 0x61043093, 0x65c52d24, + 0x119b4be9, 0x155a565e, 0x18197087, 0x1cd86d30, 0x029f3d35, 0x065e2082, 0x0b1d065b, 0x0fdc1bec, + 0x3793a651, 0x3352bbe6, 0x3e119d3f, 0x3ad08088, 0x2497d08d, 0x2056cd3a, 0x2d15ebe3, 0x29d4f654, + 0xc5a92679, 0xc1683bce, 0xcc2b1d17, 0xc8ea00a0, 0xd6ad50a5, 0xd26c4d12, 0xdf2f6bcb, 0xdbee767c, + 0xe3a1cbc1, 0xe760d676, 0xea23f0af, 0xeee2ed18, 0xf0a5bd1d, 0xf464a0aa, 0xf9278673, 0xfde69bc4, + 0x89b8fd09, 0x8d79e0be, 0x803ac667, 0x84fbdbd0, 0x9abc8bd5, 0x9e7d9662, 0x933eb0bb, 0x97ffad0c, + 0xafb010b1, 0xab710d06, 0xa6322bdf, 0xa2f33668, 0xbcb4666d, 0xb8757bda, 0xb5365d03, 0xb1f740b4 + }; + /** * Update the crc value with new data. * @@ -52,7 +122,7 @@ uint8_t PIOS_CRC_updateByte(uint8_t crc, const uint8_t data) return crc_table[crc ^ data]; } -/* +/** * @brief Update a CRC with a data buffer * @param[in] crc Starting CRC value * @param[in] data Data buffer @@ -72,3 +142,58 @@ uint8_t PIOS_CRC_updateCRC(uint8_t crc, const uint8_t* data, int32_t length) return crc8; } +/** + * Update the crc value with new data. + * \param crc The current crc value. + * \param data Pointer to a buffer of \a data_len bytes. + * \param length Number of bytes in the \a data buffer. + * \return The updated crc value. + */ +uint16_t PIOS_CRC16_updateByte(uint16_t crc, const uint8_t data) +{ + return ((crc >> 8) ^ CRC_Table16[(crc & 0xff) ^ data]); +} + +/** + * @brief Update a CRC with a data buffer + * @param[in] crc Starting CRC value + * @param[in] data Data buffer + * @param[in] length Number of bytes to process + * @returns Updated CRC + */ +uint16_t PIOS_CRC16_updateCRC(uint16_t crc, const uint8_t* data, int32_t length) +{ + register uint8_t *p = (uint8_t *)data; + register uint16_t _crc = crc; + for (register uint32_t i = length; i > 0; i--) + _crc = (_crc >> 8) ^ CRC_Table16[(_crc ^ *p++) & 0xff]; + return _crc; +} + +/** + * Update the crc value with new data. + * \param crc The current crc value. + * \param data Pointer to a buffer of \a data_len bytes. + * \param length Number of bytes in the \a data buffer. + * \return The updated crc value. + */ +uint32_t PIOS_CRC32_updateByte(uint32_t crc, const uint8_t data) +{ + return ((crc << 8) ^ CRC_Table32[(crc >> 24) ^ data]); +} + +/** + * @brief Update a CRC with a data buffer + * @param[in] crc Starting CRC value + * @param[in] data Data buffer + * @param[in] length Number of bytes to process + * @returns Updated CRC + */ +uint32_t PIOS_CRC32_updateCRC(uint32_t crc, const uint8_t* data, int32_t length) +{ + register uint8_t *p = (uint8_t *)data; + register uint32_t _crc = crc; + for (register uint32_t i = length; i > 0; i--) + _crc = (_crc << 8) ^ CRC_Table32[(_crc >> 24) ^ *p++]; + return _crc; +} diff --git a/flight/PiOS/Common/pios_flash_jedec.c b/flight/PiOS/Common/pios_flash_jedec.c new file mode 100644 index 000000000..997bd5403 --- /dev/null +++ b/flight/PiOS/Common/pios_flash_jedec.c @@ -0,0 +1,504 @@ +/** + ****************************************************************************** + * + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_FLASH Flash device handler + * @{ + * + * @file pios_flash_w25x.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Driver for talking to W25X flash chip (and most JEDEC chips) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "pios.h" + +#define JEDEC_WRITE_ENABLE 0x06 +#define JEDEC_WRITE_DISABLE 0x04 +#define JEDEC_READ_STATUS 0x05 +#define JEDEC_WRITE_STATUS 0x01 +#define JEDEC_READ_DATA 0x03 +#define JEDEC_FAST_READ 0x0b +#define JEDEC_DEVICE_ID 0x9F +#define JEDEC_PAGE_WRITE 0x02 + +#define JEDEC_STATUS_BUSY 0x01 +#define JEDEC_STATUS_WRITEPROTECT 0x02 +#define JEDEC_STATUS_BP0 0x04 +#define JEDEC_STATUS_BP1 0x08 +#define JEDEC_STATUS_BP2 0x10 +#define JEDEC_STATUS_TP 0x20 +#define JEDEC_STATUS_SEC 0x40 +#define JEDEC_STATUS_SRP0 0x80 + +static uint8_t device_type; + +enum pios_jedec_dev_magic { + PIOS_JEDEC_DEV_MAGIC = 0xcb55aa55, +}; + +//! Device handle structure +struct jedec_flash_dev { + uint32_t spi_id; + uint32_t slave_num; + bool claimed; + uint32_t device_type; + uint32_t capacity; + const struct pios_flash_jedec_cfg * cfg; +#if defined(FLASH_FREERTOS) + xSemaphoreHandle transaction_lock; +#endif + enum pios_jedec_dev_magic magic; +}; + +//! Global structure for this flash device +struct jedec_flash_dev * flash_dev; + +//! Private functions +static int32_t PIOS_Flash_Jedec_Validate(struct jedec_flash_dev * dev); +static struct jedec_flash_dev * PIOS_Flash_Jedec_alloc(void); +static int32_t PIOS_Flash_Jedec_ClaimBus(); +static int32_t PIOS_Flash_Jedec_ReleaseBus(); +static int32_t PIOS_Flash_Jedec_WriteEnable(); +static int32_t PIOS_Flash_Jedec_Busy() ; + + +/** + * @brief Allocate a new device + */ +static struct jedec_flash_dev * PIOS_Flash_Jedec_alloc(void) +{ + struct jedec_flash_dev * jedec_dev; + + jedec_dev = (struct jedec_flash_dev *)pvPortMalloc(sizeof(*jedec_dev)); + if (!jedec_dev) return (NULL); + + jedec_dev->claimed = false; + jedec_dev->magic = PIOS_JEDEC_DEV_MAGIC; +#if defined(FLASH_FREERTOS) + jedec_dev->transaction_lock = xSemaphoreCreateMutex(); +#endif + return(jedec_dev); +} + +/** + * @brief Validate the handle to the spi device + */ +static int32_t PIOS_Flash_Jedec_Validate(struct jedec_flash_dev * dev) { + if (dev == NULL) + return -1; + if (dev->magic != PIOS_JEDEC_DEV_MAGIC) + return -2; + if (dev->spi_id == 0) + return -3; + return 0; +} + +/** + * @brief Claim the SPI bus for flash use and assert CS pin + * @return 0 for sucess, -1 for failure to get semaphore + */ +static int32_t PIOS_Flash_Jedec_ClaimBus() +{ + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + + if(PIOS_SPI_ClaimBus(flash_dev->spi_id) < 0) + return -1; + + PIOS_SPI_RC_PinSet(flash_dev->spi_id, flash_dev->slave_num, 0); + flash_dev->claimed = true; + + return 0; +} + +/** + * @brief Release the SPI bus sempahore and ensure flash chip not using bus + */ +static int32_t PIOS_Flash_Jedec_ReleaseBus() +{ + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + PIOS_SPI_RC_PinSet(flash_dev->spi_id, flash_dev->slave_num, 1); + PIOS_SPI_ReleaseBus(flash_dev->spi_id); + flash_dev->claimed = false; + return 0; +} + +/** + * @brief Returns if the flash chip is busy + * @returns -1 for failure, 0 for not busy, 1 for busy + */ +static int32_t PIOS_Flash_Jedec_Busy() +{ + int32_t status = PIOS_Flash_Jedec_ReadStatus(); + if (status < 0) + return -1; + return status & JEDEC_STATUS_BUSY; +} + +/** + * @brief Execute the write enable instruction and returns the status + * @returns 0 if successful, -1 if unable to claim bus + */ +static int32_t PIOS_Flash_Jedec_WriteEnable() +{ + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + + uint8_t out[] = {JEDEC_WRITE_ENABLE}; + if(PIOS_Flash_Jedec_ClaimBus() != 0) + return -1; + PIOS_SPI_TransferBlock(flash_dev->spi_id,out,NULL,sizeof(out),NULL); + PIOS_Flash_Jedec_ReleaseBus(); + return 0; +} + +/** + * @brief Initialize the flash device and enable write access + */ +int32_t PIOS_Flash_Jedec_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_flash_jedec_cfg * cfg) +{ + flash_dev = PIOS_Flash_Jedec_alloc(); + if(flash_dev == NULL) + return -1; + + flash_dev->spi_id = spi_id; + flash_dev->slave_num = slave_num; + flash_dev->cfg = cfg; + + device_type = PIOS_Flash_Jedec_ReadID(); + if(device_type == 0) + return -1; + + return 0; +} + +/** + * @brief Grab the semaphore to perform a transaction + * @return 0 for success, -1 for timeout + */ +int32_t PIOS_Flash_Jedec_StartTransaction() +{ +#if defined(FLASH_FREERTOS) + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + + if(xSemaphoreTake(flash_dev->transaction_lock, portMAX_DELAY) != pdTRUE) + return -1; +#endif + return 0; +} + +/** + * @brief Release the semaphore to perform a transaction + * @return 0 for success, -1 for timeout + */ +int32_t PIOS_Flash_Jedec_EndTransaction() +{ +#if defined(FLASH_FREERTOS) + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + + if(xSemaphoreGive(flash_dev->transaction_lock) != pdTRUE) + return -1; +#endif + return 0; +} + +/** + * @brief Read the status register from flash chip and return it + */ +int32_t PIOS_Flash_Jedec_ReadStatus() +{ + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + + uint8_t out[2] = {JEDEC_READ_STATUS, 0}; + uint8_t in[2] = {0,0}; + if(PIOS_Flash_Jedec_ClaimBus() < 0) + return -1; + + if(PIOS_SPI_TransferBlock(flash_dev->spi_id,out,in,sizeof(out),NULL) < 0) { + PIOS_Flash_Jedec_ReleaseBus(); + return -2; + } + + PIOS_Flash_Jedec_ReleaseBus(); + return in[1]; +} + +/** + * @brief Read the status register from flash chip and return it + */ +int32_t PIOS_Flash_Jedec_ReadID() +{ + uint8_t out[] = {JEDEC_DEVICE_ID}; + uint8_t in[4]; + if (PIOS_Flash_Jedec_ClaimBus() < 0) + return -1; + + if(PIOS_SPI_TransferBlock(flash_dev->spi_id,out,in,sizeof(out),NULL) < 0) { + PIOS_Flash_Jedec_ReleaseBus(); + return -2; + } + PIOS_Flash_Jedec_ReleaseBus(); + + flash_dev->device_type = in[1]; + flash_dev->capacity = in[3]; + return in[1]; +} + +/** + * @brief Erase a sector on the flash chip + * @param[in] add Address of flash to erase + * @returns 0 if successful + * @retval -1 if unable to claim bus + * @retval + */ +int32_t PIOS_Flash_Jedec_EraseSector(uint32_t addr) +{ + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + + uint8_t ret; + uint8_t out[] = {flash_dev->cfg->sector_erase, (addr >> 16) & 0xff, (addr >> 8) & 0xff , addr & 0xff}; + + if((ret = PIOS_Flash_Jedec_WriteEnable()) != 0) + return ret; + + if(PIOS_Flash_Jedec_ClaimBus() != 0) + return -1; + + if(PIOS_SPI_TransferBlock(flash_dev->spi_id,out,NULL,sizeof(out),NULL) < 0) { + PIOS_Flash_Jedec_ReleaseBus(); + return -2; + } + + PIOS_Flash_Jedec_ReleaseBus(); + + // Keep polling when bus is busy too + while(PIOS_Flash_Jedec_Busy() != 0) { +#if defined(FLASH_FREERTOS) + vTaskDelay(1); +#endif + } + + return 0; +} + +/** + * @brief Execute the whole chip + * @returns 0 if successful, -1 if unable to claim bus + */ +int32_t PIOS_Flash_Jedec_EraseChip() +{ + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + + uint8_t ret; + uint8_t out[] = {flash_dev->cfg->chip_erase}; + + if((ret = PIOS_Flash_Jedec_WriteEnable()) != 0) + return ret; + + if(PIOS_Flash_Jedec_ClaimBus() != 0) + return -1; + + if(PIOS_SPI_TransferBlock(flash_dev->spi_id,out,NULL,sizeof(out),NULL) < 0) { + PIOS_Flash_Jedec_ReleaseBus(); + return -2; + } + + PIOS_Flash_Jedec_ReleaseBus(); + + // Keep polling when bus is busy too + int i = 0; + while(PIOS_Flash_Jedec_Busy() != 0) { +#if defined(PIOS_INCLUDE_FREERTOS) + vTaskDelay(1); +#endif + if ((i++) % 100 == 0) + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); + +} + + return 0; +} + + +/** + * @brief Write one page of data (up to 256 bytes) aligned to a page start + * @param[in] addr Address in flash to write to + * @param[in] data Pointer to data to write to flash + * @param[in] len Length of data to write (max 256 bytes) + * @return Zero if success or error code + * @retval -1 Unable to claim SPI bus + * @retval -2 Size exceeds 256 bytes + * @retval -3 Length to write would wrap around page boundary + */ +int32_t PIOS_Flash_Jedec_WriteData(uint32_t addr, uint8_t * data, uint16_t len) +{ + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + + uint8_t ret; + uint8_t out[4] = {JEDEC_PAGE_WRITE, (addr >> 16) & 0xff, (addr >> 8) & 0xff , addr & 0xff}; + + /* Can only write one page at a time */ + if(len > 0x100) + return -2; + + /* Ensure number of bytes fits after starting address before end of page */ + if(((addr & 0xff) + len) > 0x100) + return -3; + + if((ret = PIOS_Flash_Jedec_WriteEnable()) != 0) + return ret; + + /* Execute write page command and clock in address. Keep CS asserted */ + if(PIOS_Flash_Jedec_ClaimBus() != 0) + return -1; + + if(PIOS_SPI_TransferBlock(flash_dev->spi_id,out,NULL,sizeof(out),NULL) < 0) { + PIOS_Flash_Jedec_ReleaseBus(); + return -1; + } + + /* Clock out data to flash */ + if(PIOS_SPI_TransferBlock(flash_dev->spi_id,data,NULL,len,NULL) < 0) { + PIOS_Flash_Jedec_ReleaseBus(); + return -1; + } + + PIOS_Flash_Jedec_ReleaseBus(); + + // Keep polling when bus is busy too +#if defined(FLASH_FREERTOS) + while(PIOS_Flash_Jedec_Busy() != 0) { + vTaskDelay(1); + } +#else + + // Query status this way to prevent accel chip locking us out + if(PIOS_Flash_Jedec_ClaimBus() < 0) + return -1; + + PIOS_SPI_TransferByte(flash_dev->spi_id, JEDEC_READ_STATUS); + while(PIOS_SPI_TransferByte(flash_dev->spi_id, JEDEC_READ_STATUS) & JEDEC_STATUS_BUSY); + + PIOS_Flash_Jedec_ReleaseBus(); + +#endif + return 0; +} + +/** + * @brief Write multiple chunks of data in one transaction + * @param[in] addr Address in flash to write to + * @param[in] data Pointer to data to write to flash + * @param[in] len Length of data to write (max 256 bytes) + * @return Zero if success or error code + * @retval -1 Unable to claim SPI bus + * @retval -2 Size exceeds 256 bytes + * @retval -3 Length to write would wrap around page boundary + */ +int32_t PIOS_Flash_Jedec_WriteChunks(uint32_t addr, struct pios_flash_chunk * p_chunk, uint32_t num) +{ + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + + uint8_t ret; + uint8_t out[4] = {JEDEC_PAGE_WRITE, (addr >> 16) & 0xff, (addr >> 8) & 0xff , addr & 0xff}; + + /* Can only write one page at a time */ + uint32_t len = 0; + for(uint32_t i = 0; i < num; i++) + len += p_chunk[i].len; + + if(len > 0x100) + return -2; + + /* Ensure number of bytes fits after starting address before end of page */ + if(((addr & 0xff) + len) > 0x100) + return -3; + + if((ret = PIOS_Flash_Jedec_WriteEnable()) != 0) + return ret; + + /* Execute write page command and clock in address. Keep CS asserted */ + if(PIOS_Flash_Jedec_ClaimBus() != 0) + return -1; + + if(PIOS_SPI_TransferBlock(flash_dev->spi_id,out,NULL,sizeof(out),NULL) < 0) { + PIOS_Flash_Jedec_ReleaseBus(); + return -1; + } + + for(uint32_t i = 0; i < num; i++) { + struct pios_flash_chunk * chunk = &p_chunk[i]; + + /* Clock out data to flash */ + if(PIOS_SPI_TransferBlock(flash_dev->spi_id,chunk->addr,NULL,chunk->len,NULL) < 0) { + PIOS_Flash_Jedec_ReleaseBus(); + return -1; + } + + } + PIOS_Flash_Jedec_ReleaseBus(); + + // Skip checking for busy with this to get OS running again fast + + return 0; +} + +/** + * @brief Read data from a location in flash memory + * @param[in] addr Address in flash to write to + * @param[in] data Pointer to data to write from flash + * @param[in] len Length of data to write (max 256 bytes) + * @return Zero if success or error code + * @retval -1 Unable to claim SPI bus + */ +int32_t PIOS_Flash_Jedec_ReadData(uint32_t addr, uint8_t * data, uint16_t len) +{ + if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) + return -1; + + if(PIOS_Flash_Jedec_ClaimBus() == -1) + return -1; + + /* Execute read command and clock in address. Keep CS asserted */ + uint8_t out[] = {JEDEC_READ_DATA, (addr >> 16) & 0xff, (addr >> 8) & 0xff , addr & 0xff}; + + if(PIOS_SPI_TransferBlock(flash_dev->spi_id,out,NULL,sizeof(out),NULL) < 0) { + PIOS_Flash_Jedec_ReleaseBus(); + return -2; + } + + /* Copy the transfer data to the buffer */ + if(PIOS_SPI_TransferBlock(flash_dev->spi_id,NULL,data,len,NULL) < 0) { + PIOS_Flash_Jedec_ReleaseBus(); + return -3; + } + + PIOS_Flash_Jedec_ReleaseBus(); + + return 0; +} diff --git a/flight/PiOS/Common/pios_flash_w25x.c b/flight/PiOS/Common/pios_flash_w25x.c deleted file mode 100644 index f474beb3f..000000000 --- a/flight/PiOS/Common/pios_flash_w25x.c +++ /dev/null @@ -1,249 +0,0 @@ -/* - * pios_flash_w25x.c - * OpenPilotOSX - * - * Created by James Cotton on 1/23/11. - * Copyright 2011 OpenPilot. All rights reserved. - * - */ - -#include "pios.h" -#include "pios_flash_w25x.h" -#include "pios_adxl345.h" - -#define W25X_WRITE_ENABLE 0x06 -#define W25X_WRITE_DISABLE 0x04 -#define W25X_READ_STATUS 0x05 -#define W25X_WRITE_STATUS 0x01 -#define W25X_READ_DATA 0x03 -#define W25X_FAST_READ 0x0b -#define W25X_DEVICE_ID 0x90 -#define W25X_SECTOR_ERASE 0x20 -#define W25X_PAGE_WRITE 0x02 -#define W25X_CHIP_ERASE 0x60 - -#define W25X_STATUS_BUSY 0x01 -#define W25X_STATUS_WRITEPROTECT 0x02 -#define W25X_STATUS_BP0 0x04 -#define W25X_STATUS_BP1 0x08 -#define W25X_STATUS_BP2 0x10 -#define W25X_STATUS_TP 0x20 -#define W25X_STATUS_SEC 0x40 -#define W25X_STATUS_SRP0 0x80 - -static uint8_t device_type; - -//! Private functions -static int8_t PIOS_Flash_W25X_ClaimBus(); -static void PIOS_Flash_W25X_ReleaseBus(); -static uint8_t PIOS_Flash_W25X_WriteEnable(); -static uint8_t PIOS_Flash_W25X_Busy() ; - -static uint32_t PIOS_SPI_FLASH; - -/** - * @brief Claim the SPI bus for flash use and assert CS pin - * @return 0 for sucess, -1 for failure to get semaphore - */ -static int8_t PIOS_Flash_W25X_ClaimBus() -{ - int8_t ret = PIOS_SPI_ClaimBus(PIOS_SPI_FLASH); - PIOS_FLASH_ENABLE; - return (ret == 0) ? 0 : -1; -} - -/** - * @brief Release the SPI bus sempahore and ensure flash chip not using bus - */ -static void PIOS_Flash_W25X_ReleaseBus() -{ - PIOS_FLASH_DISABLE; - PIOS_SPI_ReleaseBus(PIOS_SPI_FLASH); -} - -/** - * @brief Returns if the flash chip is busy - */ -static uint8_t PIOS_Flash_W25X_Busy() -{ - return PIOS_Flash_W25X_ReadStatus() & W25X_STATUS_BUSY; -} - -/** - * @brief Execute the write enable instruction and returns the status - * @returns 0 if successful, -1 if unable to claim bus - */ -static uint8_t PIOS_Flash_W25X_WriteEnable() -{ - uint8_t out[] = {W25X_WRITE_ENABLE}; - if(PIOS_Flash_W25X_ClaimBus() != 0) - return -1; - PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL); - PIOS_Flash_W25X_ReleaseBus(); - return 0; -} - -/** - * @brief Initialize the flash device and enable write access - */ -int8_t PIOS_Flash_W25X_Init(uint32_t spi_id) -{ - PIOS_SPI_FLASH = spi_id; - - PIOS_GPIO_Enable(PIOS_FLASH_CS_PIN); - device_type = PIOS_Flash_W25X_ReadID(); - return 0; -} - - -/** - * @brief Read the status register from flash chip and return it - */ -uint8_t PIOS_Flash_W25X_ReadStatus() -{ - uint8_t out[2] = {W25X_READ_STATUS, 0}; - uint8_t in[2] = {0,0}; - PIOS_Flash_W25X_ClaimBus(); - PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,in,sizeof(out),NULL); - PIOS_Flash_W25X_ReleaseBus(); - return in[1]; -} - -/** - * @brief Read the status register from flash chip and return it - */ -uint8_t PIOS_Flash_W25X_ReadID() -{ - uint8_t out[] = {W25X_DEVICE_ID, 0, 0, 0, 0, 0}; - uint8_t in[6]; - PIOS_Flash_W25X_ClaimBus(); - PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,in,sizeof(out),NULL); - PIOS_Flash_W25X_ReleaseBus(); - return in[5]; -} - -/** - * @brief Erase a sector on the flash chip - * @param[in] add Address of flash to erase - * @returns 0 if successful - * @retval -1 if unable to claim bus - * @retval - */ -int8_t PIOS_Flash_W25X_EraseSector(uint32_t addr) -{ - uint8_t ret; - uint8_t out[] = {W25X_SECTOR_ERASE, (addr >> 16) & 0xff, (addr >> 8) & 0xff , addr & 0xff}; - - if((ret = PIOS_Flash_W25X_WriteEnable()) != 0) - return ret; - - if(PIOS_Flash_W25X_ClaimBus() != 0) - return -1; - PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL); - PIOS_Flash_W25X_ReleaseBus(); - - uint32_t i = 1; - while(PIOS_Flash_W25X_Busy()) { - if(++i == 0) - return -1; - } - - return 0; -} - -/** - * @brief Execute the whole chip - * @returns 0 if successful, -1 if unable to claim bus - */ -int8_t PIOS_Flash_W25X_EraseChip() -{ - uint8_t ret; - uint8_t out[] = {W25X_CHIP_ERASE}; - - if((ret = PIOS_Flash_W25X_WriteEnable()) != 0) - return ret; - - if(PIOS_Flash_W25X_ClaimBus() != 0) - return -1; - PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL); - PIOS_Flash_W25X_ReleaseBus(); - - uint32_t i = 1; - while(PIOS_Flash_W25X_Busy()) { - if(++i == 0) - return -1; - } - - return 0; -} - - -/** - * @brief Write one page of data (up to 256 bytes) aligned to a page start - * @param[in] addr Address in flash to write to - * @param[in] data Pointer to data to write to flash - * @param[in] len Length of data to write (max 256 bytes) - * @return Zero if success or error code - * @retval -1 Unable to claim SPI bus - * @retval -2 Size exceeds 256 bytes - * @retval -3 Length to write would wrap around page boundary - */ -int8_t PIOS_Flash_W25X_WriteData(uint32_t addr, uint8_t * data, uint16_t len) -{ - uint8_t ret; - uint8_t out[4] = {W25X_PAGE_WRITE, (addr >> 16) & 0xff, (addr >> 8) & 0xff , addr & 0xff}; - - /* Can only write one page at a time */ - if(len > 0x100) - return -2; - - /* Ensure number of bytes fits after starting address before end of page */ - if(((addr & 0xff) + len) > 0x100) - return -3; - - if((ret = PIOS_Flash_W25X_WriteEnable()) != 0) - return ret; - - /* Execute write page command and clock in address. Keep CS asserted */ - if(PIOS_Flash_W25X_ClaimBus() != 0) - return -1; - PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL); - - /* Clock out data to flash */ - PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,data,NULL,len,NULL); - - PIOS_Flash_W25X_ReleaseBus(); - - uint32_t i = 1; - while(PIOS_Flash_W25X_Busy()) { - if(++i == 0) - return -1; - } - - return 0; -} - -/** - * @brief Read data from a location in flash memory - * @param[in] addr Address in flash to write to - * @param[in] data Pointer to data to write from flash - * @param[in] len Length of data to write (max 256 bytes) - * @return Zero if success or error code - * @retval -1 Unable to claim SPI bus - */ -int8_t PIOS_Flash_W25X_ReadData(uint32_t addr, uint8_t * data, uint16_t len) -{ - if(PIOS_Flash_W25X_ClaimBus() == -1) - return -1; - - /* Execute read command and clock in address. Keep CS asserted */ - uint8_t out[] = {W25X_READ_DATA, (addr >> 16) & 0xff, (addr >> 8) & 0xff , addr & 0xff}; - PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL); - - /* Copy the transfer data to the buffer */ - PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,NULL,data,len,NULL); - - PIOS_Flash_W25X_ReleaseBus(); - - return 0; -} diff --git a/flight/PiOS/Common/pios_flashfs_objlist.c b/flight/PiOS/Common/pios_flashfs_objlist.c index b4322ab78..4111eb029 100644 --- a/flight/PiOS/Common/pios_flashfs_objlist.c +++ b/flight/PiOS/Common/pios_flashfs_objlist.c @@ -56,31 +56,29 @@ struct fileHeader { } __attribute__((packed)); -#define OBJECT_TABLE_MAGIC 0x85FB3D35 -#define OBJ_MAGIC 0x3015A371 -#define OBJECT_TABLE_START 0x00000010 -#define OBJECT_TABLE_END 0x00001000 -#define SECTOR_SIZE 0x00001000 #define MAX_BADMAGIC 1000 +static const struct flashfs_cfg * cfg; /** * @brief Initialize the flash object setting FS * @return 0 if success, -1 if failure */ -int32_t PIOS_FLASHFS_Init() +int32_t PIOS_FLASHFS_Init(const struct flashfs_cfg * new_cfg) { - + cfg = new_cfg; + // Check for valid object table or create one uint32_t object_table_magic; uint32_t magic_fail_count = 0; bool magic_good = false; while(!magic_good) { - if (PIOS_Flash_W25X_ReadData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)) != 0) + if (PIOS_Flash_Jedec_ReadData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)) != 0) return -1; - if(object_table_magic != OBJECT_TABLE_MAGIC) { + if(object_table_magic != new_cfg->table_magic) { if(magic_fail_count++ > MAX_BADMAGIC) { - PIOS_FLASHFS_ClearObjectTableHeader(); + if(PIOS_FLASHFS_Format() != 0) + return -1; #if defined(PIOS_LED_HEARTBEAT) PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); #endif /* PIOS_LED_HEARTBEAT */ @@ -89,7 +87,6 @@ int32_t PIOS_FLASHFS_Init() } else { PIOS_DELAY_WaituS(1000); } - } else { magic_good = true; @@ -97,18 +94,18 @@ int32_t PIOS_FLASHFS_Init() } - int32_t addr = OBJECT_TABLE_START; + int32_t addr = cfg->obj_table_start; struct objectHeader header; numObjects = 0; // Loop through header area while objects detect to count how many saved - while(addr < OBJECT_TABLE_END) { + while(addr < cfg->obj_table_end) { // Read the instance data - if (PIOS_Flash_W25X_ReadData(addr, (uint8_t *)&header, sizeof(header)) != 0) + if (PIOS_Flash_Jedec_ReadData(addr, (uint8_t *)&header, sizeof(header)) != 0) return -1; // Counting number of valid headers - if(header.objMagic != OBJ_MAGIC) + if(header.objMagic != cfg->obj_magic) break; numObjects++; @@ -124,7 +121,7 @@ int32_t PIOS_FLASHFS_Init() */ int32_t PIOS_FLASHFS_Format() { - if(PIOS_Flash_W25X_EraseChip() != 0) + if(PIOS_Flash_Jedec_EraseChip() != 0) return -1; if(PIOS_FLASHFS_ClearObjectTableHeader() != 0) return -1; @@ -137,11 +134,15 @@ int32_t PIOS_FLASHFS_Format() */ static int32_t PIOS_FLASHFS_ClearObjectTableHeader() { - if(PIOS_Flash_W25X_EraseSector(0) != 0) + if(PIOS_Flash_Jedec_EraseSector(0) != 0) return -1; - uint32_t object_table_magic = OBJECT_TABLE_MAGIC; - if (PIOS_Flash_W25X_WriteData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)) != 0) + if (PIOS_Flash_Jedec_WriteData(0, (uint8_t *)&cfg->table_magic, sizeof(cfg->table_magic)) != 0) + return -1; + + uint32_t object_table_magic; + PIOS_Flash_Jedec_ReadData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)); + if(object_table_magic != cfg->table_magic) return -1; return 0; @@ -155,15 +156,15 @@ static int32_t PIOS_FLASHFS_ClearObjectTableHeader() */ static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId) { - int32_t addr = OBJECT_TABLE_START; + int32_t addr = cfg->obj_table_start; struct objectHeader header; // Loop through header area while objects detect to count how many saved - while(addr < OBJECT_TABLE_END) { + while(addr < cfg->obj_table_end) { // Read the instance data - if (PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0) + if (PIOS_Flash_Jedec_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0) return -1; - if(header.objMagic != OBJ_MAGIC) + if(header.objMagic != cfg->obj_magic) break; // stop searching once hit first non-object header else if (header.objId == objId && header.instId == instId) break; @@ -185,6 +186,7 @@ static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId) * @retval -2 No room in object table * @retval -3 Unable to write entry into object table * @retval -4 FS not initialized + * @retval -5 */ int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId) { @@ -194,18 +196,22 @@ int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId) return -4; // Don't worry about max size of flash chip here, other code will catch that - header.objMagic = OBJ_MAGIC; + header.objMagic = cfg->obj_magic; header.objId = objId; header.instId = instId; - header.address = OBJECT_TABLE_END + SECTOR_SIZE * numObjects; + header.address = cfg->obj_table_end + cfg->sector_size * numObjects; - int32_t addr = OBJECT_TABLE_START + sizeof(header) * numObjects; + int32_t addr = cfg->obj_table_start + sizeof(header) * numObjects; // No room for this header in object table - if((addr + sizeof(header)) > OBJECT_TABLE_END) + if((addr + sizeof(header)) > cfg->obj_table_end) return -2; - if(PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0) + // Verify the address is within the chip + if((addr + cfg->sector_size) > cfg->chip_size) + return -5; + + if(PIOS_Flash_Jedec_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0) return -3; // This numObejcts value must stay consistent or there will be a break in the table @@ -228,6 +234,9 @@ int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data) uint32_t objId = UAVObjGetID(obj); uint8_t crc = 0; + if(PIOS_Flash_Jedec_StartTransaction() != 0) + return -1; + int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId); // Object currently not saved @@ -235,36 +244,50 @@ int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data) addr = PIOS_FLASHFS_GetNewAddress(objId, instId); // Could not allocate a sector - if(addr < 0) + if(addr < 0) { + PIOS_Flash_Jedec_EndTransaction(); return -1; + } struct fileHeader header = { .id = objId, .instId = instId, .size = UAVObjGetNumBytes(obj) }; - - if(PIOS_Flash_W25X_EraseSector(addr) != 0) - return -2; - - // Save header - // This information IS redundant with the object table id. Oh well. Better safe than sorry. - if(PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0) - return -3; - + // Update CRC crc = PIOS_CRC_updateCRC(0, (uint8_t *) &header, sizeof(header)); - - // Save data - if(PIOS_Flash_W25X_WriteData(addr + sizeof(header), data, UAVObjGetNumBytes(obj)) != 0) - return -4; - - // Update CRC crc = PIOS_CRC_updateCRC(crc, (uint8_t *) data, UAVObjGetNumBytes(obj)); - // Save CRC (written so will work when CRC changes to uint16) - if(PIOS_Flash_W25X_WriteData(addr + sizeof(header) + UAVObjGetNumBytes(obj), (uint8_t *) &crc, sizeof(crc)) != 0) - return -4; + if(PIOS_Flash_Jedec_EraseSector(addr) != 0) { + PIOS_Flash_Jedec_EndTransaction(); + return -2; + } + + struct pios_flash_chunk chunks[3] = { + { + .addr = (uint8_t *) &header, + .len = sizeof(header), + }, + { + .addr = (uint8_t *) data, + .len = UAVObjGetNumBytes(obj) + }, + { + .addr = (uint8_t *) &crc, + .len = sizeof(crc) + } + }; + + if(PIOS_Flash_Jedec_WriteChunks(addr, chunks, NELEMENTS(chunks)) != 0) { + PIOS_Flash_Jedec_EndTransaction(); + return -1; + } + + if(PIOS_Flash_Jedec_EndTransaction() != 0) { + PIOS_Flash_Jedec_EndTransaction(); + return -1; + } return 0; } @@ -292,43 +315,61 @@ int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data) const uint8_t crc_read_step = 8; uint8_t crc_read_buffer[crc_read_step]; + if(PIOS_Flash_Jedec_StartTransaction() != 0) + return -1; + int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId); // Object currently not saved - if(addr < 0) + if(addr < 0) { + PIOS_Flash_Jedec_EndTransaction(); return -1; + } struct fileHeader header; // Load header // This information IS redundant with the object table id. Oh well. Better safe than sorry. - if(PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0) + if(PIOS_Flash_Jedec_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0) { + PIOS_Flash_Jedec_EndTransaction(); return -2; - + } + // Update CRC crc = PIOS_CRC_updateCRC(0, (uint8_t *) &header, sizeof(header)); - if((header.id != objId) || (header.instId != instId)) + if((header.id != objId) || (header.instId != instId)) { + PIOS_Flash_Jedec_EndTransaction(); return -3; - + } + // To avoid having to allocate the RAM for a copy of the object, we read by chunks // and compute the CRC for(uint32_t i = 0; i < objSize; i += crc_read_step) { - PIOS_Flash_W25X_ReadData(addr + sizeof(header) + i, crc_read_buffer, crc_read_step); + PIOS_Flash_Jedec_ReadData(addr + sizeof(header) + i, crc_read_buffer, crc_read_step); uint8_t valid_bytes = ((i + crc_read_step) >= objSize) ? objSize - i : crc_read_step; crc = PIOS_CRC_updateCRC(crc, crc_read_buffer, valid_bytes); } // Read CRC (written so will work when CRC changes to uint16) - if(PIOS_Flash_W25X_ReadData(addr + sizeof(header) + objSize, (uint8_t *) &crcFlash, sizeof(crcFlash)) != 0) + if(PIOS_Flash_Jedec_ReadData(addr + sizeof(header) + objSize, (uint8_t *) &crcFlash, sizeof(crcFlash)) != 0) { + PIOS_Flash_Jedec_EndTransaction(); return -5; + } - if(crc != crcFlash) + if(crc != crcFlash) { + PIOS_Flash_Jedec_EndTransaction(); return -6; + } // Read the instance data - if (PIOS_Flash_W25X_ReadData(addr + sizeof(header), data, objSize) != 0) + if (PIOS_Flash_Jedec_ReadData(addr + sizeof(header), data, objSize) != 0) { + PIOS_Flash_Jedec_EndTransaction(); return -4; + } + + if(PIOS_Flash_Jedec_EndTransaction() != 0) + return -1; return 0; } @@ -354,7 +395,7 @@ int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId) if(addr < 0) return -1; - if(PIOS_Flash_W25X_EraseSector(addr) != 0) + if(PIOS_Flash_Jedec_EraseSector(addr) != 0) return -2; return 0; diff --git a/flight/PiOS/Common/pios_gcsrcvr.c b/flight/PiOS/Common/pios_gcsrcvr.c index ad34b5c20..eda2a94ed 100644 --- a/flight/PiOS/Common/pios_gcsrcvr.c +++ b/flight/PiOS/Common/pios_gcsrcvr.c @@ -152,10 +152,9 @@ static void PIOS_gcsrcvr_Supervisor(uint32_t gcsrcvr_id) { } /* - * RTC runs at 625Hz so divide down the base rate so - * that this loop runs at 25Hz. + * RTC runs at 625Hz. */ - if(++(gcsrcvr_dev->supv_timer) < 25) { + if(++(gcsrcvr_dev->supv_timer) < (PIOS_GCSRCVR_TIMEOUT_MS * 1000 / 625)) { return; } gcsrcvr_dev->supv_timer = 0; diff --git a/flight/PiOS/Common/pios_hmc5843.c b/flight/PiOS/Common/pios_hmc5843.c index 688d2e90f..4f6b562d6 100644 --- a/flight/PiOS/Common/pios_hmc5843.c +++ b/flight/PiOS/Common/pios_hmc5843.c @@ -318,7 +318,7 @@ bool PIOS_HMC5843_NewDataAvailable(void) * \param[in] len number of bytes which should be read * \return 0 if operation was successful * \return -1 if error during I2C transfer -* \return -4 if invalid length +* \return -2 if unable to claim i2c device */ static bool PIOS_HMC5843_Read(uint8_t address, uint8_t * buffer, uint8_t len) { @@ -352,7 +352,8 @@ static bool PIOS_HMC5843_Read(uint8_t address, uint8_t * buffer, uint8_t len) * \param[in] address Register address * \param[in] buffer source buffer * \return 0 if operation was successful -* \return -1 if error during I2C transfer +* \retval -1 if error during I2C transfer +* \retval -2 if unable to claim i2c device */ static bool PIOS_HMC5843_Write(uint8_t address, uint8_t buffer) { diff --git a/flight/PiOS/Common/pios_hmc5883.c b/flight/PiOS/Common/pios_hmc5883.c index 3ac97698b..8891709fc 100644 --- a/flight/PiOS/Common/pios_hmc5883.c +++ b/flight/PiOS/Common/pios_hmc5883.c @@ -5,10 +5,8 @@ * @addtogroup PIOS_HMC5883 HMC5883 Functions * @brief Deals with the hardware interface to the magnetometers * @{ - * * @file pios_hmc5883.c - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief HMC5883 Magnetic Sensor Functions from AHRS * @see The GNU Public License (GPL) Version 3 * @@ -38,61 +36,30 @@ /* Global Variables */ /* Local Types */ -typedef struct { - uint8_t M_ODR; /* OUTPUT DATA RATE --> here below the relative define (See datasheet page 11 for more details) */ - uint8_t Meas_Conf; /* Measurement Configuration,: Normal, positive bias, or negative bias --> here below the relative define */ - uint8_t Gain; /* Gain Configuration, select the full scale --> here below the relative define (See datasheet page 11 for more details) */ - uint8_t Mode; -} PIOS_HMC5883_ConfigTypeDef; /* Local Variables */ volatile bool pios_hmc5883_data_ready; -static void PIOS_HMC5883_Config(PIOS_HMC5883_ConfigTypeDef * HMC5883_Config_Struct); -static bool PIOS_HMC5883_Read(uint8_t address, uint8_t * buffer, uint8_t len); -static bool PIOS_HMC5883_Write(uint8_t address, uint8_t buffer); +static int32_t PIOS_HMC5883_Config(const struct pios_hmc5883_cfg * cfg); +static int32_t PIOS_HMC5883_Read(uint8_t address, uint8_t * buffer, uint8_t len); +static int32_t PIOS_HMC5883_Write(uint8_t address, uint8_t buffer); + +static const struct pios_hmc5883_cfg * dev_cfg; /** * @brief Initialize the HMC5883 magnetometer sensor. * @return none */ -void PIOS_HMC5883_Init(void) +void PIOS_HMC5883_Init(const struct pios_hmc5883_cfg * cfg) { - GPIO_InitTypeDef GPIO_InitStructure; - EXTI_InitTypeDef EXTI_InitStructure; - NVIC_InitTypeDef NVIC_InitStructure; - - /* Enable DRDY GPIO clock */ - RCC_APB2PeriphClockCmd(PIOS_HMC5883_DRDY_CLK | RCC_APB2Periph_AFIO, ENABLE); - - /* Configure EOC pin as input floating */ - GPIO_InitStructure.GPIO_Pin = PIOS_HMC5883_DRDY_GPIO_PIN; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; - GPIO_Init(PIOS_HMC5883_DRDY_GPIO_PORT, &GPIO_InitStructure); - - /* Configure the End Of Conversion (EOC) interrupt */ - GPIO_EXTILineConfig(PIOS_HMC5883_DRDY_PORT_SOURCE, PIOS_HMC5883_DRDY_PIN_SOURCE); - EXTI_InitStructure.EXTI_Line = PIOS_HMC5883_DRDY_EXTI_LINE; - EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; - EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising; - EXTI_InitStructure.EXTI_LineCmd = ENABLE; - EXTI_Init(&EXTI_InitStructure); - - /* Enable and set EOC EXTI Interrupt to the lowest priority */ - NVIC_InitStructure.NVIC_IRQChannel = PIOS_HMC5883_DRDY_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_HMC5883_DRDY_PRIO; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); - - /* Configure the HMC5883 Sensor */ - PIOS_HMC5883_ConfigTypeDef HMC5883_InitStructure; - HMC5883_InitStructure.M_ODR = PIOS_HMC5883_ODR_15; - HMC5883_InitStructure.Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL; - HMC5883_InitStructure.Gain = PIOS_HMC5883_GAIN_1_9; - HMC5883_InitStructure.Mode = PIOS_HMC5883_MODE_CONTINUOUS; - PIOS_HMC5883_Config(&HMC5883_InitStructure); + dev_cfg = cfg; // store config before enabling interrupt + PIOS_EXTI_Init(cfg->exti_cfg); + + int32_t val = PIOS_HMC5883_Config(cfg); + + PIOS_Assert(val == 0); + pios_hmc5883_data_ready = false; } @@ -100,247 +67,271 @@ void PIOS_HMC5883_Init(void) * @brief Initialize the HMC5883 magnetometer sensor * \return none * \param[in] PIOS_HMC5883_ConfigTypeDef struct to be used to configure sensor. -* -* CTRL_REGA: Control Register A -* Read Write -* Default value: 0x10 -* 7:5 0 These bits must be cleared for correct operation. -* 4:2 DO2-DO0: Data Output Rate Bits -* DO2 | DO1 | DO0 | Minimum Data Output Rate (Hz) -* ------------------------------------------------------ -* 0 | 0 | 0 | 0.75 -* 0 | 0 | 1 | 1.5 -* 0 | 1 | 0 | 3 -* 0 | 1 | 1 | 7.5 -* 1 | 0 | 0 | 15 (default) -* 1 | 0 | 1 | 30 -* 1 | 1 | 0 | 75 -* 1 | 1 | 1 | Not Used -* 1:0 MS1-MS0: Measurement Configuration Bits -* MS1 | MS0 | MODE -* ------------------------------ -* 0 | 0 | Normal -* 0 | 1 | Positive Bias -* 1 | 0 | Negative Bias -* 1 | 1 | Not Used -* -* CTRL_REGB: Control RegisterB -* Read Write -* Default value: 0x20 -* 7:5 GN2-GN0: Gain Configuration Bits. -* GN2 | GN1 | GN0 | Mag Input | Gain | Output Range -* | | | Range[Ga] | [LSB/mGa] | -* ------------------------------------------------------ -* 0 | 0 | 0 | ±0.88Ga | 1370 | 0xF800–0x07FF (-2048:2047) -* 0 | 0 | 1 | ±1.3Ga (def) | 1090 | 0xF800–0x07FF (-2048:2047) -* 0 | 1 | 0 | ±1.9Ga | 820 | 0xF800–0x07FF (-2048:2047) -* 0 | 1 | 1 | ±2.5Ga | 660 | 0xF800–0x07FF (-2048:2047) -* 1 | 0 | 0 | ±4.0Ga | 440 | 0xF800–0x07FF (-2048:2047) -* 1 | 0 | 1 | ±4.7Ga | 390 | 0xF800–0x07FF (-2048:2047) -* 1 | 1 | 0 | ±5.6Ga | 330 | 0xF800–0x07FF (-2048:2047) -* 1 | 1 | 1 | ±8.1Ga | 230 | 0xF800–0x07FF (-2048:2047) -* |Not recommended| -* -* 4:0 CRB4-CRB: 0 This bit must be cleared for correct operation. -* -* _MODE_REG: Mode Register -* Read Write -* Default value: 0x02 -* 7:2 0 These bits must be cleared for correct operation. -* 1:0 MD1-MD0: Mode Select Bits -* MS1 | MS0 | MODE -* ------------------------------ -* 0 | 0 | Continuous-Conversion Mode. -* 0 | 1 | Single-Conversion Mode -* 1 | 0 | Negative Bias -* 1 | 1 | Sleep Mode -*/ -static void PIOS_HMC5883_Config(PIOS_HMC5883_ConfigTypeDef * HMC5883_Config_Struct) + * + * CTRL_REGA: Control Register A + * Read Write + * Default value: 0x10 + * 7:5 0 These bits must be cleared for correct operation. + * 4:2 DO2-DO0: Data Output Rate Bits + * DO2 | DO1 | DO0 | Minimum Data Output Rate (Hz) + * ------------------------------------------------------ + * 0 | 0 | 0 | 0.75 + * 0 | 0 | 1 | 1.5 + * 0 | 1 | 0 | 3 + * 0 | 1 | 1 | 7.5 + * 1 | 0 | 0 | 15 (default) + * 1 | 0 | 1 | 30 + * 1 | 1 | 0 | 75 + * 1 | 1 | 1 | Not Used + * 1:0 MS1-MS0: Measurement Configuration Bits + * MS1 | MS0 | MODE + * ------------------------------ + * 0 | 0 | Normal + * 0 | 1 | Positive Bias + * 1 | 0 | Negative Bias + * 1 | 1 | Not Used + * + * CTRL_REGB: Control RegisterB + * Read Write + * Default value: 0x20 + * 7:5 GN2-GN0: Gain Configuration Bits. + * GN2 | GN1 | GN0 | Mag Input | Gain | Output Range + * | | | Range[Ga] | [LSB/mGa] | + * ------------------------------------------------------ + * 0 | 0 | 0 | ±0.88Ga | 1370 | 0xF800–0x07FF (-2048:2047) + * 0 | 0 | 1 | ±1.3Ga (def) | 1090 | 0xF800–0x07FF (-2048:2047) + * 0 | 1 | 0 | ±1.9Ga | 820 | 0xF800–0x07FF (-2048:2047) + * 0 | 1 | 1 | ±2.5Ga | 660 | 0xF800–0x07FF (-2048:2047) + * 1 | 0 | 0 | ±4.0Ga | 440 | 0xF800–0x07FF (-2048:2047) + * 1 | 0 | 1 | ±4.7Ga | 390 | 0xF800–0x07FF (-2048:2047) + * 1 | 1 | 0 | ±5.6Ga | 330 | 0xF800–0x07FF (-2048:2047) + * 1 | 1 | 1 | ±8.1Ga | 230 | 0xF800–0x07FF (-2048:2047) + * |Not recommended| + * + * 4:0 CRB4-CRB: 0 This bit must be cleared for correct operation. + * + * _MODE_REG: Mode Register + * Read Write + * Default value: 0x02 + * 7:2 0 These bits must be cleared for correct operation. + * 1:0 MD1-MD0: Mode Select Bits + * MS1 | MS0 | MODE + * ------------------------------ + * 0 | 0 | Continuous-Conversion Mode. + * 0 | 1 | Single-Conversion Mode + * 1 | 0 | Negative Bias + * 1 | 1 | Sleep Mode + */ +static uint8_t CTRLB = 0x00; +static int32_t PIOS_HMC5883_Config(const struct pios_hmc5883_cfg * cfg) { uint8_t CTRLA = 0x00; - uint8_t CTRLB = 0x00; uint8_t MODE = 0x00; - - CTRLA |= (uint8_t) (HMC5883_Config_Struct->M_ODR | HMC5883_Config_Struct->Meas_Conf); - CTRLB |= (uint8_t) (HMC5883_Config_Struct->Gain); - MODE |= (uint8_t) (HMC5883_Config_Struct->Mode); - + CTRLB = 0; + + CTRLA |= (uint8_t) (cfg->M_ODR | cfg->Meas_Conf); + CTRLB |= (uint8_t) (cfg->Gain); + MODE |= (uint8_t) (cfg->Mode); + // CRTL_REGA - while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A, CTRLA)) ; - + if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A, CTRLA) != 0) + return -1; + // CRTL_REGB - while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B, CTRLB)) ; - + if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B, CTRLB) != 0) + return -1; + // Mode register - while (!PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, MODE)) ; + if (PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, MODE) != 0) + return -1; + + return 0; } /** * @brief Read current X, Z, Y values (in that order) * \param[out] int16_t array of size 3 to store X, Z, and Y magnetometer readings - * \return none -*/ -void PIOS_HMC5883_ReadMag(int16_t out[3]) + * \return 0 for success or -1 for failure + */ +int32_t PIOS_HMC5883_ReadMag(int16_t out[3]) { - uint8_t buffer[6]; - uint8_t ctrlB; - pios_hmc5883_data_ready = false; - - while (!PIOS_HMC5883_Read(PIOS_HMC5883_CONFIG_REG_B, &ctrlB, 1)) ; - while (!PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_XMSB_REG, buffer, 6)) ; - - switch (ctrlB & 0xE0) { - case 0x00: - for (int i = 0; i < 3; i++) - out[i] = ((int16_t) ((uint16_t) buffer[2 * i] << 8) - + buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_0_88Ga; - break; - case 0x20: - for (int i = 0; i < 3; i++) - out[i] = ((int16_t) ((uint16_t) buffer[2 * i] << 8) - + buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_1_3Ga; - break; - case 0x40: - for (int i = 0; i < 3; i++) - out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8) - + buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_1_9Ga; - break; - case 0x60: - for (int i = 0; i < 3; i++) - out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8) - + buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_2_5Ga; - break; - case 0x80: - for (int i = 0; i < 3; i++) - out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8) - + buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_4_0Ga; - break; - case 0xA0: - for (int i = 0; i < 3; i++) - out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8) - + buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_4_7Ga; - break; - case 0xC0: - for (int i = 0; i < 3; i++) - out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8) - + buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_5_6Ga; - break; - case 0xE0: - for (int i = 0; i < 3; i++) - out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8) - + buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_8_1Ga; - break; + uint8_t buffer[6]; + int32_t temp; + int32_t sensitivity; + + if (PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_XMSB_REG, buffer, 6) != 0) { + return -1; } + + switch (CTRLB & 0xE0) { + case 0x00: + sensitivity = PIOS_HMC5883_Sensitivity_0_88Ga; + break; + case 0x20: + sensitivity = PIOS_HMC5883_Sensitivity_1_3Ga; + break; + case 0x40: + sensitivity = PIOS_HMC5883_Sensitivity_1_9Ga; + break; + case 0x60: + sensitivity = PIOS_HMC5883_Sensitivity_2_5Ga; + break; + case 0x80: + sensitivity = PIOS_HMC5883_Sensitivity_4_0Ga; + break; + case 0xA0: + sensitivity = PIOS_HMC5883_Sensitivity_4_7Ga; + break; + case 0xC0: + sensitivity = PIOS_HMC5883_Sensitivity_5_6Ga; + break; + case 0xE0: + sensitivity = PIOS_HMC5883_Sensitivity_8_1Ga; + break; + default: + PIOS_Assert(0); + } + + for (int i = 0; i < 3; i++) { + temp = ((int16_t) ((uint16_t) buffer[2 * i] << 8) + + buffer[2 * i + 1]) * 1000 / sensitivity; + out[i] = temp; + } + // Data reads out as X,Z,Y + temp = out[2]; + out[2] = out[1]; + out[1] = temp; + + // This should not be necessary but for some reason it is coming out of continuous conversion mode + PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, PIOS_HMC5883_MODE_CONTINUOUS); + + return 0; } /** * @brief Read the identification bytes from the HMC5883 sensor * \param[out] uint8_t array of size 4 to store HMC5883 ID. - * \return none -*/ -void PIOS_HMC5883_ReadID(uint8_t out[4]) + * \return 0 if successful, -1 if not + */ +uint8_t PIOS_HMC5883_ReadID(uint8_t out[4]) { - while (!PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_IDA_REG, out, 3)) ; + uint8_t retval = PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_IDA_REG, out, 3); out[3] = '\0'; + return retval; } /** * @brief Tells whether new magnetometer readings are available * \return true if new data is available * \return false if new data is not available -*/ + */ bool PIOS_HMC5883_NewDataAvailable(void) { return (pios_hmc5883_data_ready); } /** -* @brief Reads one or more bytes into a buffer -* \param[in] address HMC5883 register address (depends on size) -* \param[out] buffer destination buffer -* \param[in] len number of bytes which should be read -* \return 0 if operation was successful -* \return -1 if error during I2C transfer -* \return -4 if invalid length -*/ -static bool PIOS_HMC5883_Read(uint8_t address, uint8_t * buffer, uint8_t len) + * @brief Reads one or more bytes into a buffer + * \param[in] address HMC5883 register address (depends on size) + * \param[out] buffer destination buffer + * \param[in] len number of bytes which should be read + * \return 0 if operation was successful + * \return -1 if error during I2C transfer + * \return -2 if unable to claim i2c device + */ +static int32_t PIOS_HMC5883_Read(uint8_t address, uint8_t * buffer, uint8_t len) { uint8_t addr_buffer[] = { address, }; - + const struct pios_i2c_txn txn_list[] = { { - .info = __func__, - .addr = PIOS_HMC5883_I2C_ADDR, - .rw = PIOS_I2C_TXN_WRITE, - .len = sizeof(addr_buffer), - .buf = addr_buffer, - } + .info = __func__, + .addr = PIOS_HMC5883_I2C_ADDR, + .rw = PIOS_I2C_TXN_WRITE, + .len = sizeof(addr_buffer), + .buf = addr_buffer, + } , { - .info = __func__, - .addr = PIOS_HMC5883_I2C_ADDR, - .rw = PIOS_I2C_TXN_READ, - .len = len, - .buf = buffer, - } + .info = __func__, + .addr = PIOS_HMC5883_I2C_ADDR, + .rw = PIOS_I2C_TXN_READ, + .len = len, + .buf = buffer, + } }; - + return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); } /** -* @brief Writes one or more bytes to the HMC5883 -* \param[in] address Register address -* \param[in] buffer source buffer -* \return 0 if operation was successful -* \return -1 if error during I2C transfer -*/ -static bool PIOS_HMC5883_Write(uint8_t address, uint8_t buffer) + * @brief Writes one or more bytes to the HMC5883 + * \param[in] address Register address + * \param[in] buffer source buffer + * \return 0 if operation was successful + * \return -1 if error during I2C transfer + * \return -2 if unable to claim i2c device + */ +static int32_t PIOS_HMC5883_Write(uint8_t address, uint8_t buffer) { uint8_t data[] = { address, buffer, }; - + const struct pios_i2c_txn txn_list[] = { { - .info = __func__, - .addr = PIOS_HMC5883_I2C_ADDR, - .rw = PIOS_I2C_TXN_WRITE, - .len = sizeof(data), - .buf = data, - } + .info = __func__, + .addr = PIOS_HMC5883_I2C_ADDR, + .rw = PIOS_I2C_TXN_WRITE, + .len = sizeof(data), + .buf = data, + } , }; - + ; return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); } /** * @brief Run self-test operation. Do not call this during operational use!! - * \return 0 if test failed - * \return non-zero value if test succeeded + * \return 0 if success, -1 if test failed */ int32_t PIOS_HMC5883_Test(void) { + int32_t failed = 0; + uint8_t registers[3] = {0,0,0}; + uint8_t status; + uint8_t ctrl_a_read; + uint8_t ctrl_b_read; + uint8_t mode_read; + int16_t values[3]; + + + /* Verify that ID matches (HMC5883 ID is null-terminated ASCII string "H43") */ char id[4]; PIOS_HMC5883_ReadID((uint8_t *)id); - if(!strncmp("H43\0",id,4)) - return 0; - else - return 1; - - int32_t passed = 1; - uint8_t registers[3] = {0,0,0}; - + if((id[0] != 'H') || (id[1] != '4') || (id[2] != '3')) // Expect H43 + return -1; + /* Backup existing configuration */ - while (!PIOS_HMC5883_Read(PIOS_HMC5883_CONFIG_REG_A,registers,3) ); - + if (PIOS_HMC5883_Read(PIOS_HMC5883_CONFIG_REG_A,registers,3) != 0) + return -1; + + /* Stop the device and read out last value */ + PIOS_DELAY_WaitmS(10); + if (PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, PIOS_HMC5883_MODE_IDLE) != 0) + return -1; + if( PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_STATUS_REG, &status,1) != 0) + return -1; + if (PIOS_HMC5883_ReadMag(values) != 0) + return -1; + /* * Put HMC5883 into self test mode * This is done by placing measurement config into positive (0x01) or negative (0x10) bias @@ -352,34 +343,54 @@ int32_t PIOS_HMC5883_Test(void) * * Changing measurement config back to PIOS_HMC5883_MEASCONF_NORMAL will leave self-test mode. */ - while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A, PIOS_HMC5883_MEASCONF_BIAS_POS | PIOS_HMC5883_ODR_15)) ; - while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B, PIOS_HMC5883_GAIN_2_5)) ; - while (!PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, PIOS_HMC5883_MODE_SINGLE)) ; - - uint8_t values[6]; - while (!PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_XMSB_REG, values, 6)) ; - int16_t x = (int16_t) (((uint16_t) values[0] << 8) + values[1]); - int16_t y = (int16_t) (((uint16_t) values[2] << 8) + values[3]); - int16_t z = (int16_t) (((uint16_t) values[4] << 8) + values[5]); - - if(abs(abs(x) - 766) > 20) - passed &= 0; - if(abs(abs(y) - 766) > 20) - passed &= 0; - if(abs(abs(z) - 713) > 20) - passed &= 0; - - /* Restore backup configuration */ - while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A,registers[0]) ); - while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B,registers[1]) ); - while (!PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG,registers[2]) ); - - return passed; + PIOS_DELAY_WaitmS(10); + if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A, PIOS_HMC5883_MEASCONF_BIAS_POS | PIOS_HMC5883_ODR_15) != 0) + return -1; + PIOS_DELAY_WaitmS(10); + if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B, PIOS_HMC5883_GAIN_8_1) != 0) + return -1; + PIOS_DELAY_WaitmS(10); + if (PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, PIOS_HMC5883_MODE_SINGLE) != 0) + return -1; + + /* Must wait for value to be updated */ + PIOS_DELAY_WaitmS(200); + + if (PIOS_HMC5883_ReadMag(values) != 0) + return -1; + + /* + if(abs(values[0] - 766) > 20) + failed |= 1; + if(abs(values[1] - 766) > 20) + failed |= 1; + if(abs(values[2] - 713) > 20) + failed |= 1; + */ + + PIOS_HMC5883_Read(PIOS_HMC5883_CONFIG_REG_A, &ctrl_a_read,1); + PIOS_HMC5883_Read(PIOS_HMC5883_CONFIG_REG_B, &ctrl_b_read,1); + PIOS_HMC5883_Read(PIOS_HMC5883_MODE_REG, &mode_read,1); + PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_STATUS_REG, &status,1); + + + /* Restore backup configuration */ + PIOS_DELAY_WaitmS(10); + if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A, registers[0]) != 0) + return -1; + PIOS_DELAY_WaitmS(10); + if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B, registers[1]) != 0) + return -1; + PIOS_DELAY_WaitmS(10); + if (PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, registers[2]) != 0) + return -1; + + return failed; } /** -* @brief IRQ Handler -*/ + * @brief IRQ Handler + */ void PIOS_HMC5883_IRQHandler(void) { pios_hmc5883_data_ready = true; diff --git a/flight/PiOS/Common/pios_imu3000.c b/flight/PiOS/Common/pios_imu3000.c deleted file mode 100644 index 79eaf36ca..000000000 --- a/flight/PiOS/Common/pios_imu3000.c +++ /dev/null @@ -1,238 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_IMU3000 IMU3000 Functions - * @brief Deals with the hardware interface to the 3-axis gyro - * @{ - * - * @file pios_IMU3000.c - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @brief IMU3000 3-axis gyor functions from INS - * @see The GNU Public License (GPL) Version 3 - * - ****************************************************************************** - */ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_IMU3000) - -/* Global Variables */ - -/* Local Types */ -typedef struct { - uint8_t Fifo_store; /* FIFO storage of different readings (See datasheet page 31 for more details) */ - uint8_t Smpl_rate_div; /* Sample rate divider to use (See datasheet page 32 for more details) */ - uint8_t DigLPF_Scale; /* Digital low-pass filter and full-range scale (See datasheet page 33 for more details) */ - uint8_t Interrupt_cfg; /* Interrupt configuration (See datasheet page 35 for more details) */ - uint8_t User_ctl; /* User control settings (See datasheet page 41 for more details) */ - uint8_t Pwr_mgmt_clk; /* Power management and clock selection (See datasheet page 32 for more details) */ -} PIOS_IMU3000_ConfigTypeDef; - -/* Local Variables */ - -static void PIOS_IMU3000_Config(PIOS_IMU3000_ConfigTypeDef * IMU3000_Config_Struct); -static bool PIOS_IMU3000_Read(uint8_t address, uint8_t * buffer, uint8_t len); -static bool PIOS_IMU3000_Write(uint8_t address, uint8_t buffer); - -/** - * @brief Initialize the IMU3000 3-axis gyro sensor. - * @return none - */ -void PIOS_IMU3000_Init(void) -{ - GPIO_InitTypeDef GPIO_InitStructure; - EXTI_InitTypeDef EXTI_InitStructure; - NVIC_InitTypeDef NVIC_InitStructure; - - /* Enable INT GPIO clock */ - RCC_APB2PeriphClockCmd(PIOS_IMU3000_INT_CLK | RCC_APB2Periph_AFIO, ENABLE); - - /* Configure IMU3000 interrupt pin as input floating */ - GPIO_InitStructure.GPIO_Pin = PIOS_IMU3000_INT_GPIO_PIN; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; - GPIO_Init(PIOS_IMU3000_INT_GPIO_PORT, &GPIO_InitStructure); - - /* Configure the End Of Conversion (EOC) interrupt */ - GPIO_EXTILineConfig(PIOS_IMU3000_INT_PORT_SOURCE, PIOS_IMU3000_INT_PIN_SOURCE); - EXTI_InitStructure.EXTI_Line = PIOS_IMU3000_INT_EXTI_LINE; - EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; - EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising; - EXTI_InitStructure.EXTI_LineCmd = ENABLE; - EXTI_Init(&EXTI_InitStructure); - - /* Enable and set EOC EXTI Interrupt to the lowest priority */ - NVIC_InitStructure.NVIC_IRQChannel = PIOS_IMU3000_INT_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IMU3000_INT_PRIO; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); - - /* Configure the IMU3000 Sensor */ - PIOS_IMU3000_ConfigTypeDef IMU3000_InitStructure; - IMU3000_InitStructure.Fifo_store = PIOS_IMU3000_FIFO_TEMP_OUT | PIOS_IMU3000_FIFO_GYRO_X_OUT | - PIOS_IMU3000_FIFO_GYRO_Y_OUT | PIOS_IMU3000_FIFO_GYRO_Z_OUT | PIOS_IMU3000_FIFO_FOOTER; - IMU3000_InitStructure.Smpl_rate_div = 8; - IMU3000_InitStructure.DigLPF_Scale = PIOS_IMU3000_LOWPASS_256_HZ | PIOS_IMU3000_SCALE_500_DEG; - IMU3000_InitStructure.Interrupt_cfg = PIOS_IMU3000_INT_CLR_ANYRD | PIOS_IMU3000_INT_DATA_RDY; - IMU3000_InitStructure.User_ctl = PIOS_IMU3000_USERCTL_FIFO_EN; - IMU3000_InitStructure.Pwr_mgmt_clk = PIOS_IMU3000_PWRMGMT_PLL_X_CLK; - PIOS_IMU3000_Config(&IMU3000_InitStructure); -} - -/** - * @brief Initialize the IMU3000 3-axis gyro sensor - * \return none - * \param[in] PIOS_IMU3000_ConfigTypeDef struct to be used to configure sensor. -* -*/ -static void PIOS_IMU3000_Config(PIOS_IMU3000_ConfigTypeDef * IMU3000_Config_Struct) -{ - // TODO: Add checks against current config so we only update what has changed - - // FIFO storage - while (!PIOS_IMU3000_Write(PIOS_IMU3000_FIFO_EN_REG, IMU3000_Config_Struct->Fifo_store)) ; - - // Sample rate divider - while (!PIOS_IMU3000_Write(PIOS_IMU3000_SMPLRT_DIV_REG, IMU3000_Config_Struct->Smpl_rate_div)) ; - - // Digital low-pass filter and scale - while (!PIOS_IMU3000_Write(PIOS_IMU3000_DLPF_CFG_REG, IMU3000_Config_Struct->DigLPF_Scale)) ; - - // Interrupt configuration - while (!PIOS_IMU3000_Write(PIOS_IMU3000_INT_CFG_REG, IMU3000_Config_Struct->Interrupt_cfg)) ; - - // Interrupt configuration - while (!PIOS_IMU3000_Write(PIOS_IMU3000_USER_CTRL_REG, IMU3000_Config_Struct->User_ctl)) ; - - // Interrupt configuration - while (!PIOS_IMU3000_Write(PIOS_IMU3000_PWR_MGMT_REG, IMU3000_Config_Struct->Pwr_mgmt_clk)) ; -} - -/** - * @brief Read current X, Z, Y values (in that order) - * \param[out] int16_t array of size 3 to store X, Z, and Y magnetometer readings - * \return none -*/ -void PIOS_IMU3000_ReadGyros(int16_t out[3]) -{ -} - - -/** - * @brief Read the identification bytes from the IMU3000 sensor - * \return ID read from IMU3000 -*/ -uint8_t PIOS_IMU3000_ReadID() -{ - uint8_t id; - while (!PIOS_IMU3000_Read(0x00, &id, 1)) ; - return id; -} - -/** -* @brief Reads one or more bytes from IMU3000 into a buffer -* \param[in] address IMU3000 register address (depends on size) -* \param[out] buffer destination buffer -* \param[in] len number of bytes which should be read -* \return 0 if operation was successful -* \return -1 if error during I2C transfer -* \return -4 if invalid length -*/ -static bool PIOS_IMU3000_Read(uint8_t address, uint8_t * buffer, uint8_t len) -{ - uint8_t addr_buffer[] = { - address, - }; - - const struct pios_i2c_txn txn_list[] = { - { - .info = __func__, - .addr = PIOS_IMU3000_I2C_ADDR, - .rw = PIOS_I2C_TXN_WRITE, - .len = sizeof(addr_buffer), - .buf = addr_buffer, - } - , - { - .info = __func__, - .addr = PIOS_IMU3000_I2C_ADDR, - .rw = PIOS_I2C_TXN_READ, - .len = len, - .buf = buffer, - } - }; - - return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); -} - -/** -* @brief Writes one or more bytes to the IMU3000 -* \param[in] address Register address -* \param[in] buffer source buffer -* \return 0 if operation was successful -* \return -1 if error during I2C transfer -*/ -static bool PIOS_IMU3000_Write(uint8_t address, uint8_t buffer) -{ - uint8_t data[] = { - address, - buffer, - }; - - const struct pios_i2c_txn txn_list[] = { - { - .info = __func__, - .addr = PIOS_IMU3000_I2C_ADDR, - .rw = PIOS_I2C_TXN_WRITE, - .len = sizeof(data), - .buf = data, - } - , - }; - - return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); -} - -/** - * @brief Run self-test operation. - * \return 0 if test failed - * \return non-zero value if test succeeded - */ -uint8_t PIOS_IMU3000_Test(void) -{ - /* Verify that ID matches (IMU3000 ID is 0x69) */ - return (0x69 ^ PIOS_IMU3000_ReadID() ); -} - -/** -* @brief IRQ Handler -*/ -void PIOS_IMU3000_IRQHandler(void) -{ -} - -#endif /* PIOS_INCLUDE_IMU3000 */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS/Common/pios_l3gd20.c b/flight/PiOS/Common/pios_l3gd20.c new file mode 100644 index 000000000..3151d26e2 --- /dev/null +++ b/flight/PiOS/Common/pios_l3gd20.c @@ -0,0 +1,386 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_L3GD20 L3GD20 Functions + * @brief Deals with the hardware interface to the 3-axis gyro + * @{ + * + * @file pios_l3gd20.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief L3GD20 3-axis gyro chip + * @see The GNU Public License (GPL) Version 3 + * + ****************************************************************************** + */ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_L3GD20) + +#include "fifo_buffer.h" + +/* Global Variables */ +enum pios_l3gd20_dev_magic { + PIOS_L3GD20_DEV_MAGIC = 0x9d39bced, +}; + +#define PIOS_L3GD20_MAX_DOWNSAMPLE 2 +struct l3gd20_dev { + uint32_t spi_id; + uint32_t slave_num; + xQueueHandle queue; + const struct pios_l3gd20_cfg * cfg; + enum pios_l3gd20_filter bandwidth; + enum pios_l3gd20_range range; + enum pios_l3gd20_dev_magic magic; +}; + +//! Global structure for this device device +static struct l3gd20_dev * dev; + +//! Private functions +static struct l3gd20_dev * PIOS_L3GD20_alloc(void); +static int32_t PIOS_L3GD20_Validate(struct l3gd20_dev * dev); +static void PIOS_L3GD20_Config(struct pios_l3gd20_cfg const * cfg); +static int32_t PIOS_L3GD20_SetReg(uint8_t address, uint8_t buffer); +static int32_t PIOS_L3GD20_GetReg(uint8_t address); +static int32_t PIOS_L3GD20_ClaimBus(); +static int32_t PIOS_L3GD20_ClaimBusIsr(); +static int32_t PIOS_L3GD20_ReleaseBus(); + +volatile bool l3gd20_configured = false; + +/* Local Variables */ +#define DEG_TO_RAD (M_PI / 180.0) + +/** + * @brief Allocate a new device + */ +static struct l3gd20_dev * PIOS_L3GD20_alloc(void) +{ + struct l3gd20_dev * l3gd20_dev; + + l3gd20_dev = (struct l3gd20_dev *)pvPortMalloc(sizeof(*l3gd20_dev)); + if (!l3gd20_dev) return (NULL); + + l3gd20_dev->magic = PIOS_L3GD20_DEV_MAGIC; + + l3gd20_dev->queue = xQueueCreate(PIOS_L3GD20_MAX_DOWNSAMPLE, sizeof(struct pios_l3gd20_data)); + if(l3gd20_dev->queue == NULL) { + vPortFree(l3gd20_dev); + return NULL; + } + + return(l3gd20_dev); +} + +/** + * @brief Validate the handle to the spi device + * @returns 0 for valid device or -1 otherwise + */ +static int32_t PIOS_L3GD20_Validate(struct l3gd20_dev * dev) +{ + if (dev == NULL) + return -1; + if (dev->magic != PIOS_L3GD20_DEV_MAGIC) + return -2; + if (dev->spi_id == 0) + return -3; + return 0; +} + +/** + * @brief Initialize the MPU6050 3-axis gyro sensor. + * @return none + */ +#include +int32_t PIOS_L3GD20_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_l3gd20_cfg * cfg) +{ + dev = PIOS_L3GD20_alloc(); + if(dev == NULL) + return -1; + + dev->spi_id = spi_id; + dev->slave_num = slave_num; + dev->cfg = cfg; + + /* Configure the MPU6050 Sensor */ + PIOS_L3GD20_Config(cfg); + + /* Set up EXTI */ + PIOS_EXTI_Init(cfg->exti_cfg); + + // An initial read is needed to get it running + struct pios_l3gd20_data data; + PIOS_L3GD20_ReadGyros(&data); + + return 0; +} + +/** + * @brief Initialize the L3GD20 3-axis gyro sensor + * \return none + * \param[in] PIOS_L3GD20_ConfigTypeDef struct to be used to configure sensor. +* +*/ +static void PIOS_L3GD20_Config(struct pios_l3gd20_cfg const * cfg) +{ + // This register enables the channels and sets the bandwidth + while(PIOS_L3GD20_SetReg(PIOS_L3GD20_CTRL_REG1, PIOS_L3GD20_CTRL1_FASTEST | + PIOS_L3GD20_CTRL1_PD | PIOS_L3GD20_CTRL1_ZEN | + PIOS_L3GD20_CTRL1_YEN | PIOS_L3GD20_CTRL1_XEN) != 0); + + // Disable the high pass filters + while(PIOS_L3GD20_SetReg(PIOS_L3GD20_CTRL_REG2, 0) != 0); + // Set int2 to go high on data ready + while(PIOS_L3GD20_SetReg(PIOS_L3GD20_CTRL_REG3, 0x08) != 0); + // Select SPI interface, 500 deg/s, endianness? + while(PIOS_L3GD20_SetRange(cfg->range) != 0); + // Enable FIFO, disable HPF + while(PIOS_L3GD20_SetReg(PIOS_L3GD20_CTRL_REG5, 0x40) != 0); + // Fifo stream mode + while(PIOS_L3GD20_SetReg(PIOS_L3GD20_FIFO_CTRL_REG, 0x40) != 0); +} + +/** + * @brief Sets the maximum range of the L3GD20 + * @returns 0 for success, -1 for invalid device, -2 if unable to set register + */ +int32_t PIOS_L3GD20_SetRange(enum pios_l3gd20_range range) +{ + if(PIOS_L3GD20_Validate(dev) != 0) + return -1; + + dev->range = range; + if(PIOS_L3GD20_SetReg(PIOS_L3GD20_CTRL_REG4, dev->range) != 0) + return -2; + + return 0; +} + +/** + * @brief Claim the SPI bus for the accel communications and select this chip + * @return 0 if successful, -1 for invalid device, -2 if unable to claim bus + */ +static int32_t PIOS_L3GD20_ClaimBus() +{ + if(PIOS_L3GD20_Validate(dev) != 0) + return -1; + + if(PIOS_SPI_ClaimBus(dev->spi_id) != 0) + return -2; + + PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + return 0; +} + +/** + * @brief Claim the SPI bus for the accel communications and select this chip + * @return 0 if successful, -1 for invalid device, -2 if unable to claim bus + */ +static int32_t PIOS_L3GD20_ClaimBusIsr() +{ + if(PIOS_L3GD20_Validate(dev) != 0) + return -1; + + if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) + return -2; + + PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + return 0; +} + +/** + * @brief Release the SPI bus for the accel communications and end the transaction + * @return 0 if successful, -1 for invalid device + */ +int32_t PIOS_L3GD20_ReleaseBus() +{ + if(PIOS_L3GD20_Validate(dev) != 0) + return -1; + + PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,1); + + return PIOS_SPI_ReleaseBus(dev->spi_id); +} + +/** + * @brief Read a register from L3GD20 + * @returns The register value or -1 if failure to get bus + * @param reg[in] Register address to be read + */ +static int32_t PIOS_L3GD20_GetReg(uint8_t reg) +{ + uint8_t data; + + if(PIOS_L3GD20_ClaimBus() != 0) + return -1; + + PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte + data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response + + PIOS_L3GD20_ReleaseBus(); + return data; +} + +/** + * @brief Writes one byte to the L3GD20 + * \param[in] reg Register address + * \param[in] data Byte to write + * \return 0 if operation was successful + * \return -1 if unable to claim SPI bus + * \return -2 if unable to claim i2c device + */ +static int32_t PIOS_L3GD20_SetReg(uint8_t reg, uint8_t data) +{ + if(PIOS_L3GD20_ClaimBus() != 0) + return -1; + + PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg); + PIOS_SPI_TransferByte(dev->spi_id, data); + + PIOS_L3GD20_ReleaseBus(); + + return 0; +} + +/** + * @brief Read current X, Z, Y values (in that order) + * \param[out] int16_t array of size 3 to store X, Z, and Y magnetometer readings + * \returns The number of samples remaining in the fifo + */ +uint32_t l3gd20_irq = 0; +int32_t PIOS_L3GD20_ReadGyros(struct pios_l3gd20_data * data) +{ + uint8_t buf[7] = {PIOS_L3GD20_GYRO_X_OUT_LSB | 0x80 | 0x40, 0, 0, 0, 0, 0, 0}; + uint8_t rec[7]; + + if(PIOS_L3GD20_ClaimBus() != 0) + return -1; + + if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) { + PIOS_L3GD20_ReleaseBus(); + data->gyro_x = 0; + data->gyro_y = 0; + data->gyro_z = 0; + data->temperature = 0; + return -2; + } + + PIOS_L3GD20_ReleaseBus(); + + memcpy((uint8_t *) &(data->gyro_x), &rec[1], 6); + data->temperature = PIOS_L3GD20_GetReg(PIOS_L3GD20_OUT_TEMP); + + return 0; +} + +/** + * @brief Read the identification bytes from the MPU6050 sensor + * \return ID read from MPU6050 or -1 if failure +*/ +int32_t PIOS_L3GD20_ReadID() +{ + int32_t l3gd20_id = PIOS_L3GD20_GetReg(PIOS_L3GD20_WHOAMI); + if(l3gd20_id < 0) + return -1; + return l3gd20_id; +} + +/** + * \brief Reads the queue handle + * \return Handle to the queue or null if invalid device + */ +xQueueHandle PIOS_L3GD20_GetQueue() +{ + if(PIOS_L3GD20_Validate(dev) != 0) + return (xQueueHandle) NULL; + + return dev->queue; +} + +float PIOS_L3GD20_GetScale() +{ + if(PIOS_L3GD20_Validate(dev) != 0) + return -1; + + switch (dev->range) { + case PIOS_L3GD20_SCALE_250_DEG: + return 0.00875f; + case PIOS_L3GD20_SCALE_500_DEG: + return 0.01750f; + case PIOS_L3GD20_SCALE_2000_DEG: + return 0.070f; + } + return 0; +} + +/** + * @brief Run self-test operation. + * \return 0 if test succeeded + * \return non-zero value if test succeeded + */ +uint8_t PIOS_L3GD20_Test(void) +{ + int32_t l3gd20_id = PIOS_L3GD20_ReadID(); + if(l3gd20_id < 0) + return -1; + + uint8_t id = l3gd20_id; + if(id == 0xD4) + return 0; + + return -2; +} + +/** +* @brief IRQ Handler. Read all the data from onboard buffer +*/ +void PIOS_L3GD20_IRQHandler(void) +{ + l3gd20_irq++; + + struct pios_l3gd20_data data; + uint8_t buf[7] = {PIOS_L3GD20_GYRO_X_OUT_LSB | 0x80 | 0x40, 0, 0, 0, 0, 0, 0}; + uint8_t rec[7]; + + /* This code duplicates ReadGyros above but uses ClaimBusIsr */ + if(PIOS_L3GD20_ClaimBusIsr() != 0) + return; + + if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) { + PIOS_L3GD20_ReleaseBus(); + return; + } + + PIOS_L3GD20_ReleaseBus(); + + memcpy((uint8_t *) &(data.gyro_x), &rec[1], 6); + data.temperature = PIOS_L3GD20_GetReg(PIOS_L3GD20_OUT_TEMP); + + xQueueSend(dev->queue, (void *) &data, 0); +} + +#endif /* L3GD20 */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/Common/pios_mpu6000.c b/flight/PiOS/Common/pios_mpu6000.c new file mode 100644 index 000000000..56e8cccbd --- /dev/null +++ b/flight/PiOS/Common/pios_mpu6000.c @@ -0,0 +1,477 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_MPU6000 MPU6000 Functions + * @brief Deals with the hardware interface to the 3-axis gyro + * @{ + * + * @file pios_mpu000.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief MPU6000 6-axis gyro and accel chip + * @see The GNU Public License (GPL) Version 3 + * + ****************************************************************************** + */ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_MPU6000) + +#include "fifo_buffer.h" + +/* Global Variables */ + +enum pios_mpu6000_dev_magic { + PIOS_MPU6000_DEV_MAGIC = 0x9da9b3ed, +}; + +#define PIOS_MPU6000_MAX_DOWNSAMPLE 2 +struct mpu6000_dev { + uint32_t spi_id; + uint32_t slave_num; + xQueueHandle queue; + const struct pios_mpu6000_cfg * cfg; + enum pios_mpu6000_dev_magic magic; +}; + +//! Global structure for this device device +static struct mpu6000_dev * dev; +volatile bool mpu6000_configured = false; + +//! Private functions +static struct mpu6000_dev * PIOS_MPU6000_alloc(void); +static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev * dev); +static void PIOS_MPU6000_Config(struct pios_mpu6000_cfg const * cfg); +static int32_t PIOS_MPU6000_SetReg(uint8_t address, uint8_t buffer); +static int32_t PIOS_MPU6000_GetReg(uint8_t address); + +#define DEG_TO_RAD (M_PI / 180.0) + +#define GRAV 9.81f + +/** + * @brief Allocate a new device + */ +static struct mpu6000_dev * PIOS_MPU6000_alloc(void) +{ + struct mpu6000_dev * mpu6000_dev; + + mpu6000_dev = (struct mpu6000_dev *)pvPortMalloc(sizeof(*mpu6000_dev)); + if (!mpu6000_dev) return (NULL); + + mpu6000_dev->magic = PIOS_MPU6000_DEV_MAGIC; + + mpu6000_dev->queue = xQueueCreate(PIOS_MPU6000_MAX_DOWNSAMPLE, sizeof(struct pios_mpu6000_data)); + if(mpu6000_dev->queue == NULL) { + vPortFree(mpu6000_dev); + return NULL; + } + + return(mpu6000_dev); +} + +/** + * @brief Validate the handle to the spi device + * @returns 0 for valid device or -1 otherwise + */ +static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev * dev) +{ + if (dev == NULL) + return -1; + if (dev->magic != PIOS_MPU6000_DEV_MAGIC) + return -2; + if (dev->spi_id == 0) + return -3; + return 0; +} + +/** + * @brief Initialize the MPU6000 3-axis gyro sensor. + * @return 0 for success, -1 for failure + */ +int32_t PIOS_MPU6000_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_mpu6000_cfg * cfg) +{ + dev = PIOS_MPU6000_alloc(); + if(dev == NULL) + return -1; + + dev->spi_id = spi_id; + dev->slave_num = slave_num; + dev->cfg = cfg; + + /* Configure the MPU6000 Sensor */ + PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_256); + PIOS_MPU6000_Config(cfg); + PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_16); + + /* Set up EXTI line */ + PIOS_EXTI_Init(cfg->exti_cfg); + return 0; +} + +/** + * @brief Initialize the MPU6000 3-axis gyro sensor + * \return none + * \param[in] PIOS_MPU6000_ConfigTypeDef struct to be used to configure sensor. +* +*/ +static void PIOS_MPU6000_Config(struct pios_mpu6000_cfg const * cfg) +{ + // Reset chip + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_PWR_MGMT_REG, 0x80) != 0); + PIOS_DELAY_WaitmS(100); + + // Reset chip and fifo + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_USER_CTRL_REG, 0x01 | 0x02 | 0x04) != 0); + // Wait for reset to finish + while (PIOS_MPU6000_GetReg(PIOS_MPU6000_USER_CTRL_REG) & 0x07); + + //Power management configuration + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_PWR_MGMT_REG, cfg->Pwr_mgmt_clk) != 0) ; + + // Interrupt configuration + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_INT_CFG_REG, cfg->interrupt_cfg) != 0) ; + + // Interrupt configuration + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_INT_EN_REG, cfg->interrupt_en) != 0) ; + + // FIFO storage +#if defined(PIOS_MPU6000_ACCEL) + // Set the accel scale + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_ACCEL_CFG_REG, cfg->accel_range) != 0); + + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_FIFO_EN_REG, cfg->Fifo_store | PIOS_MPU6000_ACCEL_OUT) != 0); +#else + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_FIFO_EN_REG, cfg->Fifo_store) != 0); +#endif + + // Sample rate divider + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_SMPLRT_DIV_REG, cfg->Smpl_rate_div) != 0) ; + + // Digital low-pass filter and scale + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_DLPF_CFG_REG, cfg->filter) != 0) ; + + // Digital low-pass filter and scale + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_GYRO_CFG_REG, cfg->gyro_range) != 0) ; + + // Interrupt configuration + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_USER_CTRL_REG, cfg->User_ctl) != 0) ; + + // Interrupt configuration + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_PWR_MGMT_REG, cfg->Pwr_mgmt_clk) != 0) ; + + // Interrupt configuration + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_INT_CFG_REG, cfg->interrupt_cfg) != 0) ; + + // Interrupt configuration + while (PIOS_MPU6000_SetReg(PIOS_MPU6000_INT_EN_REG, cfg->interrupt_en) != 0) ; + if((PIOS_MPU6000_GetReg(PIOS_MPU6000_INT_EN_REG)) != cfg->interrupt_en) + return; + + mpu6000_configured = true; +} + +/** + * @brief Claim the SPI bus for the accel communications and select this chip + * @return 0 if successful, -1 for invalid device, -2 if unable to claim bus + */ +int32_t PIOS_MPU6000_ClaimBus() +{ + if(PIOS_MPU6000_Validate(dev) != 0) + return -1; + + if(PIOS_SPI_ClaimBus(dev->spi_id) != 0) + return -2; + + PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + return 0; +} + +/** + * @brief Release the SPI bus for the accel communications and end the transaction + * @return 0 if successful + */ +int32_t PIOS_MPU6000_ReleaseBus() +{ + if(PIOS_MPU6000_Validate(dev) != 0) + return -1; + + PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,1); + + return PIOS_SPI_ReleaseBus(dev->spi_id); +} + +/** + * @brief Read a register from MPU6000 + * @returns The register value or -1 if failure to get bus + * @param reg[in] Register address to be read + */ +static int32_t PIOS_MPU6000_GetReg(uint8_t reg) +{ + uint8_t data; + + if(PIOS_MPU6000_ClaimBus() != 0) + return -1; + + PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte + data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response + + PIOS_MPU6000_ReleaseBus(); + return data; +} + +/** + * @brief Writes one byte to the MPU6000 + * \param[in] reg Register address + * \param[in] data Byte to write + * \return 0 if operation was successful + * \return -1 if unable to claim SPI bus + * \return -2 if unable to claim i2c device + */ +static int32_t PIOS_MPU6000_SetReg(uint8_t reg, uint8_t data) +{ + if(PIOS_MPU6000_ClaimBus() != 0) + return -1; + + if(PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg) != 0) { + PIOS_MPU6000_ReleaseBus(); + return -2; + } + + if(PIOS_SPI_TransferByte(dev->spi_id, data) != 0) { + PIOS_MPU6000_ReleaseBus(); + return -3; + } + + PIOS_MPU6000_ReleaseBus(); + + return 0; +} + +/** + * @brief Read current X, Z, Y values (in that order) + * \param[out] int16_t array of size 3 to store X, Z, and Y magnetometer readings + * \returns The number of samples remaining in the fifo + */ +int32_t PIOS_MPU6000_ReadGyros(struct pios_mpu6000_data * data) +{ + uint8_t buf[7] = {PIOS_MPU6000_GYRO_X_OUT_MSB | 0x80, 0, 0, 0, 0, 0, 0}; + uint8_t rec[7]; + + if(PIOS_MPU6000_ClaimBus() != 0) + return -1; + + if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) + return -2; + + PIOS_MPU6000_ReleaseBus(); + + data->gyro_x = rec[1] << 8 | rec[2]; + data->gyro_y = rec[3] << 8 | rec[4]; + data->gyro_z = rec[5] << 8 | rec[6]; + + return 0; +} + +/* + * @brief Read the identification bytes from the MPU6000 sensor + * \return ID read from MPU6000 or -1 if failure +*/ +int32_t PIOS_MPU6000_ReadID() +{ + int32_t mpu6000_id = PIOS_MPU6000_GetReg(PIOS_MPU6000_WHOAMI); + if(mpu6000_id < 0) + return -1; + return mpu6000_id; +} + +/** + * \brief Reads the queue handle + * \return Handle to the queue or null if invalid device + */ +xQueueHandle PIOS_MPU6000_GetQueue() +{ + if(PIOS_MPU6000_Validate(dev) != 0) + return (xQueueHandle) NULL; + + return dev->queue; +} + + +float PIOS_MPU6000_GetScale() +{ + switch (dev->cfg->gyro_range) { + case PIOS_MPU6000_SCALE_250_DEG: + return 1.0f / 131.0f; + case PIOS_MPU6000_SCALE_500_DEG: + return 1.0f / 65.5f; + case PIOS_MPU6000_SCALE_1000_DEG: + return 1.0f / 32.8f; + case PIOS_MPU6000_SCALE_2000_DEG: + return 1.0f / 16.4f; + } + return 0; +} + +float PIOS_MPU6000_GetAccelScale() +{ + switch (dev->cfg->accel_range) { + case PIOS_MPU6000_ACCEL_2G: + return GRAV / 16384.0f; + case PIOS_MPU6000_ACCEL_4G: + return GRAV / 8192.0f; + case PIOS_MPU6000_ACCEL_8G: + return GRAV / 4096.0f; + case PIOS_MPU6000_ACCEL_16G: + return GRAV / 2048.0f; + } + return 0; +} + +/** + * @brief Run self-test operation. + * \return 0 if test succeeded + * \return non-zero value if test succeeded + */ +uint8_t PIOS_MPU6000_Test(void) +{ + /* Verify that ID matches (MPU6000 ID is 0x69) */ + int32_t mpu6000_id = PIOS_MPU6000_ReadID(); + if(mpu6000_id < 0) + return -1; + + if(mpu6000_id != 0x68); + return -2; + + return 0; +} + +/** + * @brief Run self-test operation. + * \return 0 if test succeeded + * \return non-zero value if test succeeded + */ +static int32_t PIOS_MPU6000_FifoDepth(void) +{ + uint8_t mpu6000_send_buf[3] = {PIOS_MPU6000_FIFO_CNT_MSB | 0x80, 0, 0}; + uint8_t mpu6000_rec_buf[3]; + + if(PIOS_MPU6000_ClaimBus() != 0) + return -1; + + if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { + PIOS_MPU6000_ReleaseBus(); + return -1; + } + + PIOS_MPU6000_ReleaseBus(); + + return (mpu6000_rec_buf[1] << 8) | mpu6000_rec_buf[2]; +} + +/** +* @brief IRQ Handler. Read all the data from onboard buffer +*/ +uint32_t mpu6000_irq = 0; +int32_t mpu6000_count; +uint32_t mpu6000_fifo_backup = 0; + +uint8_t mpu6000_last_read_count = 0; +uint32_t mpu6000_fails = 0; + +uint32_t mpu6000_interval_us; +uint32_t mpu6000_time_us; +uint32_t mpu6000_transfer_size; + +void PIOS_MPU6000_IRQHandler(void) +{ + static uint32_t timeval; + mpu6000_interval_us = PIOS_DELAY_DiffuS(timeval); + timeval = PIOS_DELAY_GetRaw(); + + if(!mpu6000_configured) + return; + + mpu6000_count = PIOS_MPU6000_FifoDepth(); + if(mpu6000_count < sizeof(struct pios_mpu6000_data)) + return; + + if(PIOS_MPU6000_ClaimBus() != 0) + return; + + uint8_t mpu6000_send_buf[1+sizeof(struct pios_mpu6000_data)] = {PIOS_MPU6000_FIFO_REG | 0x80, 0, 0, 0, 0, 0, 0, 0, 0}; + uint8_t mpu6000_rec_buf[1+sizeof(struct pios_mpu6000_data)]; + + if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { + PIOS_MPU6000_ReleaseBus(); + mpu6000_fails++; + return; + } + + PIOS_MPU6000_ReleaseBus(); + + struct pios_mpu6000_data data; + + // In the case where extras samples backed up grabbed an extra + if (mpu6000_count >= (sizeof(data) * 2)) { + mpu6000_fifo_backup++; + if(PIOS_MPU6000_ClaimBus() != 0) + return; + + uint8_t mpu6000_send_buf[1+sizeof(struct pios_mpu6000_data)] = {PIOS_MPU6000_FIFO_REG | 0x80, 0, 0, 0, 0, 0, 0, 0, 0}; + uint8_t mpu6000_rec_buf[1+sizeof(struct pios_mpu6000_data)]; + + if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { + PIOS_MPU6000_ReleaseBus(); + mpu6000_fails++; + return; + } + + PIOS_MPU6000_ReleaseBus(); + } + +#if defined(PIOS_MPU6000_ACCEL) + data.accel_x = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; + data.accel_y = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; + data.accel_z = mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]; + data.temperature = mpu6000_rec_buf[7] << 8 | mpu6000_rec_buf[8]; + data.gyro_x = mpu6000_rec_buf[9] << 8 | mpu6000_rec_buf[10]; + data.gyro_y = mpu6000_rec_buf[11] << 8 | mpu6000_rec_buf[12]; + data.gyro_z = mpu6000_rec_buf[13] << 8 | mpu6000_rec_buf[14]; +#else + data.temperature = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; + data.gyro_x = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; + data.gyro_y = mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]; + data.gyro_z = mpu6000_rec_buf[7] << 8 | mpu6000_rec_buf[8]; +#endif + + xQueueSend(dev->queue, (void *) &data, 0); + + mpu6000_irq++; + + mpu6000_time_us = PIOS_DELAY_DiffuS(timeval); +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/Common/pios_ms5611.c b/flight/PiOS/Common/pios_ms5611.c new file mode 100644 index 000000000..61b621352 --- /dev/null +++ b/flight/PiOS/Common/pios_ms5611.c @@ -0,0 +1,270 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_MS5611 MS5611 Functions + * @brief Hardware functions to deal with the altitude pressure sensor + * @{ + * + * @file pios_ms5611.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief MS5611 Pressure Sensor Routines + * @see The GNU Public License (GPL) Version 3 + * + ******************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +// TODO: Clean this up. Getting around old constant. +#define PIOS_MS5611_OVERSAMPLING oversampling + +#include "pios.h" + +#if defined(PIOS_INCLUDE_MS5611) + +/* Glocal Variables */ +ConversionTypeTypeDef CurrentRead; + +/* Local Variables */ +MS5611CalibDataTypeDef CalibData; + +/* Straight from the datasheet */ +static uint32_t RawTemperature; +static uint32_t RawPressure; +static int64_t Pressure; +static int64_t Temperature; + +static int32_t PIOS_MS5611_Read(uint8_t address, uint8_t * buffer, uint8_t len); +static int32_t PIOS_MS5611_WriteCommand(uint8_t command); + +// Move into proper driver structure with cfg stored +static uint32_t oversampling; +static const struct pios_ms5611_cfg * dev_cfg; +static int32_t i2c_id; + +static enum pios_ms5611_osr osr = MS5611_OSR_256; + +/** + * Initialise the MS5611 sensor + */ +int32_t ms5611_read_flag; +void PIOS_MS5611_Init(const struct pios_ms5611_cfg * cfg, int32_t i2c_device) +{ + i2c_id = i2c_device; + + oversampling = cfg->oversampling; + dev_cfg = cfg; // Store cfg before enabling interrupt + + PIOS_MS5611_WriteCommand(MS5611_RESET); + PIOS_DELAY_WaitmS(20); + + uint8_t data[2]; + + /* Calibration parameters */ + for (int i = 0; i < 6; i++) { + PIOS_MS5611_Read(MS5611_CALIB_ADDR + i * 2, data, 2); + CalibData.C[i] = (data[0] << 8) | data[1]; + } +} + +/** +* Start the ADC conversion +* \param[in] PresOrTemp BMP085_PRES_ADDR or BMP085_TEMP_ADDR +* \return 0 for success, -1 for failure (conversion completed and not read) +*/ +int32_t PIOS_MS5611_StartADC(ConversionTypeTypeDef Type) +{ + /* Start the conversion */ + if (Type == TemperatureConv) { + while (PIOS_MS5611_WriteCommand(MS5611_TEMP_ADDR + osr) != 0) + continue; + } else if (Type == PressureConv) { + while (PIOS_MS5611_WriteCommand(MS5611_PRES_ADDR + osr) != 0) + continue; + } + + CurrentRead = Type; + + return 0; +} + +/** + * @brief Return the delay for the current osr + */ +int32_t PIOS_MS5611_GetDelay() { + switch(osr) { + case MS5611_OSR_256: + return 2; + case MS5611_OSR_512: + return 2; + case MS5611_OSR_1024: + return 3; + case MS5611_OSR_2048: + return 5; + case MS5611_OSR_4096: + return 10; + default: + break; + } + return 10; +} +/** +* Read the ADC conversion value (once ADC conversion has completed) +* \param[in] PresOrTemp BMP085_PRES_ADDR or BMP085_TEMP_ADDR +* \return 0 if successfully read the ADC, -1 if failed +*/ +int32_t PIOS_MS5611_ReadADC(void) +{ + uint8_t Data[3]; + Data[0] = 0; + Data[1] = 0; + Data[2] = 0; + + static int64_t deltaTemp; + + /* Read and store the 16bit result */ + if (CurrentRead == TemperatureConv) { + /* Read the temperature conversion */ + if (PIOS_MS5611_Read(MS5611_ADC_READ, Data, 3) != 0) + return -1; + + RawTemperature = (Data[0] << 16) | (Data[1] << 8) | Data[2]; + + deltaTemp = RawTemperature - (CalibData.C[4] << 8); + Temperature = 2000l + ((deltaTemp * CalibData.C[5]) >> 23); + + } else { + int64_t Offset; + int64_t Sens; + + /* Read the pressure conversion */ + if (PIOS_MS5611_Read(MS5611_ADC_READ, Data, 3) != 0) + return -1; + RawPressure = ((Data[0] << 16) | (Data[1] << 8) | Data[2]); + + Offset = (((int64_t) CalibData.C[1]) << 16) + ((((int64_t) CalibData.C[3]) * deltaTemp) >> 7); + Sens = ((int64_t) CalibData.C[0]) << 15; + Sens = Sens + ((((int64_t) CalibData.C[2]) * deltaTemp) >> 8); + + Pressure = (((((int64_t) RawPressure) * Sens) >> 21) - Offset) >> 15; + } + return 0; +} + +/** + * Return the most recently computed temperature in kPa + */ +float PIOS_MS5611_GetTemperature(void) +{ + return ((float) Temperature) / 100.0f; +} + +/** + * Return the most recently computed pressure in kPa + */ +float PIOS_MS5611_GetPressure(void) +{ + return ((float) Pressure) / 1000.0f; +} + +/** +* Reads one or more bytes into a buffer +* \param[in] the command indicating the address to read +* \param[out] buffer destination buffer +* \param[in] len number of bytes which should be read +* \return 0 if operation was successful +* \return -1 if error during I2C transfer +*/ +int32_t PIOS_MS5611_Read(uint8_t address, uint8_t * buffer, uint8_t len) +{ + + const struct pios_i2c_txn txn_list[] = { + { + .info = __func__, + .addr = MS5611_I2C_ADDR, + .rw = PIOS_I2C_TXN_WRITE, + .len = 1, + .buf = &address, + } + , + { + .info = __func__, + .addr = MS5611_I2C_ADDR, + .rw = PIOS_I2C_TXN_READ, + .len = len, + .buf = buffer, + } + }; + + return PIOS_I2C_Transfer(i2c_id, txn_list, NELEMENTS(txn_list)); +} + +/** +* Writes one or more bytes to the MS5611 +* \param[in] address Register address +* \param[in] buffer source buffer +* \return 0 if operation was successful +* \return -1 if error during I2C transfer +*/ +int32_t PIOS_MS5611_WriteCommand(uint8_t command) +{ + const struct pios_i2c_txn txn_list[] = { + { + .info = __func__, + .addr = MS5611_I2C_ADDR, + .rw = PIOS_I2C_TXN_WRITE, + .len = 1, + .buf = &command, + } + , + }; + + return PIOS_I2C_Transfer(i2c_id, txn_list, NELEMENTS(txn_list)); +} + +/** +* @brief Run self-test operation. +* \return 0 if self-test succeed, -1 if failed +*/ +int32_t PIOS_MS5611_Test() +{ + // TODO: Is there a better way to test this than just checking that pressure/temperature has changed? + int32_t cur_value = 0; + + cur_value = Temperature; + PIOS_MS5611_StartADC(TemperatureConv); + PIOS_DELAY_WaitmS(5); + PIOS_MS5611_ReadADC(); + if (cur_value == Temperature) + return -1; + + cur_value=Pressure; + PIOS_MS5611_StartADC(PressureConv); + PIOS_DELAY_WaitmS(26); + PIOS_MS5611_ReadADC(); + if (cur_value == Pressure) + return -1; + + return 0; +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c new file mode 100644 index 000000000..1f65748ee --- /dev/null +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -0,0 +1,2342 @@ +/** +****************************************************************************** +* @addtogroup PIOS PIOS Core hardware abstraction layer +* @{ +* @addtogroup PIOS_RFM22B Radio Functions +* @brief PIOS interface for for the RFM22B radio +* @{ +* +* @file pios_rfm22b.c +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief Implements a driver the the RFM22B driver +* @see The GNU Public License (GPL) Version 3 +* +*****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +// ***************************************************************** +// RFM22B hardware layer +// +// This module uses the RFM22B's internal packet handling hardware to +// encapsulate our own packet data. +// +// The RFM22B internal hardware packet handler configuration is as follows .. +// +// 4-byte (32-bit) preamble .. alternating 0's & 1's +// 4-byte (32-bit) sync +// 1-byte packet length (number of data bytes to follow) +// 0 to 255 user data bytes +// +// Our own packet data will also contain it's own header and 32-bit CRC +// as a single 16-bit CRC is not sufficient for wireless comms. +// +// ***************************************************************** + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_RFM22B) + +#include // memmove + +#include +#include + +#include + +#include + +/* Local Defines */ +#define STACK_SIZE_BYTES 200 + +// RTC timer is running at 625Hz (1.6ms or 5 ticks == 8ms). +// A 256 byte message at 56kbps should take less than 40ms +// Note: This timeout should be rate dependent. +#define PIOS_RFM22B_SUPERVISOR_TIMEOUT 65 // ~100ms + +// this is too adjust the RF module so that it is on frequency +#define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default +#define OSC_LOAD_CAP_1 0x7D // board 1 +#define OSC_LOAD_CAP_2 0x7B // board 2 +#define OSC_LOAD_CAP_3 0x7E // board 3 +#define OSC_LOAD_CAP_4 0x7F // board 4 + +// ************************************ + +#define TX_TEST_MODE_TIMELIMIT_MS 30000 // TX test modes time limit (in ms) + +//#define TX_PREAMBLE_NIBBLES 8 // 7 to 511 (number of nibbles) +//#define RX_PREAMBLE_NIBBLES 5 // 5 to 31 (number of nibbles) +#define TX_PREAMBLE_NIBBLES 12 // 7 to 511 (number of nibbles) +#define RX_PREAMBLE_NIBBLES 6 // 5 to 31 (number of nibbles) + +// the size of the rf modules internal transmit buffers. +#define TX_BUFFER_SIZE 256 +// the size of the rf modules internal FIFO buffers +#define FIFO_SIZE 64 + +#define TX_FIFO_HI_WATERMARK 62 // 0-63 +#define TX_FIFO_LO_WATERMARK 32 // 0-63 + +#define RX_FIFO_HI_WATERMARK 32 // 0-63 + +#define PREAMBLE_BYTE 0x55 // preamble byte (preceeds SYNC_BYTE's) + +#define SYNC_BYTE_1 0x2D // RF sync bytes (32-bit in all) +#define SYNC_BYTE_2 0xD4 // +#define SYNC_BYTE_3 0x4B // +#define SYNC_BYTE_4 0x59 // + +// ************************************ +// the default TX power level + +#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_0 // +1dBm ... 1.25mW +//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_1 // +2dBm ... 1.6mW +//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_2 // +5dBm ... 3.16mW +//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_3 // +8dBm ... 6.3mW +//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_4 // +11dBm .. 12.6mW +//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_5 // +14dBm .. 25mW +//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_6 // +17dBm .. 50mW +//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_7 // +20dBm .. 100mW + +// ************************************ +// the default RF datarate + +//#define RFM22_DEFAULT_RF_DATARATE 500 // 500 bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 1000 // 1k bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 2000 // 2k bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 4000 // 4k bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 8000 // 8k bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 9600 // 9.6k bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 16000 // 16k bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 19200 // 19k2 bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 24000 // 24k bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 32000 // 32k bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 64000 // 64k bits per sec +#define RFM22_DEFAULT_RF_DATARATE 128000 // 128k bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 192000 // 192k bits per sec +//#define RFM22_DEFAULT_RF_DATARATE 256000 // 256k bits per sec .. NOT YET WORKING + +// ************************************ + +#define RFM22_DEFAULT_SS_RF_DATARATE 125 // 128bps + +// ************************************ +// Normal data streaming +// GFSK modulation +// no manchester encoding +// data whitening +// FIFO mode +// 5-nibble rx preamble length detection +// 10-nibble tx preamble length +// AFC enabled + +/* Local type definitions */ +enum pios_rfm22b_dev_magic { + PIOS_RFM22B_DEV_MAGIC = 0x68e971b6, +}; + +struct pios_rfm22b_dev { + enum pios_rfm22b_dev_magic magic; + struct pios_rfm22b_cfg cfg; + + uint32_t deviceID; + + // The COM callback functions. + pios_com_callback rx_in_cb; + uint32_t rx_in_context; + pios_com_callback tx_out_cb; + uint32_t tx_out_context; + + // The supervisor countdown timer. + uint16_t supv_timer; + uint16_t resets; +}; + +uint32_t random32 = 0x459ab8d8; + +/* Local function forwared declarations */ +static void PIOS_RFM22B_Supervisor(uint32_t ppm_id); +static void rfm22_processInt(void); +static void PIOS_RFM22_EXT_Int(void); +static void rfm22_setTxMode(uint8_t mode); + +// SPI read/write functions +void rfm22_startBurstWrite(uint8_t addr); +inline void rfm22_burstWrite(uint8_t data) +{ + PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data); +} +void rfm22_endBurstWrite(void); +void rfm22_write(uint8_t addr, uint8_t data); +void rfm22_startBurstRead(uint8_t addr); +inline uint8_t rfm22_burstRead(void) +{ + return PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff); +} +void rfm22_endBurstRead(void); +uint8_t rfm22_read(uint8_t addr); +uint8_t rfm22_txStart(); + +/* Provide a COM driver */ +static void PIOS_RFM22B_ChangeBaud(uint32_t rfm22b_id, uint32_t baud); +static void PIOS_RFM22B_RegisterRxCallback(uint32_t rfm22b_id, pios_com_callback rx_in_cb, uint32_t context); +static void PIOS_RFM22B_RegisterTxCallback(uint32_t rfm22b_id, pios_com_callback tx_out_cb, uint32_t context); +static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail); +static void PIOS_RFM22B_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail); + +/* Local variables */ +const struct pios_com_driver pios_rfm22b_com_driver = { + .set_baud = PIOS_RFM22B_ChangeBaud, + .tx_start = PIOS_RFM22B_TxStart, + .rx_start = PIOS_RFM22B_RxStart, + .bind_tx_cb = PIOS_RFM22B_RegisterTxCallback, + .bind_rx_cb = PIOS_RFM22B_RegisterRxCallback, +}; + +// External interrupt configuration +static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { + .vector = PIOS_RFM22_EXT_Int, + .line = PIOS_RFM22_EXTI_LINE, + .pin = { + .gpio = PIOS_RFM22_EXTI_GPIO_PORT, + .init = { + .GPIO_Pin = PIOS_RFM22_EXTI_GPIO_PIN, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = PIOS_RFM22_EXTI_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_RFM22_EXTI_PRIO, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = PIOS_RFM22_EXTI_LINE, + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Falling, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +// xtal 10 ppm, 434MHz +#define LOOKUP_SIZE 14 +const uint32_t data_rate[] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 64000, 128000, 192000, 256000}; +const uint8_t modulation_index[] = { 16, 8, 4, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}; +const uint32_t freq_deviation[] = { 4000, 4000, 4000, 4000, 4000, 4800, 8000, 9600, 12000, 16000, 32000, 64000, 96000, 128000}; +const uint32_t rx_bandwidth[] = { 17500, 17500, 17500, 17500, 17500, 19400, 32200, 38600, 51200, 64100, 137900, 269300, 420200, 518800}; +const int8_t est_rx_sens_dBm[] = { -118, -118, -117, -116, -115, -115, -112, -112, -110, -109, -106, -103, -101, -100}; // estimated receiver sensitivity for BER = 1E-3 + +const uint8_t reg_1C[] = { 0x37, 0x37, 0x37, 0x37, 0x3A, 0x3B, 0x26, 0x28, 0x2E, 0x16, 0x07, 0x83, 0x8A, 0x8C}; // rfm22_if_filter_bandwidth + +const uint8_t reg_1D[] = { 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44}; // rfm22_afc_loop_gearshift_override +const uint8_t reg_1E[] = { 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x02}; // rfm22_afc_timing_control + +const uint8_t reg_1F[] = { 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03}; // rfm22_clk_recovery_gearshift_override +const uint8_t reg_20[] = { 0xE8, 0xF4, 0xFA, 0x70, 0x3F, 0x34, 0x3F, 0x34, 0x2A, 0x3F, 0x3F, 0x5E, 0x3F, 0x2F}; // rfm22_clk_recovery_oversampling_ratio +const uint8_t reg_21[] = { 0x60, 0x20, 0x00, 0x01, 0x02, 0x02, 0x02, 0x02, 0x03, 0x02, 0x02, 0x01, 0x02, 0x02}; // rfm22_clk_recovery_offset2 +const uint8_t reg_22[] = { 0x20, 0x41, 0x83, 0x06, 0x0C, 0x75, 0x0C, 0x75, 0x12, 0x0C, 0x0C, 0x5D, 0x0C, 0xBB}; // rfm22_clk_recovery_offset1 +const uint8_t reg_23[] = { 0xC5, 0x89, 0x12, 0x25, 0x4A, 0x25, 0x4A, 0x25, 0x6F, 0x4A, 0x4A, 0x86, 0x4A, 0x0D}; // rfm22_clk_recovery_offset0 +const uint8_t reg_24[] = { 0x00, 0x00, 0x00, 0x02, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x05, 0x07, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 +const uint8_t reg_25[] = { 0x0A, 0x23, 0x85, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x74, 0xFF, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 + +const uint8_t reg_2A[] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 0x17, 0x31, 0x50, 0x50, 0x50}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz + +const uint8_t reg_6E[] = { 0x04, 0x08, 0x10, 0x20, 0x41, 0x4E, 0x83, 0x9D, 0xC4, 0x08, 0x10, 0x20, 0x31, 0x41}; // rfm22_tx_data_rate1 +const uint8_t reg_6F[] = { 0x19, 0x31, 0x62, 0xC5, 0x89, 0xA5, 0x12, 0x49, 0x9C, 0x31, 0x62, 0xC5, 0x27, 0x89}; // rfm22_tx_data_rate0 + +const uint8_t reg_70[] = { 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x0D, 0x0D, 0x0D, 0x0D, 0x0D}; // rfm22_modulation_mode_control1 +const uint8_t reg_71[] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23}; // rfm22_modulation_mode_control2 + +const uint8_t reg_72[] = { 0x06, 0x06, 0x06, 0x06, 0x06, 0x08, 0x0D, 0x0F, 0x13, 0x1A, 0x33, 0x66, 0x9A, 0xCD}; // rfm22_frequency_deviation + +// ************************************ +// Scan Spectrum settings +// GFSK modulation +// no manchester encoding +// data whitening +// FIFO mode +// 5-nibble rx preamble length detection +// 10-nibble tx preamble length +#define SS_LOOKUP_SIZE 2 + +// xtal 1 ppm, 434MHz +const uint32_t ss_rx_bandwidth[] = { 2600, 10600}; + +const uint8_t ss_reg_1C[] = { 0x51, 0x32}; // rfm22_if_filter_bandwidth +const uint8_t ss_reg_1D[] = { 0x00, 0x00}; // rfm22_afc_loop_gearshift_override + +const uint8_t ss_reg_20[] = { 0xE8, 0x38}; // rfm22_clk_recovery_oversampling_ratio +const uint8_t ss_reg_21[] = { 0x60, 0x02}; // rfm22_clk_recovery_offset2 +const uint8_t ss_reg_22[] = { 0x20, 0x4D}; // rfm22_clk_recovery_offset1 +const uint8_t ss_reg_23[] = { 0xC5, 0xD3}; // rfm22_clk_recovery_offset0 +const uint8_t ss_reg_24[] = { 0x00, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 +const uint8_t ss_reg_25[] = { 0x0F, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 + +const uint8_t ss_reg_2A[] = { 0xFF, 0xFF}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz + +const uint8_t ss_reg_70[] = { 0x24, 0x2D}; // rfm22_modulation_mode_control1 +const uint8_t ss_reg_71[] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2 + +// ************************************ + +volatile bool initialized = false; + +#if defined(RFM22_EXT_INT_USE) +volatile bool exec_using_spi; // set this if you want to access the SPI bus outside of the interrupt +#endif + +uint8_t device_type; // the RF chips device ID number +uint8_t device_version; // the RF chips revision number + +volatile uint8_t rf_mode; // holds our current RF mode + +uint32_t lower_carrier_frequency_limit_Hz; // the minimum RF frequency we can use +uint32_t upper_carrier_frequency_limit_Hz; // the maximum RF frequency we can use +uint32_t carrier_frequency_hz; // the current RF frequency we are on + +uint32_t carrier_datarate_bps; // the RF data rate we are using + +uint32_t rf_bandwidth_used; // the RF bandwidth currently used +uint32_t ss_rf_bandwidth_used; // the RF bandwidth currently used + +uint8_t hbsel; // holds the hbsel (1 or 2) +float frequency_step_size; // holds the minimum frequency step size + +uint8_t frequency_hop_channel; // current frequency hop channel + +uint8_t frequency_hop_step_size_reg; // + +uint8_t adc_config; // holds the adc config reg value + +volatile uint8_t device_status; // device status register +volatile uint8_t int_status1; // interrupt status register 1 +volatile uint8_t int_status2; // interrupt status register 2 +volatile uint8_t ezmac_status; // ezmac status register + +volatile int16_t afc_correction; // afc correction reading +volatile int32_t afc_correction_Hz; // afc correction reading (in Hz) + +volatile int16_t temperature_reg; // the temperature sensor reading + +#if defined(RFM22_DEBUG) +volatile uint8_t prev_device_status; // just for debugging +volatile uint8_t prev_int_status1; // " " +volatile uint8_t prev_int_status2; // " " +volatile uint8_t prev_ezmac_status; // " " + +const char *debug_msg = ""; +const char *error_msg = ""; +static uint32_t debug_val = 0; +#endif + +volatile uint8_t osc_load_cap; // xtal frequency calibration value + +volatile uint8_t rssi; // the current RSSI (register value) +volatile int8_t rssi_dBm; // dBm value + +// the transmit power to use for data transmissions +uint8_t tx_power; +// the tx power register read back +volatile uint8_t tx_pwr; + +// The transmit buffer. Holds data that is being transmitted. +uint8_t tx_buffer[TX_BUFFER_SIZE] __attribute__ ((aligned(4))); +// The transmit buffer. Hosts data that is wating to be transmitted. +uint8_t tx_pre_buffer[TX_BUFFER_SIZE] __attribute__ ((aligned(4))); +// The tx pre-buffer write index. +uint16_t tx_pre_buffer_size; +// the tx data read index +volatile uint16_t tx_data_rd; +// the tx data write index +volatile uint16_t tx_data_wr; + +// the current receive buffer in use (double buffer) +volatile uint8_t rx_buffer_current; +// the receive buffer .. received packet data is saved here +volatile uint8_t rx_buffer[258] __attribute__ ((aligned(4))); +// the receive buffer write index +volatile uint16_t rx_buffer_wr; + +// the received packet +volatile int8_t rx_packet_start_rssi_dBm; // +volatile int8_t rx_packet_start_afc_Hz; // +volatile int8_t rx_packet_rssi_dBm; // the received packet signal strength +volatile int8_t rx_packet_afc_Hz; // the receive packet frequency offset + +int lookup_index; +int ss_lookup_index; + +volatile bool power_on_reset; // set if the RF module has reset itself + +volatile uint16_t rfm22_int_timer; // used to detect if the RF module stops responding. thus act accordingly if it does stop responding. +volatile uint16_t rfm22_int_time_outs; // counter +volatile uint16_t prev_rfm22_int_time_outs; // + +uint16_t timeout_ms = 20000; // +uint16_t timeout_sync_ms = 3; // +uint16_t timeout_data_ms = 20; // + +struct pios_rfm22b_dev * rfm22b_dev_g; + + +static bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev) +{ + return (rfm22b_dev->magic == PIOS_RFM22B_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_rfm22b_dev * PIOS_RFM22B_alloc(void) +{ + struct pios_rfm22b_dev * rfm22b_dev; + + rfm22b_dev = (struct pios_rfm22b_dev *)pvPortMalloc(sizeof(*rfm22b_dev)); + if (!rfm22b_dev) return(NULL); + rfm22b_dev_g = rfm22b_dev; + + rfm22b_dev->magic = PIOS_RFM22B_DEV_MAGIC; + return(rfm22b_dev); +} +#else +static struct pios_rfm22b_dev pios_rfm22b_devs[PIOS_RFM22B_MAX_DEVS]; +static uint8_t pios_rfm22b_num_devs; +static struct pios_rfm22b_dev * PIOS_RFM22B_alloc(void) +{ + struct pios_rfm22b_dev * rfm22b_dev; + + if (pios_rfm22b_num_devs >= PIOS_RFM22B_MAX_DEVS) + return NULL; + + rfm22b_dev = &pios_rfm22b_devs[pios_rfm22b_num_devs++]; + rfm22b_dev->magic = PIOS_RFM22B_DEV_MAGIC; + + return (rfm22b_dev); +} +#endif + +/** + * Initialise an RFM22B device + */ +int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, const struct pios_rfm22b_cfg *cfg) +{ + PIOS_DEBUG_Assert(rfm22b_id); + PIOS_DEBUG_Assert(cfg); + + // Allocate the device structure. + struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *) PIOS_RFM22B_alloc(); + if (!rfm22b_dev) + return(-1); + + // Bind the configuration to the device instance + rfm22b_dev->cfg = *cfg; + + *rfm22b_id = (uint32_t)rfm22b_dev; + + // Initialize the TX pre-buffer pointer. + tx_pre_buffer_size = 0; + + // Create our (hopefully) unique 32 bit id from the processor serial number. + uint8_t crcs[] = { 0, 0, 0, 0 }; + { + char serial_no_str[33]; + PIOS_SYS_SerialNumberGet(serial_no_str); + // Create a 32 bit value using 4 8 bit CRC values. + for (uint8_t i = 0; serial_no_str[i] != 0; ++i) + crcs[i % 4] = PIOS_CRC_updateByte(crcs[i % 4], serial_no_str[i]); + } + rfm22b_dev->deviceID = crcs[0] | crcs[1] << 8 | crcs[2] << 16 | crcs[3] << 24; + DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID); + + // Initialize the supervisor timer. + rfm22b_dev->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; + rfm22b_dev->resets = 0; + + // Initialize the radio device. + int initval = rfm22_init_normal(rfm22b_dev->deviceID, cfg->minFrequencyHz, cfg->maxFrequencyHz, 50000); + + if (initval < 0) + { + + // RF module error .. flash the LED's +#if defined(PIOS_COM_DEBUG) + DEBUG_PRINTF(2, "RF ERROR res: %d\n\r\n\r", initval); +#endif + + for(unsigned int j = 0; j < 16; j++) + { + USB_LED_ON; + LINK_LED_ON; + RX_LED_OFF; + TX_LED_OFF; + + PIOS_DELAY_WaitmS(200); + + USB_LED_OFF; + LINK_LED_OFF; + RX_LED_ON; + TX_LED_ON; + + PIOS_DELAY_WaitmS(200); + } + + PIOS_DELAY_WaitmS(1000); + + return initval; + } + + rfm22_setFreqCalibration(cfg->RFXtalCap); + rfm22_setNominalCarrierFrequency(cfg->frequencyHz); + rfm22_setDatarate(cfg->maxRFBandwidth, TRUE); + rfm22_setTxPower(cfg->maxTxPower); + + DEBUG_PRINTF(2, "\n\r"); + DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID); + DEBUG_PRINTF(2, "RF datarate: %dbps\n\r", rfm22_getDatarate()); + DEBUG_PRINTF(2, "RF frequency: %dHz\n\r", rfm22_getNominalCarrierFrequency()); + DEBUG_PRINTF(2, "RF TX power: %d\n\r", rfm22_getTxPower()); + + // Setup a real-time clock callback to kickstart the radio if a transfer lock sup. + if (!PIOS_RTC_RegisterTickCallback(PIOS_RFM22B_Supervisor, *rfm22b_id)) { + PIOS_DEBUG_Assert(0); + } + + return(0); +} + +uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + + return rfm22b_dev->deviceID; +} + +int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id) +{ + return rfm22_receivedRSSI(); +} + +int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + + return rfm22b_dev->resets; +} + +static void PIOS_RFM22B_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail) +{ + struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + + bool valid = PIOS_RFM22B_validate(rfm22b_dev); + PIOS_Assert(valid); + +} + +static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail) +{ + struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + bool valid = PIOS_RFM22B_validate(rfm22b_dev); + PIOS_Assert(valid); + + // Get some data to send + bool need_yield = false; + if(tx_pre_buffer_size == 0) + tx_pre_buffer_size = (rfm22b_dev->tx_out_cb)(rfm22b_dev->tx_out_context, tx_pre_buffer, + TX_BUFFER_SIZE, NULL, &need_yield); + + if(tx_pre_buffer_size > 0) + { + // already have data to be sent + if (tx_data_wr > 0) + return; + + // we are currently transmitting or scanning the spectrum + if (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE || + rf_mode == TX_PN_MODE || rf_mode == RX_SCAN_SPECTRUM) + return; + + // is the channel clear to transmit on? + if (!rfm22_channelIsClear()) + return; + + // Start the transmit + rfm22_txStart(); + } +} + +/** + * Changes the baud rate of the RFM22B peripheral without re-initialising. + * \param[in] rfm22b_id RFM22B name (GPS, TELEM, AUX) + * \param[in] baud Requested baud rate + */ +static void PIOS_RFM22B_ChangeBaud(uint32_t rfm22b_id, uint32_t baud) +{ + struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + + bool valid = PIOS_RFM22B_validate(rfm22b_dev); + PIOS_Assert(valid); + +} + +static void PIOS_RFM22B_RegisterRxCallback(uint32_t rfm22b_id, pios_com_callback rx_in_cb, uint32_t context) +{ + struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + + bool valid = PIOS_RFM22B_validate(rfm22b_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + rfm22b_dev->rx_in_context = context; + rfm22b_dev->rx_in_cb = rx_in_cb; +} + +static void PIOS_RFM22B_RegisterTxCallback(uint32_t rfm22b_id, pios_com_callback tx_out_cb, uint32_t context) +{ + struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + + bool valid = PIOS_RFM22B_validate(rfm22b_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + rfm22b_dev->tx_out_context = context; + rfm22b_dev->tx_out_cb = tx_out_cb; +} + +static void PIOS_RFM22B_Supervisor(uint32_t rfm22b_id) +{ + /* Recover our device context */ + struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + + if (!PIOS_RFM22B_validate(rfm22b_dev)) { + /* Invalid device specified */ + return; + } + + /* If we're waiting for a receive, we just need to make sure that there are no packets waiting to be transmitted. */ + if(rf_mode == RX_WAIT_PREAMBLE_MODE) + { + /* Start a packet transfer if one is available. */ + PIOS_RFM22B_TxStart(rfm22b_id, 0); + return; + } + + /* The radio must be locked up if the timer reaches 0 */ + if(--(rfm22b_dev->supv_timer) != 0) + return; + ++(rfm22b_dev->resets); + + TX_LED_OFF; + TX_LED_OFF; + + /* Clear the TX buffer in case we locked up in a transmit */ + tx_data_wr = 0; + + rfm22_init_normal(rfm22b_dev->deviceID, rfm22b_dev->cfg.minFrequencyHz, rfm22b_dev->cfg.maxFrequencyHz, 50000); + + /* Start a packet transfer if one is available. */ + rf_mode = RX_WAIT_PREAMBLE_MODE; + PIOS_RFM22B_TxStart(rfm22b_id, 0); + if(rf_mode == RX_WAIT_PREAMBLE_MODE) + { + /* Switch to RX mode */ + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + } +} + +static void rfm22_setDebug(const char* msg) +{ + debug_msg = msg; +} + +static void rfm22_setError(const char* msg) +{ + error_msg = msg; +} + +// ************************************ +// SPI read/write + +void rfm22_startBurstWrite(uint8_t addr) +{ + // wait 1us .. so we don't toggle the CS line to quickly + PIOS_DELAY_WaituS(1); + + // chip select line LOW + PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0); + + PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr); +} + +void rfm22_endBurstWrite(void) +{ + // chip select line HIGH + PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1); +} + +void rfm22_write(uint8_t addr, uint8_t data) +{ + // wait 1us .. so we don't toggle the CS line to quickly + PIOS_DELAY_WaituS(1); + + // chip select line LOW + PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0); + + PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr); + PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data); + + // chip select line HIGH + PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1); +} + +void rfm22_startBurstRead(uint8_t addr) +{ + // wait 1us .. so we don't toggle the CS line to quickly + PIOS_DELAY_WaituS(1); + + // chip select line LOW + PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0); + + PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f); +} + +void rfm22_endBurstRead(void) +{ + // chip select line HIGH + PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1); +} + +uint8_t rfm22_read(uint8_t addr) +{ + uint8_t rdata; + + // wait 1us .. so we don't toggle the CS line to quickly + PIOS_DELAY_WaituS(1); + + // chip select line LOW + PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0); + + PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f); + rdata = PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff); + + // chip select line HIGH + PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1); + + return rdata; +} + +// ************************************ +// external interrupt + + +static void PIOS_RFM22_EXT_Int(void) +{ + rfm22_setDebug("Ext Int"); + if (!exec_using_spi) + rfm22_processInt(); + rfm22_setDebug("Ext Done"); +} + +void rfm22_disableExtInt(void) +{ +#if defined(RFM22_EXT_INT_USE) + rfm22_setDebug("Disable Int"); + // Configure the external interrupt + GPIO_EXTILineConfig(PIOS_RFM22_EXTI_PORT_SOURCE, PIOS_RFM22_EXTI_PIN_SOURCE); + EXTI_InitTypeDef EXTI_InitStructure = pios_exti_rfm22b_cfg.exti.init; + EXTI_InitStructure.EXTI_LineCmd = DISABLE; + EXTI_Init(&EXTI_InitStructure); + + EXTI_ClearFlag(PIOS_RFM22_EXTI_LINE); + rfm22_setDebug("Disable Int done"); +#endif +} + +void rfm22_enableExtInt(void) +{ +#if defined(RFM22_EXT_INT_USE) + rfm22_setDebug("Ensable Int"); + if (PIOS_EXTI_Init(&pios_exti_rfm22b_cfg)) + PIOS_Assert(0); + rfm22_setDebug("Ensable Int done"); +#endif +} + + +// ************************************ +// set/get the current tx power setting + +void rfm22_setTxPower(uint8_t tx_pwr) +{ + switch (tx_pwr) + { + case 0: tx_power = RFM22_tx_pwr_txpow_0; break; // +1dBm ... 1.25mW + case 1: tx_power = RFM22_tx_pwr_txpow_1; break; // +2dBm ... 1.6mW + case 2: tx_power = RFM22_tx_pwr_txpow_2; break; // +5dBm ... 3.16mW + case 3: tx_power = RFM22_tx_pwr_txpow_3; break; // +8dBm ... 6.3mW + case 4: tx_power = RFM22_tx_pwr_txpow_4; break; // +11dBm .. 12.6mW + case 5: tx_power = RFM22_tx_pwr_txpow_5; break; // +14dBm .. 25mW + case 6: tx_power = RFM22_tx_pwr_txpow_6; break; // +17dBm .. 50mW + case 7: tx_power = RFM22_tx_pwr_txpow_7; break; // +20dBm .. 100mW + default: break; + } +} + +uint8_t rfm22_getTxPower(void) +{ + return tx_power; +} + +// ************************************ + +uint32_t rfm22_minFrequency(void) +{ + return lower_carrier_frequency_limit_Hz; +} +uint32_t rfm22_maxFrequency(void) +{ + return upper_carrier_frequency_limit_Hz; +} + +void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz) +{ + + exec_using_spi = TRUE; + + // ******* + + if (frequency_hz < lower_carrier_frequency_limit_Hz) + frequency_hz = lower_carrier_frequency_limit_Hz; + else if (frequency_hz > upper_carrier_frequency_limit_Hz) + frequency_hz = upper_carrier_frequency_limit_Hz; + + if (frequency_hz < 480000000) + hbsel = 1; + else + hbsel = 2; + uint8_t fb = (uint8_t)(frequency_hz / (10000000 * hbsel)); + + uint32_t fc = (uint32_t)(frequency_hz - (10000000 * hbsel * fb)); + + fc = (fc * 64u) / (10000ul * hbsel); + fb -= 24; + + // carrier_frequency_hz = frequency_hz; + carrier_frequency_hz = ((uint32_t)fb + 24 + ((float)fc / 64000)) * 10000000 * hbsel; + + if (hbsel > 1) + fb |= RFM22_fbs_hbsel; + + fb |= RFM22_fbs_sbse; // is this the RX LO polarity? + + frequency_step_size = 156.25f * hbsel; + + rfm22_write(RFM22_frequency_hopping_channel_select, frequency_hop_channel); // frequency hopping channel (0-255) + + rfm22_write(RFM22_frequency_offset1, 0); // no frequency offset + rfm22_write(RFM22_frequency_offset2, 0); // no frequency offset + + rfm22_write(RFM22_frequency_band_select, fb); // set the carrier frequency + rfm22_write(RFM22_nominal_carrier_frequency1, fc >> 8); // " " + rfm22_write(RFM22_nominal_carrier_frequency0, fc & 0xff); // " " + + // ******* + +#if defined(RFM22_DEBUG) + //DEBUG_PRINTF(2, "rf setFreq: %u\n\r", carrier_frequency_hz); + // DEBUG_PRINTF(2, "rf setFreq frequency_step_size: %0.2f\n\r", frequency_step_size); +#endif + + exec_using_spi = FALSE; +} + +uint32_t rfm22_getNominalCarrierFrequency(void) +{ + return carrier_frequency_hz; +} + +float rfm22_getFrequencyStepSize(void) +{ + return frequency_step_size; +} + +void rfm22_setFreqHopChannel(uint8_t channel) +{ // set the frequency hopping channel + frequency_hop_channel = channel; + rfm22_write(RFM22_frequency_hopping_channel_select, frequency_hop_channel); +} + +uint8_t rfm22_freqHopChannel(void) +{ // return the current frequency hopping channel + return frequency_hop_channel; +} + +uint32_t rfm22_freqHopSize(void) +{ // return the frequency hopping step size + return ((uint32_t)frequency_hop_step_size_reg * 10000); +} + +// ************************************ +// radio datarate about 19200 Baud +// radio frequency deviation 45kHz +// radio receiver bandwidth 67kHz. +// +// Carson's rule: +// The signal bandwidth is about 2(Delta-f + fm) .. +// +// Delta-f = frequency deviation +// fm = maximum frequency of the signal +// +// This gives 2(45 + 9.6) = 109.2kHz. + +void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) +{ + + exec_using_spi = TRUE; + + lookup_index = 0; + while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps) + lookup_index++; + + carrier_datarate_bps = datarate_bps = data_rate[lookup_index]; + + rf_bandwidth_used = rx_bandwidth[lookup_index]; + + // rfm22_if_filter_bandwidth + rfm22_write(0x1C, reg_1C[lookup_index]); + + // rfm22_afc_loop_gearshift_override + rfm22_write(0x1D, reg_1D[lookup_index]); + // RFM22_afc_timing_control + rfm22_write(0x1E, reg_1E[lookup_index]); + + // RFM22_clk_recovery_gearshift_override + rfm22_write(0x1F, reg_1F[lookup_index]); + // rfm22_clk_recovery_oversampling_ratio + rfm22_write(0x20, reg_20[lookup_index]); + // rfm22_clk_recovery_offset2 + rfm22_write(0x21, reg_21[lookup_index]); + // rfm22_clk_recovery_offset1 + rfm22_write(0x22, reg_22[lookup_index]); + // rfm22_clk_recovery_offset0 + rfm22_write(0x23, reg_23[lookup_index]); + // rfm22_clk_recovery_timing_loop_gain1 + rfm22_write(0x24, reg_24[lookup_index]); + // rfm22_clk_recovery_timing_loop_gain0 + rfm22_write(0x25, reg_25[lookup_index]); + + // rfm22_afc_limiter + rfm22_write(0x2A, reg_2A[lookup_index]); + + if (carrier_datarate_bps < 100000) + // rfm22_chargepump_current_trimming_override + rfm22_write(0x58, 0x80); + else + // rfm22_chargepump_current_trimming_override + rfm22_write(0x58, 0xC0); + + // rfm22_tx_data_rate1 + rfm22_write(0x6E, reg_6E[lookup_index]); + // rfm22_tx_data_rate0 + rfm22_write(0x6F, reg_6F[lookup_index]); + + // Enable data whitening + // uint8_t txdtrtscale_bit = rfm22_read(RFM22_modulation_mode_control1) & RFM22_mmc1_txdtrtscale; + // rfm22_write(RFM22_modulation_mode_control1, txdtrtscale_bit | RFM22_mmc1_enwhite); + + if (!data_whitening) + // rfm22_modulation_mode_control1 + rfm22_write(0x70, reg_70[lookup_index] & ~RFM22_mmc1_enwhite); + else + // rfm22_modulation_mode_control1 + rfm22_write(0x70, reg_70[lookup_index] | RFM22_mmc1_enwhite); + + // rfm22_modulation_mode_control2 + rfm22_write(0x71, reg_71[lookup_index]); + + // rfm22_frequency_deviation + rfm22_write(0x72, reg_72[lookup_index]); + + rfm22_write(RFM22_ook_counter_value1, 0x00); + rfm22_write(RFM22_ook_counter_value2, 0x00); + + // ******************************** + // calculate the TX register values + /* + uint16_t fd = frequency_deviation / 625; + + uint8_t mmc1 = RFM22_mmc1_enphpwdn | RFM22_mmc1_manppol; + uint16_t txdr; + if (datarate_bps < 30000) + { + txdr = (datarate_bps * 20972) / 10000; + mmc1 |= RFM22_mmc1_txdtrtscale; + } + else + txdr = (datarate_bps * 6553) / 100000; + + uint8_t mmc2 = RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk; // FIFO mode, GFSK + // uint8_t mmc2 = RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_gfsk; // PN9 mode, GFSK .. TX TEST MODE + if (fd & 0x100) mmc2 |= RFM22_mmc2_fd; + + rfm22_write(RFM22_frequency_deviation, fd); // set the TX peak frequency deviation + + rfm22_write(RFM22_modulation_mode_control1, mmc1); + rfm22_write(RFM22_modulation_mode_control2, mmc2); + + rfm22_write(RFM22_tx_data_rate1, txdr >> 8); // set the TX data rate + rfm22_write(RFM22_tx_data_rate0, txdr); // " " + */ + // ******************************** + // determine a clear channel time + + // initialise the stopwatch with a suitable resolution for the datarate + //STOPWATCH_init(4000000ul / carrier_datarate_bps); // set resolution to the time for 1 nibble (4-bits) at rf datarate + + // ******************************** + // determine suitable time-out periods + + // milliseconds + timeout_sync_ms = (8000ul * 16) / carrier_datarate_bps; + if (timeout_sync_ms < 3) + // because out timer resolution is only 1ms + timeout_sync_ms = 3; + + // milliseconds + timeout_data_ms = (8000ul * 100) / carrier_datarate_bps; + if (timeout_data_ms < 3) + // because out timer resolution is only 1ms + timeout_data_ms = 3; + + // ******************************** + +#if defined(RFM22_DEBUG) +/* + DEBUG_PRINTF(2, "rf datarate_bps: %d\n\r", datarate_bps); + DEBUG_PRINTF(2, "rf frequency_deviation: %d\n\r", frequency_deviation); + uint32_t frequency_deviation = freq_deviation[lookup_index]; // Hz + uint32_t modulation_bandwidth = datarate_bps + (2 * frequency_deviation); + DEBUG_PRINTF(2, "rf modulation_bandwidth: %u\n\r", modulation_bandwidth); + DEBUG_PRINTF(2, "rf_rx_bandwidth[%u]: %u\n\r", lookup_index, rx_bandwidth[lookup_index]); + DEBUG_PRINTF(2, "rf est rx sensitivity[%u]: %ddBm\n\r", lookup_index, est_rx_sens_dBm[lookup_index]); +*/ +#endif + + // ******* + + exec_using_spi = FALSE; +} + +uint32_t rfm22_getDatarate(void) +{ + return carrier_datarate_bps; +} + +// ************************************ + +void rfm22_setSSBandwidth(uint32_t bandwidth_index) +{ + + exec_using_spi = TRUE; + + ss_lookup_index = bandwidth_index; + + ss_rf_bandwidth_used = ss_rx_bandwidth[lookup_index]; + + // ******************************** + + rfm22_write(0x1C, ss_reg_1C[ss_lookup_index]); // rfm22_if_filter_bandwidth + rfm22_write(0x1D, ss_reg_1D[ss_lookup_index]); // rfm22_afc_loop_gearshift_override + + rfm22_write(0x20, ss_reg_20[ss_lookup_index]); // rfm22_clk_recovery_oversampling_ratio + rfm22_write(0x21, ss_reg_21[ss_lookup_index]); // rfm22_clk_recovery_offset2 + rfm22_write(0x22, ss_reg_22[ss_lookup_index]); // rfm22_clk_recovery_offset1 + rfm22_write(0x23, ss_reg_23[ss_lookup_index]); // rfm22_clk_recovery_offset0 + rfm22_write(0x24, ss_reg_24[ss_lookup_index]); // rfm22_clk_recovery_timing_loop_gain1 + rfm22_write(0x25, ss_reg_25[ss_lookup_index]); // rfm22_clk_recovery_timing_loop_gain0 + + rfm22_write(0x2A, ss_reg_2A[ss_lookup_index]); // rfm22_afc_limiter + + rfm22_write(0x58, 0x80); // rfm22_chargepump_current_trimming_override + + rfm22_write(0x70, ss_reg_70[ss_lookup_index]); // rfm22_modulation_mode_control1 + rfm22_write(0x71, ss_reg_71[ss_lookup_index]); // rfm22_modulation_mode_control2 + + rfm22_write(RFM22_ook_counter_value1, 0x00); + rfm22_write(RFM22_ook_counter_value2, 0x00); + + // ******************************** + +#if defined(RFM22_DEBUG) + DEBUG_PRINTF(2, "ss_rf_rx_bandwidth[%u]: %u\n\r", ss_lookup_index, ss_rx_bandwidth[ss_lookup_index]); +#endif + + // ******* + + exec_using_spi = FALSE; +} + +// ************************************ + +void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode) +{ + exec_using_spi = TRUE; + + // disable interrupts + rfm22_write(RFM22_interrupt_enable1, 0x00); + rfm22_write(RFM22_interrupt_enable2, 0x00); + + // Switch to TUNE mode + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); + + RX_LED_OFF; + TX_LED_OFF; + + if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE) + { + // FIFO mode, GFSK modulation + uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; + rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | + RFM22_mmc2_modtyp_gfsk); + } + + // empty the rx buffer + rx_buffer_wr = 0; + // reset the timer + rfm22_int_timer = 0; + rf_mode = mode; + + // Clear the TX buffer. + tx_data_rd = tx_data_wr = 0; + + // clear FIFOs + if (!multi_packet_mode) + { + rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); + rfm22_write(RFM22_op_and_func_ctrl2, 0x00); + } else { + rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_rxmpk | RFM22_opfc2_ffclrrx | + RFM22_opfc2_ffclrtx); + rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_rxmpk); + } + + // enable RX interrupts + rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_encrcerror | RFM22_ie1_enpkvalid | + RFM22_ie1_enrxffafull | RFM22_ie1_enfferr); + rfm22_write(RFM22_interrupt_enable2, RFM22_ie2_enpreainval | RFM22_ie2_enpreaval | + RFM22_ie2_enswdet); + + // enable the receiver + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_rxon); + + exec_using_spi = FALSE; +} + +// ************************************ + +uint16_t rfm22_addHeader() +{ + uint16_t i = 0; + + for (uint16_t j = (TX_PREAMBLE_NIBBLES + 1) / 2; j > 0; j--) + { + rfm22_burstWrite(PREAMBLE_BYTE); + i++; + } + rfm22_burstWrite(SYNC_BYTE_1); i++; + rfm22_burstWrite(SYNC_BYTE_2); i++; + + return i; +} + +// ************************************ + +uint8_t rfm22_txStart() +{ + if((tx_pre_buffer_size == 0) || (exec_using_spi == TRUE)) + { + // Clear the TX buffer. + tx_data_rd = tx_data_wr = 0; + return 0; + } + + exec_using_spi = TRUE; + + // Disable interrrupts. + PIOS_IRQ_Disable(); + + // Initialize the supervisor timer. + rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; + + // disable interrupts + rfm22_write(RFM22_interrupt_enable1, 0x00); + rfm22_write(RFM22_interrupt_enable2, 0x00); + + // TUNE mode + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); + + // Queue the data up for sending + memcpy(tx_buffer, tx_pre_buffer, tx_pre_buffer_size); + tx_data_rd = 0; + tx_data_wr = tx_pre_buffer_size; + tx_pre_buffer_size = 0; + + RX_LED_OFF; + + // Set the destination address in the transmit header. + // The destination address is the first 4 bytes of the message. + rfm22_write(RFM22_transmit_header0, tx_buffer[0]); + rfm22_write(RFM22_transmit_header1, tx_buffer[1]); + rfm22_write(RFM22_transmit_header2, tx_buffer[2]); + rfm22_write(RFM22_transmit_header3, tx_buffer[3]); + + // FIFO mode, GFSK modulation + uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; + rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | + RFM22_mmc2_modtyp_gfsk); + + // set the tx power + rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | + RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); + + // clear FIFOs + rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); + rfm22_write(RFM22_op_and_func_ctrl2, 0x00); + + // ******************* + // add some data to the chips TX FIFO before enabling the transmitter + + // set the total number of data bytes we are going to transmit + rfm22_write(RFM22_transmit_packet_length, tx_data_wr); + + // add some data + rfm22_startBurstWrite(RFM22_fifo_access); + for (uint16_t i = 0; (tx_data_rd < tx_data_wr) && (i < FIFO_SIZE); ++tx_data_rd, ++i) + rfm22_burstWrite(tx_buffer[tx_data_rd]); + rfm22_endBurstWrite(); + + // ******************* + + // reset the timer + rfm22_int_timer = 0; + + rf_mode = TX_DATA_MODE; + + // enable TX interrupts + rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); + + // enable the transmitter + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); + + // Re-ensable interrrupts. + PIOS_IRQ_Enable(); + + TX_LED_ON; + + exec_using_spi = FALSE; + return 1; +} + + +static void rfm22_setTxMode(uint8_t mode) +{ + rfm22_setDebug("setTxMode"); + if (mode != TX_DATA_MODE && mode != TX_STREAM_MODE && mode != TX_CARRIER_MODE && mode != TX_PN_MODE) + return; // invalid mode + + exec_using_spi = TRUE; + + // disable interrupts + rfm22_write(RFM22_interrupt_enable1, 0x00); + rfm22_write(RFM22_interrupt_enable2, 0x00); + + // TUNE mode + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); + + RX_LED_OFF; + + // set the tx power + rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | + RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); + + uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; + if (mode == TX_CARRIER_MODE) + // blank carrier mode - for testing + rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | + RFM22_mmc2_modtyp_none); // FIFO mode, Blank carrier + else if (mode == TX_PN_MODE) + // psuedo random data carrier mode - for testing + rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | + RFM22_mmc2_modtyp_gfsk); // FIFO mode, PN9 carrier + else + // data transmission + // FIFO mode, GFSK modulation + rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | + RFM22_mmc2_modtyp_gfsk); + + // clear FIFOs + rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); + rfm22_write(RFM22_op_and_func_ctrl2, 0x00); + + // add some data to the chips TX FIFO before enabling the transmitter + { + uint16_t rd = 0; + uint16_t wr = tx_data_wr; + + if (mode == TX_DATA_MODE) + // set the total number of data bytes we are going to transmit + rfm22_write(RFM22_transmit_packet_length, wr); + + uint16_t max_bytes = FIFO_SIZE - 1; + uint16_t i = 0; + rfm22_startBurstWrite(RFM22_fifo_access); + if (mode == TX_STREAM_MODE) { + if (rd >= wr) { + // no data to send - yet .. just send preamble pattern + while (true) { + rfm22_burstWrite(PREAMBLE_BYTE); + if (++i >= max_bytes) break; + } + } else // add the RF heaader + i += rfm22_addHeader(); + } + + // add some data + for (uint16_t j = wr - rd; j > 0; j--) { + rfm22_burstWrite(tx_buffer[rd++]); + if (++i >= max_bytes) + break; + } + + rfm22_endBurstWrite(); + + tx_data_rd = rd; + } + + // reset the timer + rfm22_int_timer = 0; + + rf_mode = mode; + + // enable TX interrupts + // rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem | RFM22_ie1_enfferr); + rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); + + // read interrupt status - clear interrupts + rfm22_read(RFM22_interrupt_status1); + rfm22_read(RFM22_interrupt_status2); + + // enable the transmitter + // rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_txon); + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); + + TX_LED_ON; + + // ******************* + + exec_using_spi = FALSE; + + rfm22_setDebug("setTxMode end"); +} + +// ************************************ +// external interrupt line triggered (or polled) from the rf chip + +void rfm22_processRxInt(void) +{ + register uint8_t int_stat1 = int_status1; + register uint8_t int_stat2 = int_status2; + rfm22_setDebug("processRxInt"); + + // FIFO under/over flow error. Restart RX mode. + if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) + { + rfm22_setError("R_UNDER/OVERRUN"); + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + return; + } + + // Valid preamble detected + if (int_stat2 & RFM22_is2_ipreaval && (rf_mode == RX_WAIT_PREAMBLE_MODE)) + { + rf_mode = RX_WAIT_SYNC_MODE; + RX_LED_ON; + rfm22_setDebug("pream_det"); + } + + // Sync word detected + if (int_stat2 & RFM22_is2_iswdet && ((rf_mode == RX_WAIT_PREAMBLE_MODE || rf_mode == RX_WAIT_SYNC_MODE))) + { + rf_mode = RX_DATA_MODE; + RX_LED_ON; + rfm22_setDebug("sync_det"); + + // read the 10-bit signed afc correction value + // bits 9 to 2 + afc_correction = (uint16_t)rfm22_read(RFM22_afc_correction_read) << 8; + // bits 1 & 0 + afc_correction |= (uint16_t)rfm22_read(RFM22_ook_counter_value1) & 0x00c0; + afc_correction >>= 6; + // convert the afc value to Hz + afc_correction_Hz = (int32_t)(frequency_step_size * afc_correction + 0.5f); + + // remember the rssi for this packet + rx_packet_start_rssi_dBm = rssi_dBm; + // remember the afc value for this packet + rx_packet_start_afc_Hz = afc_correction_Hz; + } + + // RX FIFO almost full, it needs emptying + if (int_stat1 & RFM22_is1_irxffafull) + { + if (rf_mode == RX_DATA_MODE) + { + // read data from the rf chips FIFO buffer + // read the total length of the packet data + uint16_t len = rfm22_read(RFM22_received_packet_length); + + // The received packet is going to be larger than the specified length + if ((rx_buffer_wr + RX_FIFO_HI_WATERMARK) > len) + { + rfm22_setError("r_size_error1"); + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + return; + } + + // Another packet length error. + if (((rx_buffer_wr + RX_FIFO_HI_WATERMARK) >= len) && !(int_stat1 & RFM22_is1_ipkvalid)) + { + rfm22_setError("r_size_error2"); + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + return; + } + + // Fetch the data from the RX FIFO + rfm22_startBurstRead(RFM22_fifo_access); + for (uint8_t i = 0; i < RX_FIFO_HI_WATERMARK; ++i) + rx_buffer[rx_buffer_wr++] = rfm22_burstRead(); + rfm22_endBurstRead(); + } + else + { // just clear the RX FIFO + rfm22_startBurstRead(RFM22_fifo_access); + for (register uint16_t i = RX_FIFO_HI_WATERMARK; i > 0; i--) + rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer + rfm22_endBurstRead(); + } + } + + // CRC error .. discard the received data + if (int_stat1 & RFM22_is1_icrerror) + { + rfm22_int_timer = 0; // reset the timer + rfm22_setError("CRC_ERR"); + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + return; + } + + // Valid packet received + if (int_stat1 & RFM22_is1_ipkvalid) + { + + // read the total length of the packet data + register uint16_t len = rfm22_read(RFM22_received_packet_length); + + // their must still be data in the RX FIFO we need to get + if (rx_buffer_wr < len) + { + // Fetch the data from the RX FIFO + rfm22_startBurstRead(RFM22_fifo_access); + while (rx_buffer_wr < len) + rx_buffer[rx_buffer_wr++] = rfm22_burstRead(); + rfm22_endBurstRead(); + } + + if (rx_buffer_wr != len) + { + // we have a packet length error .. discard the packet + rfm22_setError("r_pack_len_error"); + debug_val = len; + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + return; + } + + // we have a valid received packet + rfm22_setDebug("VALID_R_PACKET"); + + if (rx_buffer_wr > 0) + { + // remember the rssi for this packet + rx_packet_rssi_dBm = rx_packet_start_rssi_dBm; + // remember the afc offset for this packet + rx_packet_afc_Hz = rx_packet_start_afc_Hz; + // Add the rssi and afc to the end of the packet. + rx_buffer[rx_buffer_wr++] = rx_packet_start_rssi_dBm; + rx_buffer[rx_buffer_wr++] = rx_packet_start_afc_Hz; + // Pass this packet on + bool need_yield = false; + if (rfm22b_dev_g->rx_in_cb) + (rfm22b_dev_g->rx_in_cb)(rfm22b_dev_g->rx_in_context, (uint8_t*)rx_buffer, + rx_buffer_wr, NULL, &need_yield); + rx_buffer_wr = 0; + } + + // Send a packet if it's available. + if(!rfm22_txStart()) + { + // Switch to RX mode + rfm22_setDebug(" Set RX"); + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + } + } + + rfm22_setDebug("processRxInt end"); +} + +void rfm22_processTxInt(void) +{ + register uint8_t int_stat1 = int_status1; + + // reset the timer + rfm22_int_timer = 0; + + // FIFO under/over flow error. Back to RX mode. + if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) + { + rfm22_setError("T_UNDER/OVERRUN"); + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + return; + } + + // Transmit timeout. Abort the transmit. + if (rfm22_int_timer >= timeout_data_ms) + { + rfm22_int_time_outs++; + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + return; + } + + // the rf module is not in tx mode + if ((device_status & RFM22_ds_cps_mask) != RFM22_ds_cps_tx) + { + if (rfm22_int_timer >= 100) + { + rfm22_int_time_outs++; + rfm22_setError("T_TIMEOUT"); + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode + return; + } + } + + // TX FIFO almost empty, it needs filling up + if (int_stat1 & RFM22_is1_ixtffaem) + { + // top-up the rf chips TX FIFO buffer + uint16_t max_bytes = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1; + rfm22_startBurstWrite(RFM22_fifo_access); + for (uint16_t i = 0; (tx_data_rd < tx_data_wr) && (i < max_bytes); ++i, ++tx_data_rd) + rfm22_burstWrite(tx_buffer[tx_data_rd]); + rfm22_endBurstWrite(); + } + + // Packet has been sent + if (int_stat1 & RFM22_is1_ipksent) + { + rfm22_setDebug(" T_Sent"); + + // Send another packet if it's available. + if(!rfm22_txStart()) + { + // Switch to RX mode + rfm22_setDebug(" Set RX"); + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + return; + } + } + + rfm22_setDebug("ProcessTxInt done"); +} + +static void rfm22_processInt(void) +{ + rfm22_setDebug("ProcessInt"); + // this is called from the external interrupt handler + + if (!initialized || power_on_reset) + // we haven't yet been initialized + return; + + exec_using_spi = TRUE; + + // Reset the supervisor timer. + rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; + + // read interrupt status registers - clears the interrupt line + int_status1 = rfm22_read(RFM22_interrupt_status1); + int_status2 = rfm22_read(RFM22_interrupt_status2); + + // read device status register + device_status = rfm22_read(RFM22_device_status); + + // read ezmac status register + ezmac_status = rfm22_read(RFM22_ezmac_status); + + // Read the RSSI if we're in RX mode + if (rf_mode != TX_DATA_MODE && rf_mode != TX_STREAM_MODE && + rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE) + { + // read rx signal strength .. 45 = -100dBm, 205 = -20dBm + rssi = rfm22_read(RFM22_rssi); + // convert to dBm + rssi_dBm = (int8_t)(rssi >> 1) - 122; + } + else + // read the tx power register + tx_pwr = rfm22_read(RFM22_tx_power); + + // the RF module has gone and done a reset - we need to re-initialize the rf module + if (int_status2 & RFM22_is2_ipor) + { + initialized = FALSE; + power_on_reset = TRUE; + rfm22_setError("Reset"); + // Need to do something here! + return; + } + + switch (rf_mode) + { + case RX_SCAN_SPECTRUM: + break; + + case RX_WAIT_PREAMBLE_MODE: + case RX_WAIT_SYNC_MODE: + case RX_DATA_MODE: + + rfm22_processRxInt(); + break; + + case TX_DATA_MODE: + case TX_STREAM_MODE: + + rfm22_processTxInt(); + break; + + case TX_CARRIER_MODE: + case TX_PN_MODE: + + // if (rfm22_int_timer >= TX_TEST_MODE_TIMELIMIT_MS) // 'nn'ms limit + // { + // rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode + // tx_data_rd = tx_data_wr = 0; // wipe TX buffer + // break; + // } + + break; + + default: // unknown mode - this should NEVER happen, maybe we should do a complete CPU reset here + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // to rx mode + break; + } + + exec_using_spi = FALSE; + + rfm22_setDebug("ProcessInt done"); +} + +// ************************************ + +int8_t rfm22_getRSSI(void) +{ + exec_using_spi = TRUE; + + rssi = rfm22_read(RFM22_rssi); // read rx signal strength .. 45 = -100dBm, 205 = -20dBm + rssi_dBm = (int8_t)(rssi >> 1) - 122; // convert to dBm + + exec_using_spi = FALSE; + return rssi_dBm; +} + +int8_t rfm22_receivedRSSI(void) +{ // return the packets signal strength + if (!initialized) + return -127; + else + return rx_packet_rssi_dBm; +} + +int32_t rfm22_receivedAFCHz(void) +{ // return the packets offset frequency + if (!initialized) + return 0; + else + return rx_packet_afc_Hz; +} + +// ************************************ + +// ************************************ + +void rfm22_setTxStream(void) // TEST ONLY +{ + if (!initialized) + return; + + tx_data_rd = tx_data_wr = 0; + + rfm22_setTxMode(TX_STREAM_MODE); +} + +// ************************************ + +void rfm22_setTxNormal(void) +{ + if (!initialized) + return; + + // if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE) + if (rf_mode != RX_SCAN_SPECTRUM) + { + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + tx_data_rd = tx_data_wr = 0; + + rx_packet_start_rssi_dBm = 0; + rx_packet_start_afc_Hz = 0; + rx_packet_rssi_dBm = 0; + rx_packet_afc_Hz = 0; + } +} + +// enable a blank tx carrier (for frequency alignment) +void rfm22_setTxCarrierMode(void) +{ + if (!initialized) + return; + + if (rf_mode != TX_CARRIER_MODE && rf_mode != RX_SCAN_SPECTRUM) + rfm22_setTxMode(TX_CARRIER_MODE); +} + +// enable a psuedo random data tx carrier (for spectrum inspection) +void rfm22_setTxPNMode(void) +{ + if (!initialized) + return; + + if (rf_mode != TX_PN_MODE && rf_mode != RX_SCAN_SPECTRUM) + rfm22_setTxMode(TX_PN_MODE); +} + +// ************************************ + +// return the current mode +int8_t rfm22_currentMode(void) +{ + return rf_mode; +} + +// return TRUE if we are transmitting +bool rfm22_transmitting(void) +{ + return (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE); +} + +// return TRUE if the channel is clear to transmit on +bool rfm22_channelIsClear(void) +{ + if (!initialized) + // we haven't yet been initialized + return FALSE; + + if (rf_mode != RX_WAIT_PREAMBLE_MODE && rf_mode != RX_WAIT_SYNC_MODE) + // we are receiving something or we are transmitting or we are scanning the spectrum + return FALSE; + + return TRUE; +} + +// return TRUE if the transmiter is ready for use +bool rfm22_txReady(void) +{ + if (!initialized) + // we haven't yet been initialized + return FALSE; + + return (tx_data_rd == 0 && tx_data_wr == 0 && rf_mode != TX_DATA_MODE && + rf_mode != TX_STREAM_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE && + rf_mode != RX_SCAN_SPECTRUM); +} + +// ************************************ +// set/get the frequency calibration value + +void rfm22_setFreqCalibration(uint8_t value) +{ + osc_load_cap = value; + + if (!initialized || power_on_reset) + return; // we haven't yet been initialized + + uint8_t prev_rf_mode = rf_mode; + + if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE) + { + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + tx_data_rd = tx_data_wr = 0; + } + + exec_using_spi = TRUE; + + rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap); + + exec_using_spi = FALSE; + + if (prev_rf_mode == TX_CARRIER_MODE || prev_rf_mode == TX_PN_MODE) + rfm22_setTxMode(prev_rf_mode); +} + +uint8_t rfm22_getFreqCalibration(void) +{ + return osc_load_cap; +} + +// ************************************ +// can be called from an interrupt if you wish + +void rfm22_1ms_tick(void) +{ // call this once every ms + if (!initialized) return; // we haven't yet been initialized + + if (rf_mode != RX_SCAN_SPECTRUM) + { + if (rfm22_int_timer < 0xffff) rfm22_int_timer++; + } +} + +// ************************************ +// reset the RF module + +int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_frequency_hz) +{ + initialized = false; + +#if defined(RFM22_EXT_INT_USE) + rfm22_disableExtInt(); +#endif + + power_on_reset = false; + + // **************** + + exec_using_spi = TRUE; + + // **************** + // setup the SPI port + + // chip select line HIGH + PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1); + + // set SPI port SCLK frequency .. 4.5MHz + PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_16); + // set SPI port SCLK frequency .. 2.25MHz + // PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_32); + + // set SPI port SCLK frequency .. 285kHz .. purely for hardware fault finding + // PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_256); + + // **************** + // software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B) + + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_swres); // software reset the radio + + PIOS_DELAY_WaitmS(26); // wait 26ms + + for (int i = 50; i > 0; i--) + { + PIOS_DELAY_WaitmS(1); // wait 1ms + + // read the status registers + int_status1 = rfm22_read(RFM22_interrupt_status1); + int_status2 = rfm22_read(RFM22_interrupt_status2); + if (int_status2 & RFM22_is2_ichiprdy) break; + } + + // **************** + + // read status - clears interrupt + device_status = rfm22_read(RFM22_device_status); + int_status1 = rfm22_read(RFM22_interrupt_status1); + int_status2 = rfm22_read(RFM22_interrupt_status2); + ezmac_status = rfm22_read(RFM22_ezmac_status); + + // disable all interrupts + rfm22_write(RFM22_interrupt_enable1, 0x00); + rfm22_write(RFM22_interrupt_enable2, 0x00); + + // **************** + + exec_using_spi = FALSE; + + // **************** + + rf_mode = mode; + + device_status = int_status1 = int_status2 = ezmac_status = 0; + + rssi = 0; + rssi_dBm = -127; + + rx_buffer_current = 0; + rx_buffer_wr = 0; + rx_packet_rssi_dBm = -127; + rx_packet_afc_Hz = 0; + + tx_data_rd = tx_data_wr = 0; + + lookup_index = 0; + ss_lookup_index = 0; + + rf_bandwidth_used = 0; + ss_rf_bandwidth_used = 0; + + rfm22_int_timer = 0; + rfm22_int_time_outs = 0; + prev_rfm22_int_time_outs = 0; + + hbsel = 0; + frequency_step_size = 0.0f; + + frequency_hop_channel = 0; + + afc_correction = 0; + afc_correction_Hz = 0; + + temperature_reg = 0; + + // set the TX power + tx_power = RFM22_DEFAULT_RF_POWER; + + tx_pwr = 0; + + // **************** + // read the RF chip ID bytes + + device_type = rfm22_read(RFM22_DEVICE_TYPE) & RFM22_DT_MASK; // read the device type + device_version = rfm22_read(RFM22_DEVICE_VERSION) & RFM22_DV_MASK; // read the device version + +#if defined(RFM22_DEBUG) + DEBUG_PRINTF(2, "rf device type: %d\n\r", device_type); + DEBUG_PRINTF(2, "rf device version: %d\n\r", device_version); +#endif + + if (device_type != 0x08) + { +#if defined(RFM22_DEBUG) + DEBUG_PRINTF(2, "rf device type: INCORRECT - should be 0x08\n\r"); +#endif + return -1; // incorrect RF module type + } + + // if (device_version != RFM22_DEVICE_VERSION_V2) // V2 + // return -2; // incorrect RF module version + // if (device_version != RFM22_DEVICE_VERSION_A0) // A0 + // return -2; // incorrect RF module version + if (device_version != RFM22_DEVICE_VERSION_B1) // B1 + { +#if defined(RFM22_DEBUG) + DEBUG_PRINTF(2, "rf device version: INCORRECT\n\r"); +#endif + return -2; // incorrect RF module version + } + + // **************** + // set the minimum and maximum carrier frequency allowed + + if (min_frequency_hz < RFM22_MIN_CARRIER_FREQUENCY_HZ) min_frequency_hz = RFM22_MIN_CARRIER_FREQUENCY_HZ; + else + if (min_frequency_hz > RFM22_MAX_CARRIER_FREQUENCY_HZ) min_frequency_hz = RFM22_MAX_CARRIER_FREQUENCY_HZ; + + if (max_frequency_hz < RFM22_MIN_CARRIER_FREQUENCY_HZ) max_frequency_hz = RFM22_MIN_CARRIER_FREQUENCY_HZ; + else + if (max_frequency_hz > RFM22_MAX_CARRIER_FREQUENCY_HZ) max_frequency_hz = RFM22_MAX_CARRIER_FREQUENCY_HZ; + + if (min_frequency_hz > max_frequency_hz) + { // swap them over + uint32_t tmp = min_frequency_hz; + min_frequency_hz = max_frequency_hz; + max_frequency_hz = tmp; + } + + lower_carrier_frequency_limit_Hz = min_frequency_hz; + upper_carrier_frequency_limit_Hz = max_frequency_hz; + + // **************** + // calibrate our RF module to be exactly on frequency .. different for every module + + osc_load_cap = OSC_LOAD_CAP; // default + rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap); + + // **************** + + // disable Low Duty Cycle Mode + rfm22_write(RFM22_op_and_func_ctrl2, 0x00); + + rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); // 1MHz clock output + + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode + // rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode + + // choose the 3 GPIO pin functions + rfm22_write(RFM22_io_port_config, RFM22_io_port_default); // GPIO port use default value + rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch) + rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch) + rfm22_write(RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca); // GPIO2 = Clear Channel Assessment + + // **************** + + return 0; // OK +} + +// ************************************ + +int rfm22_init_scan_spectrum(uint32_t min_frequency_hz, uint32_t max_frequency_hz) +{ +#if defined(RFM22_DEBUG) + DEBUG_PRINTF(2, "\n\rRF init scan spectrum\n\r"); +#endif + + int res = rfm22_resetModule(RX_SCAN_SPECTRUM, min_frequency_hz, max_frequency_hz); + if (res < 0) + return res; + + // rfm22_setSSBandwidth(0); + rfm22_setSSBandwidth(1); + + // FIFO mode, GFSK modulation + uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; + rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); + + rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); // 1MHz clock output + + rfm22_write(RFM22_rssi_threshold_clear_chan_indicator, 0); + + rfm22_write(RFM22_preamble_detection_ctrl1, 31 << 3); // 31-nibbles rx preamble detection + + // avoid packet detection + rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_encrc); + rfm22_write(RFM22_header_control1, 0x0f); + rfm22_write(RFM22_header_control2, 0x77); + + rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); + rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); + rfm22_write(RFM22_sync_word1, SYNC_BYTE_3 ^ 0xff); + rfm22_write(RFM22_sync_word0, SYNC_BYTE_4 ^ 0xff); + + // all the bits to be checked + rfm22_write(RFM22_header_enable3, 0xff); + rfm22_write(RFM22_header_enable2, 0xff); + rfm22_write(RFM22_header_enable1, 0xff); + rfm22_write(RFM22_header_enable0, 0xff); + + // set frequency hopping channel step size (multiples of 10kHz) + // rfm22_write(RFM22_frequency_hopping_step_size, 0); + + // set our nominal carrier frequency + rfm22_setNominalCarrierFrequency(min_frequency_hz); + + // set minimum tx power + rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | 0); + + rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen); + + // rfm22_write(RFM22_vco_current_trimming, 0x7f); + // rfm22_write(RFM22_vco_calibration_override, 0x40); + // rfm22_write(RFM22_chargepump_current_trimming_override, 0x80); + + // Enable RF module external interrupt + rfm22_enableExtInt(); + + rfm22_setRxMode(RX_SCAN_SPECTRUM, true); + + initialized = true; + + return 0; // OK +} + +// ************************************ + +int rfm22_init_tx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz) +{ +#if defined(RFM22_DEBUG) + DEBUG_PRINTF(2, "\n\rRF init TX stream\n\r"); +#endif + + int res = rfm22_resetModule(TX_STREAM_MODE, min_frequency_hz, max_frequency_hz); + if (res < 0) + return res; + + frequency_hop_step_size_reg = 0; + + // set the RF datarate + rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, FALSE); + + // FIFO mode, GFSK modulation + uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; + rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); + + // disable the internal Tx & Rx packet handlers (without CRC) + rfm22_write(RFM22_data_access_control, 0); + + rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble + rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection + + rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header + rfm22_write(RFM22_header_control2, RFM22_header_cntl2_fixpklen | RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_32 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2 used, packet length not included in header (fixed packet length). + + rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word + rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); // + + // rfm22_write(RFM22_modem_test, 0x01); + + rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen); + // rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen); + + rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz) + + rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency + + rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); // set the tx power + // rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | tx_power); // set the tx power + + // rfm22_write(RFM22_vco_current_trimming, 0x7f); + // rfm22_write(RFM22_vco_calibration_override, 0x40); + // rfm22_write(RFM22_chargepump_current_trimming_override, 0x80); + + rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); // TX FIFO Almost Full Threshold (0 - 63) + rfm22_write(RFM22_tx_fifo_control2, TX_FIFO_LO_WATERMARK); // TX FIFO Almost Empty Threshold (0 - 63) + + // Enable RF module external interrupt + rfm22_enableExtInt(); + + initialized = true; + + return 0; // OK +} + +// ************************************ + +int rfm22_init_rx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz) +{ +#if defined(RFM22_DEBUG) + DEBUG_PRINTF(2, "\n\rRF init RX stream\n\r"); +#endif + + int res = rfm22_resetModule(RX_WAIT_PREAMBLE_MODE, min_frequency_hz, max_frequency_hz); + if (res < 0) + return res; + + frequency_hop_step_size_reg = 0; + + // set the RF datarate + rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, FALSE); + + // FIFO mode, GFSK modulation + uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; + rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); + + // disable the internal Tx & Rx packet handlers (without CRC) + rfm22_write(RFM22_data_access_control, 0); + + rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble + rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection + + rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header + rfm22_write(RFM22_header_control2, RFM22_header_cntl2_fixpklen | RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_32 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2 used, packet length not included in header (fixed packet length). + + rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word + rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); // + + // no header bits to be checked + rfm22_write(RFM22_header_enable3, 0x00); + rfm22_write(RFM22_header_enable2, 0x00); + rfm22_write(RFM22_header_enable1, 0x00); + rfm22_write(RFM22_header_enable0, 0x00); + + // rfm22_write(RFM22_modem_test, 0x01); + + rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen); + // rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen); + + rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz) + + rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency + + // rfm22_write(RFM22_vco_current_trimming, 0x7f); + // rfm22_write(RFM22_vco_calibration_override, 0x40); + // rfm22_write(RFM22_chargepump_current_trimming_override, 0x80); + + // RX FIFO Almost Full Threshold (0 - 63) + rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); + + // Enable RF module external interrupt + rfm22_enableExtInt(); + + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + + initialized = true; + + return 0; // OK +} + +// ************************************ +// Initialise this hardware layer module and the rf module + +int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size) +{ + int res = rfm22_resetModule(RX_WAIT_PREAMBLE_MODE, min_frequency_hz, max_frequency_hz); + if (res < 0) + return res; + + // initialize the frequency hopping step size + freq_hop_step_size /= 10000; // in 10kHz increments + if (freq_hop_step_size > 255) freq_hop_step_size = 255; + frequency_hop_step_size_reg = freq_hop_step_size; + + // set the RF datarate + rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, TRUE); + + // FIFO mode, GFSK modulation + uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; + rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); + + // setup to read the internal temperature sensor + + // ADC used to sample the temperature sensor + adc_config = RFM22_ac_adcsel_temp_sensor | RFM22_ac_adcref_bg; + rfm22_write(RFM22_adc_config, adc_config); + + // adc offset + rfm22_write(RFM22_adc_sensor_amp_offset, 0); + + // temp sensor calibration .. –40C to +64C 0.5C resolution + rfm22_write(RFM22_temp_sensor_calib, RFM22_tsc_tsrange0 | RFM22_tsc_entsoffs); + + // temp sensor offset + rfm22_write(RFM22_temp_value_offset, 0); + + // start an ADC conversion + rfm22_write(RFM22_adc_config, adc_config | RFM22_ac_adcstartbusy); + + // set the RSSI threshold interrupt to about -90dBm + rfm22_write(RFM22_rssi_threshold_clear_chan_indicator, (-90 + 122) * 2); + + // enable the internal Tx & Rx packet handlers (without CRC) + rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_enpactx); + + // x-nibbles tx preamble + rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); + // x-nibbles rx preamble detection + rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); + +#ifdef PIOS_RFM22_NO_HEADER + // header control - we are not using the header + rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); + + // no header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header. + rfm22_write(RFM22_header_control2, RFM22_header_cntl2_hdlen_none | + RFM22_header_cntl2_synclen_3210 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); +#else + // header control - using a 4 by header with broadcast of 0xffffffff + rfm22_write(RFM22_header_control1, + RFM22_header_cntl1_bcen_0 | + RFM22_header_cntl1_bcen_1 | + RFM22_header_cntl1_bcen_2 | + RFM22_header_cntl1_bcen_3 | + RFM22_header_cntl1_hdch_0 | + RFM22_header_cntl1_hdch_1 | + RFM22_header_cntl1_hdch_2 | + RFM22_header_cntl1_hdch_3); + // Check all bit of all bytes of the header + rfm22_write(RFM22_header_enable0, 0xff); + rfm22_write(RFM22_header_enable1, 0xff); + rfm22_write(RFM22_header_enable2, 0xff); + rfm22_write(RFM22_header_enable3, 0xff); + // Set the ID to be checked + rfm22_write(RFM22_check_header0, id & 0xff); + rfm22_write(RFM22_check_header1, (id >> 8) & 0xff); + rfm22_write(RFM22_check_header2, (id >> 16) & 0xff); + rfm22_write(RFM22_check_header3, (id >> 24) & 0xff); + // 4 header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header. + rfm22_write(RFM22_header_control2, + RFM22_header_cntl2_hdlen_3210 | + RFM22_header_cntl2_synclen_3210 | + ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); +#endif + + // sync word + rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); + rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); + rfm22_write(RFM22_sync_word1, SYNC_BYTE_3); + rfm22_write(RFM22_sync_word0, SYNC_BYTE_4); + + rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen); + + // set frequency hopping channel step size (multiples of 10kHz) + rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); + + // set our nominal carrier frequency + rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); + + // set the tx power + rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | + RFM22_tx_pwr_lna_sw | tx_power); + + // TX FIFO Almost Full Threshold (0 - 63) + rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); + + // TX FIFO Almost Empty Threshold (0 - 63) + rfm22_write(RFM22_tx_fifo_control2, TX_FIFO_LO_WATERMARK); + + // RX FIFO Almost Full Threshold (0 - 63) + rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); + + // Enable RF module external interrupt + rfm22_enableExtInt(); + + rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + + initialized = true; + + return 0; // ok +} + +// ************************************ + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c index cd4e8a1da..1d4f0a9b2 100644 --- a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c +++ b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c @@ -32,14 +32,15 @@ #include "pios_usb_defs.h" /* struct usb_*, USB_* */ #include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */ #include "pios_usbhook.h" /* PIOS_USBHOOK_Register* */ +#include "pios_usb_hid.h" /* PIOS_USB_HID_Register* */ static const struct usb_device_desc device_desc = { .bLength = sizeof(struct usb_device_desc), .bDescriptorType = USB_DESC_TYPE_DEVICE, .bcdUSB = htousbs(0x0200), - .bDeviceClass = 0x02, - .bDeviceSubClass = 0x00, - .bDeviceProtocol = 0x00, + .bDeviceClass = 0xef, + .bDeviceSubClass = 0x02, + .bDeviceProtocol = 0x01, .bMaxPacketSize0 = 64, /* Must be 64 for high-speed devices */ .idVendor = htousbs(USB_VENDOR_ID_OPENPILOT), .idProduct = htousbs(PIOS_USB_BOARD_PRODUCT_ID), @@ -97,10 +98,6 @@ static const uint8_t hid_report_desc[36] = { struct usb_config_hid_cdc { struct usb_configuration_desc config; struct usb_interface_association_desc iad; - struct usb_interface_desc hid_if; - struct usb_hid_desc hid; - struct usb_endpoint_desc hid_in; - struct usb_endpoint_desc hid_out; struct usb_interface_desc cdc_control_if; struct usb_cdc_header_func_desc cdc_header; struct usb_cdc_callmgmt_func_desc cdc_callmgmt; @@ -110,6 +107,10 @@ struct usb_config_hid_cdc { struct usb_interface_desc cdc_data_if; struct usb_endpoint_desc cdc_in; struct usb_endpoint_desc cdc_out; + struct usb_interface_desc hid_if; + struct usb_hid_desc hid; + struct usb_endpoint_desc hid_in; + struct usb_endpoint_desc hid_out; } __attribute__((packed)); static const struct usb_config_hid_cdc config_hid_cdc = { @@ -128,15 +129,87 @@ static const struct usb_config_hid_cdc config_hid_cdc = { .bDescriptorType = USB_DESC_TYPE_IAD, .bFirstInterface = 0, .bInterfaceCount = 2, - .bFunctionClass = 2, /* Communication */ - .bFunctionSubClass = 2, /* Abstract Control Model */ - .bFunctionProtocol = 0, /* V.25ter, Common AT commands */ + .bFunctionClass = USB_INTERFACE_CLASS_CDC, /* Communication */ + .bFunctionSubClass = USB_CDC_DESC_SUBTYPE_ABSTRACT_CTRL, /* Abstract Control Model */ + .bFunctionProtocol = 1, /* V.25ter, Common AT commands */ .iInterface = 0, }, + .cdc_control_if = { + .bLength = sizeof(struct usb_interface_desc), + .bDescriptorType = USB_DESC_TYPE_INTERFACE, + .bInterfaceNumber = 0, + .bAlternateSetting = 0, + .bNumEndpoints = 1, + .bInterfaceClass = USB_INTERFACE_CLASS_CDC, + .bInterfaceSubClass = USB_CDC_DESC_SUBTYPE_ABSTRACT_CTRL, /* Abstract Control Model */ + .nInterfaceProtocol = 1, /* V.25ter, Common AT commands */ + .iInterface = 0, + }, + .cdc_header = { + .bLength = sizeof(struct usb_cdc_header_func_desc), + .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, + .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_HEADER, + .bcdCDC = htousbs(0x0110), + }, + .cdc_callmgmt = { + .bLength = sizeof(struct usb_cdc_callmgmt_func_desc), + .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, + .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_CALLMGMT, + .bmCapabilities = 0x00, /* No call handling */ + .bDataInterface = 1, + }, + .cdc_acm = { + .bLength = sizeof(struct usb_cdc_acm_func_desc), + .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, + .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_ABSTRACT_CTRL, + .bmCapabilities = 0x00, + }, + .cdc_union = { + .bLength = sizeof(struct usb_cdc_union_func_desc), + .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, + .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_UNION, + .bMasterInterface = 0, + .bSlaveInterface = 1, + }, + .cdc_mgmt_in = { + .bLength = sizeof(struct usb_endpoint_desc), + .bDescriptorType = USB_DESC_TYPE_ENDPOINT, + .bEndpointAddress = USB_EP_IN(2), + .bmAttributes = USB_EP_ATTR_TT_INTERRUPT, + .wMaxPacketSize = htousbs(PIOS_USB_BOARD_CDC_MGMT_LENGTH), + .bInterval = 4, /* ms */ + }, + .cdc_data_if = { + .bLength = sizeof(struct usb_interface_desc), + .bDescriptorType = USB_DESC_TYPE_INTERFACE, + .bInterfaceNumber = 1, + .bAlternateSetting = 0, + .bNumEndpoints = 2, + .bInterfaceClass = USB_INTERFACE_CLASS_DATA, + .bInterfaceSubClass = 0, + .nInterfaceProtocol = 0, /* No class specific protocol */ + .iInterface = 0, + }, + .cdc_in = { + .bLength = sizeof(struct usb_endpoint_desc), + .bDescriptorType = USB_DESC_TYPE_ENDPOINT, + .bEndpointAddress = USB_EP_IN(3), + .bmAttributes = USB_EP_ATTR_TT_BULK, + .wMaxPacketSize = htousbs(PIOS_USB_BOARD_CDC_DATA_LENGTH), + .bInterval = 0, /* ms */ + }, + .cdc_out = { + .bLength = sizeof(struct usb_endpoint_desc), + .bDescriptorType = USB_DESC_TYPE_ENDPOINT, + .bEndpointAddress = USB_EP_OUT(3), + .bmAttributes = USB_EP_ATTR_TT_BULK, /* Bulk */ + .wMaxPacketSize = htousbs(PIOS_USB_BOARD_CDC_DATA_LENGTH), + .bInterval = 0, /* ms */ + }, .hid_if = { .bLength = sizeof(struct usb_interface_desc), .bDescriptorType = USB_DESC_TYPE_INTERFACE, - .bInterfaceNumber = 0, + .bInterfaceNumber = 2, .bAlternateSetting = 0, .bNumEndpoints = 2, .bInterfaceClass = USB_INTERFACE_CLASS_HID, @@ -169,78 +242,6 @@ static const struct usb_config_hid_cdc config_hid_cdc = { .wMaxPacketSize = htousbs(PIOS_USB_BOARD_HID_DATA_LENGTH), .bInterval = 4, /* ms */ }, - .cdc_control_if = { - .bLength = sizeof(struct usb_interface_desc), - .bDescriptorType = USB_DESC_TYPE_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_INTERFACE_CLASS_CDC, - .bInterfaceSubClass = 2, /* Abstract Control Model */ - .nInterfaceProtocol = 1, /* V.25ter, Common AT commands */ - .iInterface = 0, - }, - .cdc_header = { - .bLength = sizeof(struct usb_cdc_header_func_desc), - .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, - .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_HEADER, - .bcdCDC = htousbs(0x0110), - }, - .cdc_callmgmt = { - .bLength = sizeof(struct usb_cdc_callmgmt_func_desc), - .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, - .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_CALLMGMT, - .bmCapabilities = 0x00, /* No call handling */ - .bDataInterface = 2, - }, - .cdc_acm = { - .bLength = sizeof(struct usb_cdc_acm_func_desc), - .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, - .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_ABSTRACT_CTRL, - .bmCapabilities = 0, - }, - .cdc_union = { - .bLength = sizeof(struct usb_cdc_union_func_desc), - .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, - .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_UNION, - .bMasterInterface = 1, - .bSlaveInterface = 2, - }, - .cdc_mgmt_in = { - .bLength = sizeof(struct usb_endpoint_desc), - .bDescriptorType = USB_DESC_TYPE_ENDPOINT, - .bEndpointAddress = USB_EP_IN(2), - .bmAttributes = USB_EP_ATTR_TT_INTERRUPT, - .wMaxPacketSize = htousbs(PIOS_USB_BOARD_CDC_MGMT_LENGTH), - .bInterval = 4, /* ms */ - }, - .cdc_data_if = { - .bLength = sizeof(struct usb_interface_desc), - .bDescriptorType = USB_DESC_TYPE_INTERFACE, - .bInterfaceNumber = 2, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_INTERFACE_CLASS_DATA, - .bInterfaceSubClass = 0, - .nInterfaceProtocol = 0, /* No class specific protocol */ - .iInterface = 0, - }, - .cdc_in = { - .bLength = sizeof(struct usb_endpoint_desc), - .bDescriptorType = USB_DESC_TYPE_ENDPOINT, - .bEndpointAddress = USB_EP_IN(3), - .bmAttributes = USB_EP_ATTR_TT_BULK, - .wMaxPacketSize = htousbs(PIOS_USB_BOARD_CDC_DATA_LENGTH), - .bInterval = 0, /* ms */ - }, - .cdc_out = { - .bLength = sizeof(struct usb_endpoint_desc), - .bDescriptorType = USB_DESC_TYPE_ENDPOINT, - .bEndpointAddress = USB_EP_OUT(3), - .bmAttributes = USB_EP_ATTR_TT_BULK, /* Bulk */ - .wMaxPacketSize = htousbs(PIOS_USB_BOARD_CDC_DATA_LENGTH), - .bInterval = 0, /* ms */ - }, }; int32_t PIOS_USB_DESC_HID_CDC_Init(void) @@ -249,8 +250,8 @@ int32_t PIOS_USB_DESC_HID_CDC_Init(void) PIOS_USBHOOK_RegisterDevice((uint8_t *)&device_desc, sizeof(device_desc)); - PIOS_USBHOOK_RegisterHidInterface((uint8_t *)&(config_hid_cdc.hid_if), sizeof(config_hid_cdc.hid_if)); - PIOS_USBHOOK_RegisterHidReport((uint8_t *)hid_report_desc, sizeof(hid_report_desc)); + PIOS_USB_HID_RegisterHidDescriptor((uint8_t *)&(config_hid_cdc.hid), sizeof(config_hid_cdc.hid)); + PIOS_USB_HID_RegisterHidReport((uint8_t *)hid_report_desc, sizeof(hid_report_desc)); return 0; } diff --git a/flight/PiOS/Common/pios_usb_desc_hid_only.c b/flight/PiOS/Common/pios_usb_desc_hid_only.c index 168efe841..b15a02b32 100644 --- a/flight/PiOS/Common/pios_usb_desc_hid_only.c +++ b/flight/PiOS/Common/pios_usb_desc_hid_only.c @@ -32,6 +32,7 @@ #include "pios_usb_defs.h" /* struct usb_*, USB_* */ #include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */ #include "pios_usbhook.h" /* PIOS_USBHOOK_Register* */ +#include "pios_usb_hid.h" /* PIOS_USB_HID_Register* */ static const struct usb_device_desc device_desc = { .bLength = sizeof(struct usb_device_desc), @@ -75,7 +76,7 @@ static const uint8_t hid_report_desc[36] = { HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT), 0x03, /* Variable, Constant (read-only) */ - /* Host -> Host emulated serial channel */ + /* Host -> Device emulated serial channel */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID), 0x02, /* OpenPilot emulated Serial Channel (Host -> Device) */ HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), @@ -157,8 +158,8 @@ int32_t PIOS_USB_DESC_HID_ONLY_Init(void) PIOS_USBHOOK_RegisterDevice((uint8_t *)&device_desc, sizeof(device_desc)); - PIOS_USBHOOK_RegisterHidInterface((uint8_t *)&(config_hid_only.hid_if), sizeof(config_hid_only.hid_if)); - PIOS_USBHOOK_RegisterHidReport((uint8_t *)hid_report_desc, sizeof(hid_report_desc)); + PIOS_USB_HID_RegisterHidDescriptor((uint8_t *)&(config_hid_only.hid), sizeof(config_hid_only.hid)); + PIOS_USB_HID_RegisterHidReport((uint8_t *)hid_report_desc, sizeof(hid_report_desc)); return 0; } diff --git a/flight/PiOS/Common/pios_usb_util.c b/flight/PiOS/Common/pios_usb_util.c new file mode 100644 index 000000000..6949bd004 --- /dev/null +++ b/flight/PiOS/Common/pios_usb_util.c @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_UTIL USB utility functions + * @brief USB utility functions + * @{ + * + * @file pios_usb_util.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief USB utility functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_util.h" + +uint8_t * PIOS_USB_UTIL_AsciiToUtf8(uint8_t * dst, uint8_t * src, uint16_t srclen) +{ + for (uint8_t i = 0; i < srclen; i++) { + *dst = *src; + dst += 2; + src += 1; + } + + return dst; +} diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld index 777e09aa6..19f70959d 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld @@ -75,6 +75,7 @@ SECTIONS { . = ALIGN(4); KEEP(*(.boardinfo)) + . = ALIGN(ORIGIN(BD_INFO)+LENGTH(BD_INFO)); } > BD_INFO /* Stabs debugging sections. */ diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld index ac579364b..5df4741af 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld @@ -1,5 +1,5 @@ /* This is the size of the stack for all FreeRTOS IRQs */ -_irq_stack_size = 0x1E6; +_irq_stack_size = 0x240; /* This is the size of the stack for early init: life span is until scheduler starts */ _init_stack_size = 0x100; diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_BL_sections.ld index 69eaadb8c..777e09aa6 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_BL_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_BL_sections.ld @@ -3,7 +3,8 @@ PROVIDE ( vPortSVCHandler = 0 ) ; PROVIDE ( xPortPendSVHandler = 0 ) ; PROVIDE ( xPortSysTickHandler = 0 ) ; -_estack = 0x20004FF0; +/* This is the size of the stack for early init and for all FreeRTOS IRQs */ +_irq_stack_size = 0x400; /* Section Definitions */ SECTIONS @@ -49,6 +50,24 @@ SECTIONS _ebss = . ; } > SRAM + /* + * This stack is used both as the initial sp during early init as well as ultimately + * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that + * is used for _all_ interrupt handlers. The end of this stack should be placed + * against the lowest address in RAM so that a stack overrun results in a hard fault + * at the first access beyond the end of the stack. + */ + .irq_stack : + { + . = ALIGN(4); + _irq_stack_end = . ; + . = . + _irq_stack_size ; + . = ALIGN(4); + _irq_stack_top = . - 4 ; + _init_stack_top = _irq_stack_top; + . = ALIGN(4); + } > SRAM + . = ALIGN(4); _end = . ; @@ -56,6 +75,39 @@ SECTIONS { . = ALIGN(4); KEEP(*(.boardinfo)) - . = ALIGN(4); } > BD_INFO + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } } diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_sections.ld index badf5f986..568dddffa 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_sections.ld @@ -1,3 +1,8 @@ +/* This is the size of the stack for all FreeRTOS IRQs */ +_irq_stack_size = 0x1A0; +/* This is the size of the stack for early init: life span is until scheduler starts */ +_init_stack_size = 0x100; + /* Stub out these functions since we don't use them anyway */ PROVIDE ( vPortSVCHandler = 0 ) ; PROVIDE ( xPortPendSVHandler = 0 ) ; @@ -5,8 +10,6 @@ PROVIDE ( xPortSysTickHandler = 0 ) ; PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO)); -_estack = 0x20004FF0; - /* Section Definitions */ SECTIONS { @@ -19,6 +22,16 @@ SECTIONS *(.rodata .rodata* .gnu.linkonce.r.*) } > FLASH + /* module sections */ + .initcallmodule.init : + { + . = ALIGN(4); + __module_initcall_start = .; + KEEP(*(.initcallmodule.init)) + . = ALIGN(4); + __module_initcall_end = .; + } >FLASH + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) @@ -33,6 +46,23 @@ SECTIONS _etext = .; _sidata = .; + /* + * This stack is used both as the initial sp during early init as well as ultimately + * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that + * is used for _all_ interrupt handlers. The end of this stack should be placed + * against the lowest address in RAM so that a stack overrun results in a hard fault + * at the first access beyond the end of the stack. + */ + .irq_stack : + { + . = ALIGN(4); + _irq_stack_end = . ; + . = . + _irq_stack_size ; + . = ALIGN(4); + _irq_stack_top = . - 4 ; + . = ALIGN(4); + } > SRAM + .data : AT (_etext) { _sdata = .; @@ -41,16 +71,81 @@ SECTIONS _edata = . ; } > SRAM + + /* .bss section which is used for uninitialized data */ .bss (NOLOAD) : { _sbss = . ; *(.bss .bss.*) *(COMMON) - . = ALIGN(4); - _ebss = . ; } > SRAM - . = ALIGN(4); - _end = . ; + .heap (NOLOAD) : + { + . = ALIGN(4); + _sheap = . ; + _sheap_pre_rtos = . ; + *(.heap) + . = ALIGN(4); + _eheap = . ; + _eheap_pre_rtos = . ; + _init_stack_end = . ; + _sheap_post_rtos = . ; + . = . + _init_stack_size ; + . = ALIGN(4); + _eheap_post_rtos = . ; + _init_stack_top = . - 4 ; + } > SRAM + + + _free_ram = . ; + .free_ram (NOLOAD) : + { + . = ORIGIN(SRAM) + LENGTH(SRAM) - _free_ram ; + /* This is used by the startup in order to initialize the .bss section */ + _ebss = . ; + _eram = . ; + } > SRAM + + /* keep the heap section at the end of the SRAM + * this will allow to claim the remaining bytes not used + * at run time! (done by the reset vector). + */ + + PROVIDE ( _end = _ebss ) ; + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } } diff --git a/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld deleted file mode 100644 index 3420c385e..000000000 --- a/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld +++ /dev/null @@ -1,385 +0,0 @@ -/** - ****************************************************************************** - * - * @file link_STM3210E_INS_HD_NB.ld - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @brief PiOS linker for the OpenPilot INS board - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* This is the size of the stack for early init and for all FreeRTOS IRQs */ -_irq_stack_size = 0x400; - -/* Check valid alignment for VTOR */ -ASSERT(ORIGIN(BL_FLASH) == ALIGN(ORIGIN(BL_FLASH), 0x80), "Start of memory region flash not aligned for startup vector table"); - -/* -this sends all unreferenced IRQHandlers to reset -*/ - - -PROVIDE ( Undefined_Handler = 0 ) ; -PROVIDE ( SWI_Handler = 0 ) ; -PROVIDE ( IRQ_Handler = 0 ) ; -PROVIDE ( Prefetch_Handler = 0 ) ; -PROVIDE ( Abort_Handler = 0 ) ; -PROVIDE ( FIQ_Handler = 0 ) ; - -PROVIDE ( NMI_Handler = 0 ) ; -PROVIDE ( HardFault_Handler = 0 ) ; -PROVIDE ( MemManage_Handler = 0 ) ; -PROVIDE ( BusFault_Handler = 0 ) ; -PROVIDE ( UsageFault_Handler = 0 ) ; -PROVIDE ( SVC_Handler = 0 ) ; -PROVIDE ( DebugMon_Handler = 0 ) ; -PROVIDE ( PendSV_Handler = 0 ) ; -PROVIDE ( SysTick_Handler = 0 ) ; - -PROVIDE ( WWDG_IRQHandler = 0 ) ; -PROVIDE ( PVD_IRQHandler = 0 ) ; -PROVIDE ( TAMPER_IRQHandler = 0 ) ; -PROVIDE ( RTC_IRQHandler = 0 ) ; -PROVIDE ( FLASH_IRQHandler = 0 ) ; -PROVIDE ( RCC_IRQHandler = 0 ) ; -PROVIDE ( EXTI0_IRQHandler = 0 ) ; -PROVIDE ( EXTI1_IRQHandler = 0 ) ; -PROVIDE ( EXTI2_IRQHandler = 0 ) ; -PROVIDE ( EXTI3_IRQHandler = 0 ) ; -PROVIDE ( EXTI4_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel1_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel2_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel3_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel4_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel5_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel6_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel7_IRQHandler = 0 ) ; -PROVIDE ( ADC_IRQHandler = 0 ) ; -PROVIDE ( USB_HP_CAN1_TX_IRQHandler = 0 ) ; -PROVIDE ( USB_LP_CAN1_RX0_IRQHandler = 0 ) ; -PROVIDE ( CAN1_RX1_IRQHandler = 0 ) ; -PROVIDE ( CAN1_SCE_IRQHandler = 0 ) ; -PROVIDE ( EXTI9_5_IRQHandler = 0 ) ; -PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ; -PROVIDE ( TIM1_UP_IRQHandler = 0 ) ; -PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ; -PROVIDE ( TIM1_CC_IRQHandler = 0 ) ; -PROVIDE ( TIM2_IRQHandler = 0 ) ; -PROVIDE ( TIM3_IRQHandler = 0 ) ; -PROVIDE ( TIM4_IRQHandler = 0 ) ; -PROVIDE ( I2C1_EV_IRQHandler = 0 ) ; -PROVIDE ( I2C1_ER_IRQHandler = 0 ) ; -PROVIDE ( I2C2_EV_IRQHandler = 0 ) ; -PROVIDE ( I2C2_ER_IRQHandler = 0 ) ; -PROVIDE ( SPI1_IRQHandler = 0 ) ; -PROVIDE ( SPI2_IRQHandler = 0 ) ; -PROVIDE ( USART1_IRQHandler = 0 ) ; -PROVIDE ( USART2_IRQHandler = 0 ) ; -PROVIDE ( USART3_IRQHandler = 0 ) ; -PROVIDE ( EXTI15_10_IRQHandler = 0 ) ; -PROVIDE ( RTCAlarm_IRQHandler = 0 ) ; -PROVIDE ( USBWakeUp_IRQHandler = 0 ) ; -PROVIDE ( TIM8_BRK_IRQHandler = 0 ) ; -PROVIDE ( TIM8_UP_IRQHandler = 0 ) ; -PROVIDE ( TIM8_TRG_COM_IRQHandler = 0 ) ; -PROVIDE ( TIM8_CC_IRQHandler = 0 ) ; -PROVIDE ( ADC3_IRQHandler = 0 ) ; -PROVIDE ( FSMC_IRQHandler = 0 ) ; -PROVIDE ( SDIO_IRQHandler = 0 ) ; -PROVIDE ( TIM5_IRQHandler = 0 ) ; -PROVIDE ( SPI3_IRQHandler = 0 ) ; -PROVIDE ( UART4_IRQHandler = 0 ) ; -PROVIDE ( UART5_IRQHandler = 0 ) ; -PROVIDE ( TIM6_IRQHandler = 0 ) ; -PROVIDE ( TIM7_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel1_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel2_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel3_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel4_5_IRQHandler = 0 ) ; - - - -/******************************************************************************/ -/* Peripheral memory map */ -/******************************************************************************/ -/*this allows to compile the ST lib in "non-debug" mode*/ - - -/* Peripheral and SRAM base address in the alias region */ -PERIPH_BB_BASE = 0x42000000; -SRAM_BB_BASE = 0x22000000; - -/* Peripheral and SRAM base address in the bit-band region */ -SRAM_BASE = 0x20000000; -PERIPH_BASE = 0x40000000; - -/* Flash registers base address */ -PROVIDE ( FLASH_BASE = 0x40022000); -/* Flash Option Bytes base address */ -PROVIDE ( OB_BASE = 0x1FFFF800); - -/* Peripheral memory map */ -APB1PERIPH_BASE = PERIPH_BASE ; -APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ; -AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ; - -PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ; -PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ; -PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ; -PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ; -PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ; -PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ; -PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ; -PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ; -PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ; -PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ; -PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ; -PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ; -PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ; -PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ; - -PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ; -PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ; -PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ; -PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ; -PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ; -PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ; -PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ; -PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ; -PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ; -PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ; -PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ; -PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ; - -PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ; -PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ; -PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ; -PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ; -PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ; -PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ; -PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ; -PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ; -PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ; - -/* System Control Space memory map */ -SCS_BASE = 0xE000E000; - -PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ; -PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ; -PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ; - - -/* Sections Definitions */ - -SECTIONS -{ - - /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */ - .isr_vector : - { - PROVIDE (pios_isr_vector_table_base = .); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } > BL_FLASH - - /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */ - .flashtext : - { - . = ALIGN(4); - *(.flashtext) /* Startup code */ - . = ALIGN(4); - } > BL_FLASH - - - /* the program code is stored in the .text section, which goes to Flash */ - .text : - { - . = ALIGN(4); - - *(.text) /* remaining code */ - *(.text.*) /* remaining code */ - *(.rodata) /* read-only data (constants) */ - *(.rodata*) - *(.glue_7) - *(.glue_7t) - - . = ALIGN(4); - _etext = .; - /* This is used by the startup in order to initialize the .data secion */ - _sidata = _etext; - } > BL_FLASH - - - /* - * This stack is used both as the initial sp during early init as well as ultimately - * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that - * is used for _all_ interrupt handlers. The end of this stack should be placed - * against the lowest address in RAM so that a stack overrun results in a hard fault - * at the first access beyond the end of the stack. - */ - .irq_stack : - { - . = ALIGN(4); - _irq_stack_end = . ; - . = . + _irq_stack_size ; - . = ALIGN(4); - _irq_stack_top = . - 4 ; - . = ALIGN(4); - } >RAM - - - /* This is the initialized data section - The program executes knowing that the data is in the RAM - but the loader puts the initial values in the FLASH (inidata). - It is one task of the startup to copy the initial values from FLASH to RAM. */ - .data : AT ( _sidata ) - { - . = ALIGN(4); - /* This is used by the startup in order to initialize the .data secion */ - _sdata = . ; - - *(.data) - *(.data.*) - . = ALIGN(4); - /* This is used by the startup in order to initialize the .data secion */ - _edata = . ; - } >RAM - - - - /* This is the uninitialized data section */ - .bss : - { - . = ALIGN(4); - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; - - *(.bss) - *(COMMON) - - . = ALIGN(4); - /* This is used by the startup in order to initialize the .bss secion */ - _ebss = . ; - } >RAM - - PROVIDE ( end = _ebss ); - PROVIDE ( _end = _ebss ); - - /* this is the FLASH Bank1 */ - /* the C or assembly source must explicitly place the code or data there - using the "section" attribute */ - .b1text : - { - *(.b1text) /* remaining code */ - *(.b1rodata) /* read-only data (constants) */ - *(.b1rodata*) - } >FLASHB1 - - /* this is the EXTMEM */ - /* the C or assembly source must explicitly place the code or data there - using the "section" attribute */ - - /* EXTMEM Bank0 */ - .eb0text : - { - *(.eb0text) /* remaining code */ - *(.eb0rodata) /* read-only data (constants) */ - *(.eb0rodata*) - } >EXTMEMB0 - - /* EXTMEM Bank1 */ - .eb1text : - { - *(.eb1text) /* remaining code */ - *(.eb1rodata) /* read-only data (constants) */ - *(.eb1rodata*) - } >EXTMEMB1 - - /* EXTMEM Bank2 */ - .eb2text : - { - *(.eb2text) /* remaining code */ - *(.eb2rodata) /* read-only data (constants) */ - *(.eb2rodata*) - } >EXTMEMB2 - - /* EXTMEM Bank0 */ - .eb3text : - { - *(.eb3text) /* remaining code */ - *(.eb3rodata) /* read-only data (constants) */ - *(.eb3rodata*) - } >EXTMEMB3 - - __exidx_start = .; - __exidx_end = .; - - .boardinfo : - { - . = ALIGN(4); - KEEP(*(.boardinfo)) - . = ALIGN(4); - } > BD_INFO - - /* after that it's only debugging information. */ - - /* remove the debugging information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } -} - - diff --git a/flight/PiOS/STM32F10x/link_STM3210E_INS_memory.ld b/flight/PiOS/STM32F10x/link_STM3210E_INS_memory.ld deleted file mode 100644 index 7ecb0f65d..000000000 --- a/flight/PiOS/STM32F10x/link_STM3210E_INS_memory.ld +++ /dev/null @@ -1,13 +0,0 @@ -/* Memory Spaces Definitions */ -MEMORY -{ - RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 0x10000 - BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x05000 - 0x00080 - BD_INFO (r) : ORIGIN = 0x08005000 - 0x80, LENGTH = 0x00080 - FLASH (rx) : ORIGIN = 0x08005000, LENGTH = 0x80000 - 0x05000 - FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0 -} diff --git a/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld deleted file mode 100644 index bcf498dd0..000000000 --- a/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld +++ /dev/null @@ -1,379 +0,0 @@ -/** - ****************************************************************************** - * - * @file link_STM3210E_INS_HD_NB.ld - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @brief PiOS linker for the OpenPilot INS board - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* This is the size of the stack for early init and for all FreeRTOS IRQs */ -_irq_stack_size = 0x400; - -/* Check valid alignment for VTOR */ -ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region flash not aligned for startup vector table"); - -/* -this sends all unreferenced IRQHandlers to reset -*/ - - -PROVIDE ( Undefined_Handler = 0 ) ; -PROVIDE ( SWI_Handler = 0 ) ; -PROVIDE ( IRQ_Handler = 0 ) ; -PROVIDE ( Prefetch_Handler = 0 ) ; -PROVIDE ( Abort_Handler = 0 ) ; -PROVIDE ( FIQ_Handler = 0 ) ; - -PROVIDE ( NMI_Handler = 0 ) ; -PROVIDE ( HardFault_Handler = 0 ) ; -PROVIDE ( MemManage_Handler = 0 ) ; -PROVIDE ( BusFault_Handler = 0 ) ; -PROVIDE ( UsageFault_Handler = 0 ) ; -PROVIDE ( vPortSVCHandler = 0 ) ; -PROVIDE ( DebugMon_Handler = 0 ) ; -PROVIDE ( xPortPendSVHandler = 0 ) ; -PROVIDE ( xPortSysTickHandler = 0 ) ; - -PROVIDE ( WWDG_IRQHandler = 0 ) ; -PROVIDE ( PVD_IRQHandler = 0 ) ; -PROVIDE ( TAMPER_IRQHandler = 0 ) ; -PROVIDE ( RTC_IRQHandler = 0 ) ; -PROVIDE ( FLASH_IRQHandler = 0 ) ; -PROVIDE ( RCC_IRQHandler = 0 ) ; -PROVIDE ( EXTI0_IRQHandler = 0 ) ; -PROVIDE ( EXTI1_IRQHandler = 0 ) ; -PROVIDE ( EXTI2_IRQHandler = 0 ) ; -PROVIDE ( EXTI3_IRQHandler = 0 ) ; -PROVIDE ( EXTI4_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel1_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel2_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel3_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel4_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel5_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel6_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel7_IRQHandler = 0 ) ; -PROVIDE ( ADC_IRQHandler = 0 ) ; -PROVIDE ( USB_HP_CAN1_TX_IRQHandler = 0 ) ; -PROVIDE ( USB_LP_CAN1_RX0_IRQHandler = 0 ) ; -PROVIDE ( CAN1_RX1_IRQHandler = 0 ) ; -PROVIDE ( CAN1_SCE_IRQHandler = 0 ) ; -PROVIDE ( EXTI9_5_IRQHandler = 0 ) ; -PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ; -PROVIDE ( TIM1_UP_IRQHandler = 0 ) ; -PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ; -PROVIDE ( TIM1_CC_IRQHandler = 0 ) ; -PROVIDE ( TIM2_IRQHandler = 0 ) ; -PROVIDE ( TIM3_IRQHandler = 0 ) ; -PROVIDE ( TIM4_IRQHandler = 0 ) ; -PROVIDE ( I2C1_EV_IRQHandler = 0 ) ; -PROVIDE ( I2C1_ER_IRQHandler = 0 ) ; -PROVIDE ( I2C2_EV_IRQHandler = 0 ) ; -PROVIDE ( I2C2_ER_IRQHandler = 0 ) ; -PROVIDE ( SPI1_IRQHandler = 0 ) ; -PROVIDE ( SPI2_IRQHandler = 0 ) ; -PROVIDE ( USART1_IRQHandler = 0 ) ; -PROVIDE ( USART2_IRQHandler = 0 ) ; -PROVIDE ( USART3_IRQHandler = 0 ) ; -PROVIDE ( EXTI15_10_IRQHandler = 0 ) ; -PROVIDE ( RTCAlarm_IRQHandler = 0 ) ; -PROVIDE ( USBWakeUp_IRQHandler = 0 ) ; -PROVIDE ( TIM8_BRK_IRQHandler = 0 ) ; -PROVIDE ( TIM8_UP_IRQHandler = 0 ) ; -PROVIDE ( TIM8_TRG_COM_IRQHandler = 0 ) ; -PROVIDE ( TIM8_CC_IRQHandler = 0 ) ; -PROVIDE ( ADC3_IRQHandler = 0 ) ; -PROVIDE ( FSMC_IRQHandler = 0 ) ; -PROVIDE ( SDIO_IRQHandler = 0 ) ; -PROVIDE ( TIM5_IRQHandler = 0 ) ; -PROVIDE ( SPI3_IRQHandler = 0 ) ; -PROVIDE ( UART4_IRQHandler = 0 ) ; -PROVIDE ( UART5_IRQHandler = 0 ) ; -PROVIDE ( TIM6_IRQHandler = 0 ) ; -PROVIDE ( TIM7_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel1_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel2_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel3_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel4_5_IRQHandler = 0 ) ; - - - -/******************************************************************************/ -/* Peripheral memory map */ -/******************************************************************************/ -/*this allows to compile the ST lib in "non-debug" mode*/ - - -/* Peripheral and SRAM base address in the alias region */ -PERIPH_BB_BASE = 0x42000000; -SRAM_BB_BASE = 0x22000000; - -/* Peripheral and SRAM base address in the bit-band region */ -SRAM_BASE = 0x20000000; -PERIPH_BASE = 0x40000000; - -/* Flash registers base address */ -PROVIDE ( FLASH_BASE = 0x40022000); -/* Flash Option Bytes base address */ -PROVIDE ( OB_BASE = 0x1FFFF800); - -/* Peripheral memory map */ -APB1PERIPH_BASE = PERIPH_BASE ; -APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ; -AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ; - -PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ; -PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ; -PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ; -PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ; -PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ; -PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ; -PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ; -PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ; -PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ; -PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ; -PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ; -PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ; -PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ; -PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ; - -PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ; -PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ; -PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ; -PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ; -PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ; -PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ; -PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ; -PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ; -PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ; -PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ; -PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ; -PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ; - -PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ; -PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ; -PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ; -PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ; -PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ; -PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ; -PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ; -PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ; -PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ; - -/* System Control Space memory map */ -SCS_BASE = 0xE000E000; - -PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ; -PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ; -PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ; - -PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO)); - -/* Sections Definitions */ - -SECTIONS -{ - /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */ - .isr_vector : - { - PROVIDE (pios_isr_vector_table_base = .); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } > FLASH - - /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */ - .flashtext : - { - . = ALIGN(4); - *(.flashtext) /* Startup code */ - . = ALIGN(4); - } > FLASH - - - /* the program code is stored in the .text section, which goes to Flash */ - .text : - { - . = ALIGN(4); - - *(.text) /* remaining code */ - *(.text.*) /* remaining code */ - *(.rodata) /* read-only data (constants) */ - *(.rodata*) - *(.glue_7) - *(.glue_7t) - - . = ALIGN(4); - _etext = .; - /* This is used by the startup in order to initialize the .data secion */ - _sidata = _etext; - } > FLASH - - - /* - * This stack is used both as the initial sp during early init as well as ultimately - * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that - * is used for _all_ interrupt handlers. The end of this stack should be placed - * against the lowest address in RAM so that a stack overrun results in a hard fault - * at the first access beyond the end of the stack. - */ - .irq_stack : - { - . = ALIGN(4); - _irq_stack_end = . ; - . = . + _irq_stack_size ; - . = ALIGN(4); - _irq_stack_top = . - 4 ; - _init_stack_top = _irq_stack_top; - . = ALIGN(4); - } >RAM - - - /* This is the initialized data section - The program executes knowing that the data is in the RAM - but the loader puts the initial values in the FLASH (inidata). - It is one task of the startup to copy the initial values from FLASH to RAM. */ - .data : AT ( _sidata ) - { - . = ALIGN(4); - /* This is used by the startup in order to initialize the .data secion */ - _sdata = . ; - - *(.data) - *(.data.*) - . = ALIGN(4); - /* This is used by the startup in order to initialize the .data secion */ - _edata = . ; - } >RAM - - - - /* This is the uninitialized data section */ - .bss : - { - . = ALIGN(4); - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; - - *(.bss) - *(COMMON) - - . = ALIGN(4); - /* This is used by the startup in order to initialize the .bss secion */ - _ebss = . ; - } >RAM - - PROVIDE ( end = _ebss ); - PROVIDE ( _end = _ebss ); - - /* this is the FLASH Bank1 */ - /* the C or assembly source must explicitly place the code or data there - using the "section" attribute */ - .b1text : - { - *(.b1text) /* remaining code */ - *(.b1rodata) /* read-only data (constants) */ - *(.b1rodata*) - } >FLASHB1 - - /* this is the EXTMEM */ - /* the C or assembly source must explicitly place the code or data there - using the "section" attribute */ - - /* EXTMEM Bank0 */ - .eb0text : - { - *(.eb0text) /* remaining code */ - *(.eb0rodata) /* read-only data (constants) */ - *(.eb0rodata*) - } >EXTMEMB0 - - /* EXTMEM Bank1 */ - .eb1text : - { - *(.eb1text) /* remaining code */ - *(.eb1rodata) /* read-only data (constants) */ - *(.eb1rodata*) - } >EXTMEMB1 - - /* EXTMEM Bank2 */ - .eb2text : - { - *(.eb2text) /* remaining code */ - *(.eb2rodata) /* read-only data (constants) */ - *(.eb2rodata*) - } >EXTMEMB2 - - /* EXTMEM Bank0 */ - .eb3text : - { - *(.eb3text) /* remaining code */ - *(.eb3rodata) /* read-only data (constants) */ - *(.eb3rodata*) - } >EXTMEMB3 - - __exidx_start = .; - __exidx_end = .; - - /* after that it's only debugging information. */ - - /* remove the debugging information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } -} - - diff --git a/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld index 9cd7c8b4b..c7414707d 100644 --- a/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld @@ -1,5 +1,5 @@ /* This is the size of the stack for early init and for all FreeRTOS IRQs */ -_irq_stack_size = 0x400; +_irq_stack_size = 0x800; /* Check valid alignment for VTOR */ ASSERT(ORIGIN(BL_FLASH) == ALIGN(ORIGIN(BL_FLASH), 0x80), "Start of memory region flash not aligned for startup vector table"); diff --git a/flight/PiOS/STM32F10x/pios_adc.c b/flight/PiOS/STM32F10x/pios_adc.c index e8fbe3a85..66eb8f92e 100644 --- a/flight/PiOS/STM32F10x/pios_adc.c +++ b/flight/PiOS/STM32F10x/pios_adc.c @@ -7,8 +7,7 @@ * @{ * * @file pios_adc.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief Analog to Digital converstion routines * @see The GNU Public License (GPL) Version 3 *****************************************************************************/ @@ -31,8 +30,38 @@ #include "pios.h" #include +// Private types + +enum pios_adc_dev_magic { + PIOS_ADC_DEV_MAGIC = 0x58375124, +}; + +struct pios_adc_dev { + const struct pios_adc_cfg * cfg; + ADCCallback callback_function; +#if defined(PIOS_INCLUDE_FREERTOS) + xQueueHandle data_queue; +#endif + volatile int16_t *valid_data_buffer; + volatile uint8_t adc_oversample; + uint8_t dma_block_size; + uint16_t dma_half_buffer_size; +#if defined(PIOS_INCLUDE_ADC) + int16_t fir_coeffs[PIOS_ADC_MAX_SAMPLES+1] __attribute__ ((aligned(4))); + volatile int16_t raw_data_buffer[PIOS_ADC_MAX_SAMPLES] __attribute__ ((aligned(4))); // Double buffer that DMA just used + float downsampled_buffer[PIOS_ADC_NUM_CHANNELS] __attribute__ ((aligned(4))); +#endif + enum pios_adc_dev_magic magic; +}; + +#if defined(PIOS_INCLUDE_FREERTOS) +struct pios_adc_dev * pios_adc_dev; +#endif + // Private functions void PIOS_ADC_downsample_data(); +static struct pios_adc_dev * PIOS_ADC_Allocate(); +static bool PIOS_ADC_validate(struct pios_adc_dev *); /* Local Variables */ static GPIO_TypeDef *ADC_GPIO_PORT[PIOS_ADC_NUM_PINS] = PIOS_ADC_PORTS; @@ -42,15 +71,43 @@ static const uint32_t ADC_CHANNEL[PIOS_ADC_NUM_PINS] = PIOS_ADC_CHANNELS; static ADC_TypeDef *ADC_MAPPING[PIOS_ADC_NUM_PINS] = PIOS_ADC_MAPPING; static const uint32_t ADC_CHANNEL_MAPPING[PIOS_ADC_NUM_PINS] = PIOS_ADC_CHANNEL_MAPPING; +static bool PIOS_ADC_validate(struct pios_adc_dev * dev) +{ + if (dev == NULL) + return false; + + return (dev->magic == PIOS_ADC_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_adc_dev * PIOS_ADC_Allocate() +{ + struct pios_adc_dev * adc_dev; + + adc_dev = (struct pios_adc_dev *)pvPortMalloc(sizeof(*adc_dev)); + if (!adc_dev) return (NULL); + + adc_dev->magic = PIOS_ADC_DEV_MAGIC; + return(adc_dev); +} +#else +#error Not implemented +#endif + /** * @brief Initialise the ADC Peripheral, configure to run at the max oversampling */ -void PIOS_ADC_Init() -{ - pios_adc_devs[0].callback_function = NULL; +int32_t PIOS_ADC_Init(const struct pios_adc_cfg * cfg) +{ + pios_adc_dev = PIOS_ADC_Allocate(); + if (pios_adc_dev == NULL) + return -1; + + pios_adc_dev->cfg = cfg; + pios_adc_dev->callback_function = NULL; #if defined(PIOS_INCLUDE_FREERTOS) - pios_adc_devs[0].data_queue = NULL; + pios_adc_dev->data_queue = NULL; #endif /* Setup analog pins */ @@ -66,6 +123,8 @@ void PIOS_ADC_Init() } PIOS_ADC_Config(PIOS_ADC_MAX_OVERSAMPLING); + + return 0; } /** @@ -74,13 +133,13 @@ void PIOS_ADC_Init() */ void PIOS_ADC_Config(uint32_t oversampling) { - pios_adc_devs[0].adc_oversample = (oversampling > PIOS_ADC_MAX_OVERSAMPLING) ? PIOS_ADC_MAX_OVERSAMPLING : oversampling; + pios_adc_dev->adc_oversample = (oversampling > PIOS_ADC_MAX_OVERSAMPLING) ? PIOS_ADC_MAX_OVERSAMPLING : oversampling; ADC_DeInit(ADC1); ADC_DeInit(ADC2); /* Disable interrupts */ - DMA_ITConfig(pios_adc_devs[0].cfg->dma.rx.channel, pios_adc_devs[0].cfg->dma.irq.flags, DISABLE); + DMA_ITConfig(pios_adc_dev->cfg->dma.rx.channel, pios_adc_dev->cfg->dma.irq.flags, DISABLE); /* Enable ADC clocks */ PIOS_ADC_CLOCK_FUNCTION; @@ -139,34 +198,34 @@ void PIOS_ADC_Config(uint32_t oversampling) #endif /* This makes sure we have an even number of transfers if using ADC2 */ - pios_adc_devs[0].dma_block_size = ((PIOS_ADC_NUM_CHANNELS + PIOS_ADC_USE_ADC2) >> PIOS_ADC_USE_ADC2) << PIOS_ADC_USE_ADC2; - pios_adc_devs[0].dma_half_buffer_size = pios_adc_devs[0].dma_block_size * pios_adc_devs[0].adc_oversample; + pios_adc_dev->dma_block_size = ((PIOS_ADC_NUM_CHANNELS + PIOS_ADC_USE_ADC2) >> PIOS_ADC_USE_ADC2) << PIOS_ADC_USE_ADC2; + pios_adc_dev->dma_half_buffer_size = pios_adc_dev->dma_block_size * pios_adc_dev->adc_oversample; /* Configure DMA channel */ - DMA_InitTypeDef dma_init = pios_adc_devs[0].cfg->dma.rx.init; - dma_init.DMA_MemoryBaseAddr = (uint32_t) &pios_adc_devs[0].raw_data_buffer[0]; + DMA_InitTypeDef dma_init = pios_adc_dev->cfg->dma.rx.init; + dma_init.DMA_MemoryBaseAddr = (uint32_t) &pios_adc_dev->raw_data_buffer[0]; dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; - dma_init.DMA_BufferSize = pios_adc_devs[0].dma_half_buffer_size; /* x2 for double buffer /2 for 32-bit xfr */ - DMA_Init(pios_adc_devs[0].cfg->dma.rx.channel, &dma_init); - DMA_Cmd(pios_adc_devs[0].cfg->dma.rx.channel, ENABLE); + dma_init.DMA_BufferSize = pios_adc_dev->dma_half_buffer_size; /* x2 for double buffer /2 for 32-bit xfr */ + DMA_Init(pios_adc_dev->cfg->dma.rx.channel, &dma_init); + DMA_Cmd(pios_adc_dev->cfg->dma.rx.channel, ENABLE); /* Trigger interrupt when for half conversions too to indicate double buffer */ - DMA_ITConfig(pios_adc_devs[0].cfg->dma.rx.channel, DMA_IT_TC, ENABLE); - DMA_ITConfig(pios_adc_devs[0].cfg->dma.rx.channel, DMA_IT_HT, ENABLE); + DMA_ITConfig(pios_adc_dev->cfg->dma.rx.channel, DMA_IT_TC, ENABLE); + DMA_ITConfig(pios_adc_dev->cfg->dma.rx.channel, DMA_IT_HT, ENABLE); /* Configure DMA interrupt */ - NVIC_Init(&pios_adc_devs[0].cfg->dma.irq.init); + NVIC_Init(&pios_adc_dev->cfg->dma.irq.init); /* Finally start initial conversion */ ADC_SoftwareStartConvCmd(ADC1, ENABLE); /* Use simple averaging filter for now */ - for (int32_t i = 0; i < pios_adc_devs[0].adc_oversample; i++) - pios_adc_devs[0].fir_coeffs[i] = 1; - pios_adc_devs[0].fir_coeffs[pios_adc_devs[0].adc_oversample] = pios_adc_devs[0].adc_oversample; + for (int32_t i = 0; i < pios_adc_dev->adc_oversample; i++) + pios_adc_dev->fir_coeffs[i] = 1; + pios_adc_dev->fir_coeffs[pios_adc_dev->adc_oversample] = pios_adc_dev->adc_oversample; /* Enable DMA1 clock */ - RCC_AHBPeriphClockCmd(pios_adc_devs[0].cfg->dma.ahb_clk, ENABLE); + RCC_AHBPeriphClockCmd(pios_adc_dev->cfg->dma.ahb_clk, ENABLE); } /** @@ -183,7 +242,7 @@ int32_t PIOS_ADC_PinGet(uint32_t pin) } /* Return last conversion result */ - return pios_adc_devs[0].downsampled_buffer[pin]; + return pios_adc_dev->downsampled_buffer[pin]; } /** @@ -192,7 +251,7 @@ int32_t PIOS_ADC_PinGet(uint32_t pin) */ void PIOS_ADC_SetCallback(ADCCallback new_function) { - pios_adc_devs[0].callback_function = new_function; + pios_adc_dev->callback_function = new_function; } #if defined(PIOS_INCLUDE_FREERTOS) @@ -201,7 +260,7 @@ void PIOS_ADC_SetCallback(ADCCallback new_function) */ void PIOS_ADC_SetQueue(xQueueHandle data_queue) { - pios_adc_devs[0].data_queue = data_queue; + pios_adc_dev->data_queue = data_queue; } #endif @@ -210,7 +269,7 @@ void PIOS_ADC_SetQueue(xQueueHandle data_queue) */ float * PIOS_ADC_GetBuffer(void) { - return pios_adc_devs[0].downsampled_buffer; + return pios_adc_dev->downsampled_buffer; } /** @@ -218,7 +277,7 @@ float * PIOS_ADC_GetBuffer(void) */ int16_t * PIOS_ADC_GetRawBuffer(void) { - return (int16_t *) pios_adc_devs[0].valid_data_buffer; + return (int16_t *) pios_adc_dev->valid_data_buffer; } /** @@ -226,7 +285,7 @@ int16_t * PIOS_ADC_GetRawBuffer(void) */ uint8_t PIOS_ADC_GetOverSampling(void) { - return pios_adc_devs[0].adc_oversample; + return pios_adc_dev->adc_oversample; } /** @@ -239,8 +298,8 @@ uint8_t PIOS_ADC_GetOverSampling(void) void PIOS_ADC_SetFIRCoefficients(float * new_filter) { // Less than or equal to get normalization constant - for(int i = 0; i <= pios_adc_devs[0].adc_oversample; i++) - pios_adc_devs[0].fir_coeffs[i] = new_filter[i]; + for(int i = 0; i <= pios_adc_dev->adc_oversample; i++) + pios_adc_dev->fir_coeffs[i] = new_filter[i]; } /** @@ -251,25 +310,25 @@ void PIOS_ADC_downsample_data() { uint16_t chan; uint16_t sample; - float * downsampled_buffer = &pios_adc_devs[0].downsampled_buffer[0]; + float * downsampled_buffer = &pios_adc_dev->downsampled_buffer[0]; for (chan = 0; chan < PIOS_ADC_NUM_CHANNELS; chan++) { int32_t sum = 0; - for (sample = 0; sample < pios_adc_devs[0].adc_oversample; sample++) { - sum += pios_adc_devs[0].valid_data_buffer[chan + sample * pios_adc_devs[0].dma_block_size] * pios_adc_devs[0].fir_coeffs[sample]; + for (sample = 0; sample < pios_adc_dev->adc_oversample; sample++) { + sum += pios_adc_dev->valid_data_buffer[chan + sample * pios_adc_dev->dma_block_size] * pios_adc_dev->fir_coeffs[sample]; } - downsampled_buffer[chan] = (float) sum / pios_adc_devs[0].fir_coeffs[pios_adc_devs[0].adc_oversample]; + downsampled_buffer[chan] = (float) sum / pios_adc_dev->fir_coeffs[pios_adc_dev->adc_oversample]; } #if defined(PIOS_INCLUDE_FREERTOS) - if(pios_adc_devs[0].data_queue) { + if(pios_adc_dev->data_queue) { static portBASE_TYPE xHigherPriorityTaskWoken; - xQueueSendFromISR(pios_adc_devs[0].data_queue, pios_adc_devs[0].downsampled_buffer, &xHigherPriorityTaskWoken); + xQueueSendFromISR(pios_adc_dev->data_queue, pios_adc_dev->downsampled_buffer, &xHigherPriorityTaskWoken); portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); } #endif - if(pios_adc_devs[0].callback_function) - pios_adc_devs[0].callback_function(pios_adc_devs[0].downsampled_buffer); + if(pios_adc_dev->callback_function) + pios_adc_dev->callback_function(pios_adc_dev->downsampled_buffer); } /** @@ -283,19 +342,22 @@ void PIOS_ADC_downsample_data() */ void PIOS_ADC_DMA_Handler(void) { - if (DMA_GetFlagStatus(pios_adc_devs[0].cfg->full_flag /*DMA1_IT_TC1*/)) { // whole double buffer filled - pios_adc_devs[0].valid_data_buffer = &pios_adc_devs[0].raw_data_buffer[pios_adc_devs[0].dma_half_buffer_size]; - DMA_ClearFlag(pios_adc_devs[0].cfg->full_flag); + if (!PIOS_ADC_validate(pios_adc_dev)) + return; + + if (DMA_GetFlagStatus(pios_adc_dev->cfg->full_flag /*DMA1_IT_TC1*/)) { // whole double buffer filled + pios_adc_dev->valid_data_buffer = &pios_adc_dev->raw_data_buffer[pios_adc_dev->dma_half_buffer_size]; + DMA_ClearFlag(pios_adc_dev->cfg->full_flag); PIOS_ADC_downsample_data(); } - else if (DMA_GetFlagStatus(pios_adc_devs[0].cfg->half_flag /*DMA1_IT_HT1*/)) { - pios_adc_devs[0].valid_data_buffer = &pios_adc_devs[0].raw_data_buffer[0]; - DMA_ClearFlag(pios_adc_devs[0].cfg->half_flag); + else if (DMA_GetFlagStatus(pios_adc_dev->cfg->half_flag /*DMA1_IT_HT1*/)) { + pios_adc_dev->valid_data_buffer = &pios_adc_dev->raw_data_buffer[0]; + DMA_ClearFlag(pios_adc_dev->cfg->half_flag); PIOS_ADC_downsample_data(); } else { // This should not happen, probably due to transfer errors - DMA_ClearFlag(pios_adc_devs[0].cfg->dma.irq.flags /*DMA1_FLAG_GL1*/); + DMA_ClearFlag(pios_adc_dev->cfg->dma.irq.flags /*DMA1_FLAG_GL1*/); } } diff --git a/flight/PiOS/Common/pios_bl_helper.c b/flight/PiOS/STM32F10x/pios_bl_helper.c similarity index 100% rename from flight/PiOS/Common/pios_bl_helper.c rename to flight/PiOS/STM32F10x/pios_bl_helper.c diff --git a/flight/PiOS/STM32F10x/pios_delay.c b/flight/PiOS/STM32F10x/pios_delay.c index c4e74717b..7c04e2426 100644 --- a/flight/PiOS/STM32F10x/pios_delay.c +++ b/flight/PiOS/STM32F10x/pios_delay.c @@ -148,6 +148,25 @@ uint32_t PIOS_DELAY_GetuSSince(uint32_t t) return (PIOS_DELAY_GetuS() - t); } +/** + * @brief Get the raw delay timer, useful for timing + * @return Unitless value (uint32 wrap around) + */ +uint32_t PIOS_DELAY_GetRaw() +{ + return DWT_CYCCNT; +} + +/** + * @brief Compare to raw times to and convert to us + * @return A microsecond value + */ +uint32_t PIOS_DELAY_DiffuS(uint32_t raw) +{ + uint32_t diff = DWT_CYCCNT - raw; + return diff / us_ticks; +} + #endif /** diff --git a/flight/PiOS/STM32F10x/pios_eeprom.c b/flight/PiOS/STM32F10x/pios_eeprom.c new file mode 100644 index 000000000..f604f417b --- /dev/null +++ b/flight/PiOS/STM32F10x/pios_eeprom.c @@ -0,0 +1,155 @@ +/** +****************************************************************************** +* @addtogroup PIOS PIOS Core hardware abstraction layer +* @{ +* @addtogroup PIOS_EEPROM EEPROM reading/writing functions +* @brief PIOS EEPROM reading/writing functions +* @{ +* +* @file pios_eeprom.c +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief COM layer functions +* @see The GNU Public License (GPL) Version 3 +* +*****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include +#include +#include +#include + +#include + +static struct pios_eeprom_cfg config; + +/** + * Initialize the flash eeprom device + * \param cfg The configuration structure. + */ +void PIOS_EEPROM_Init(const struct pios_eeprom_cfg *cfg) +{ + config = *cfg; +} + +/** + * Save a block of data to the flash eeprom device. + * \param data A pointer to the data to write. + * \param len The length of data to write. + * \return 0 on sucess + */ +int32_t PIOS_EEPROM_Save(uint8_t *data, uint32_t len) +{ + + // We need to write 32 bit words, so extend the length to be an even multiple of 4 bytes, + // and include 4 bytes for the 32 bit CRC. + uint32_t nwords = (len / 4) + 1 + (len % 4 ? 1 : 0); + uint32_t size = nwords * 4; + + // Ensure that the length is not longer than the max size. + if (size > config.max_size) + return -1; + + // Calculate a 32 bit CRC of the data. + uint32_t crc = PIOS_CRC32_updateCRC(0xffffffff, data, len); + + // Unlock the Flash Program Erase controller + FLASH_Unlock(); + + // See if we have to write the data. + if ((memcmp(data, (uint8_t*)config.base_address, len) == 0) && + (memcmp((uint8_t*)&crc, (uint8_t*)config.base_address + size - 4, 4) == 0)) + return 0; + + // TODO: Check that the area isn't already erased + + // Erase page + FLASH_Status fs = FLASH_ErasePage(config.base_address); + if (fs != FLASH_COMPLETE) + { // error + FLASH_Lock(); + return -2; + } + + // write 4 bytes at a time into program flash area (emulated EEPROM area) + uint8_t *p1 = data; + uint32_t *p3 = (uint32_t *)config.base_address; + for (int32_t i = 0; i < size; p3++) + { + uint32_t value = 0; + + if (i == (size - 4)) + { + // write the CRC. + value = crc; + i += 4; + } + else + { + if (i < len) value |= (uint32_t)*p1++ << 0; else value |= 0x000000ff; i++; + if (i < len) value |= (uint32_t)*p1++ << 8; else value |= 0x0000ff00; i++; + if (i < len) value |= (uint32_t)*p1++ << 16; else value |= 0x00ff0000; i++; + if (i < len) value |= (uint32_t)*p1++ << 24; else value |= 0xff000000; i++; + } + + // write a 32-bit value + fs = FLASH_ProgramWord((uint32_t)p3, value); + if (fs != FLASH_COMPLETE) + { + FLASH_Lock(); + return -3; + } + } + + // Lock the Flash Program Erase controller + FLASH_Lock(); + + return 0; +} + +/** + * Reads a block of data from the flash eeprom device. + * \param data A pointer to the output data buffer. + * \param len The length of data to read. + * \return 0 on sucess + */ +int32_t PIOS_EEPROM_Load(uint8_t *data, uint32_t len) +{ + + // We need to write 32 bit words, so the length should have been extended + // to an even multiple of 4 bytes, and should include 4 bytes for the 32 bit CRC. + uint32_t nwords = (len / 4) + 1 + (len % 4 ? 1 : 0); + uint32_t size = nwords * 4; + + // Ensure that the length is not longer than the max size. + if (size > config.max_size) + return -1; + + // Read the data from flash. + memcpy(data, (uint8_t*)config.base_address, len); + + // Read the CRC. + uint32_t crc_flash = *((uint32_t*)(config.base_address + size - 4)); + + // Calculate a 32 bit CRC of the data. + uint32_t crc = PIOS_CRC32_updateCRC(0xffffffff, data, len); + if(crc != crc_flash) + return -2; + + return 0; +} diff --git a/flight/PiOS/STM32F10x/pios_exti.c b/flight/PiOS/STM32F10x/pios_exti.c index 8b1d2dc32..65a651f6f 100644 --- a/flight/PiOS/STM32F10x/pios_exti.c +++ b/flight/PiOS/STM32F10x/pios_exti.c @@ -224,7 +224,7 @@ static void PIOS_EXTI_15_10_irq_handler (void) } void EXTI15_10_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_15_10_irq_handler"))); -#endif +#endif /* PIOS_INCLUDE_EXTI */ /** * @} diff --git a/flight/PiOS/STM32F10x/pios_i2c.c b/flight/PiOS/STM32F10x/pios_i2c.c index e1bdb44f8..d7252916c 100644 --- a/flight/PiOS/STM32F10x/pios_i2c.c +++ b/flight/PiOS/STM32F10x/pios_i2c.c @@ -911,7 +911,13 @@ out_fail: return(-1); } -bool PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns) +/** + * @brief Perform a series of I2C transactions + * @returns 0 if success or error code + * @retval -1 for failed transaction + * @retval -2 for failure to get semaphore + */ +int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns) { struct pios_i2c_adapter * i2c_adapter = (struct pios_i2c_adapter *)i2c_id; @@ -928,6 +934,17 @@ bool PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], ui portTickType timeout; timeout = i2c_adapter->cfg->transfer_timeout_ms / portTICK_RATE_MS; semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_busy, timeout) == pdTRUE); +#else + uint32_t timeout = 0xfff; + while(i2c_adapter->busy && --timeout); + if(timeout == 0) //timed out + return false; + + PIOS_IRQ_Disable(); + if(i2c_adapter->busy) + return false; + i2c_adapter->busy = 1; + PIOS_IRQ_Enable(); #endif /* USE_FREERTOS */ PIOS_DEBUG_Assert(i2c_adapter->curr_state == I2C_STATE_STOPPED); @@ -948,6 +965,10 @@ bool PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], ui #ifdef USE_FREERTOS semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE); xSemaphoreGive(i2c_adapter->sem_ready); +#else + PIOS_IRQ_Disable(); + i2c_adapter->busy = 0; + PIOS_IRQ_Enable(); #endif /* USE_FREERTOS */ /* Spin waiting for the transfer to finish */ @@ -966,7 +987,9 @@ bool PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], ui i2c_timeout_counter++; #endif /* USE_FREERTOS */ - return (!i2c_adapter->bus_error) && semaphore_success; + return !semaphore_success ? -2 : + i2c_adapter->bus_error ? -1 : + 0; } diff --git a/flight/PiOS/Common/pios_iap.c b/flight/PiOS/STM32F10x/pios_iap.c similarity index 100% rename from flight/PiOS/Common/pios_iap.c rename to flight/PiOS/STM32F10x/pios_iap.c diff --git a/flight/PiOS/STM32F10x/pios_led.c b/flight/PiOS/STM32F10x/pios_led.c index 5db5cc884..30c6f1296 100644 --- a/flight/PiOS/STM32F10x/pios_led.c +++ b/flight/PiOS/STM32F10x/pios_led.c @@ -7,7 +7,7 @@ * @{ * * @file pios_led.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief LED functions, init, toggle, on & off. * @see The GNU Public License (GPL) Version 3 * @@ -59,7 +59,7 @@ int32_t PIOS_LED_Init(const struct pios_led_cfg * cfg) RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); break; case (uint32_t) GPIOC: - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); break; default: PIOS_Assert(0); diff --git a/flight/PiOS/STM32F10x/pios_spi.c b/flight/PiOS/STM32F10x/pios_spi.c index a47e27d83..f8b2f0e63 100644 --- a/flight/PiOS/STM32F10x/pios_spi.c +++ b/flight/PiOS/STM32F10x/pios_spi.c @@ -1,523 +1,585 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_SPI SPI Functions - * @brief PIOS interface to read and write from SPI ports - * @{ - * - * @file pios_spi.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Hardware Abstraction Layer for SPI ports of STM32 - * @see The GNU Public License (GPL) Version 3 - * @notes - * - * Note that additional chip select lines can be easily added by using - * the remaining free GPIOs of the core module. Shared SPI ports should be - * arbitrated with (FreeRTOS based) Mutexes to avoid collisions! - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include - -#if defined(PIOS_INCLUDE_SPI) - -#include - -static bool PIOS_SPI_validate(struct pios_spi_dev * com_dev) -{ - /* Should check device magic here */ - return(true); -} - -#if defined(PIOS_INCLUDE_FREERTOS) -static struct pios_spi_dev * PIOS_SPI_alloc(void) -{ - return (pvPortMalloc(sizeof(struct pios_spi_dev))); -} -#else -static struct pios_spi_dev pios_spi_devs[PIOS_SPI_MAX_DEVS]; -static uint8_t pios_spi_num_devs; -static struct pios_spi_dev * PIOS_SPI_alloc(void) -{ - if (pios_spi_num_devs >= PIOS_SPI_MAX_DEVS) { - return (NULL); - } - - return (&pios_spi_devs[pios_spi_num_devs++]); -} -#endif - -/** -* Initialises SPI pins -* \param[in] mode currently only mode 0 supported -* \return < 0 if initialisation failed -*/ -int32_t PIOS_SPI_Init(uint32_t * spi_id, const struct pios_spi_cfg * cfg) -{ - PIOS_Assert(spi_id); - PIOS_Assert(cfg); - - struct pios_spi_dev * spi_dev; - - spi_dev = (struct pios_spi_dev *) PIOS_SPI_alloc(); - if (!spi_dev) goto out_fail; - - /* Bind the configuration to the device instance */ - spi_dev->cfg = cfg; - -#if defined(PIOS_INCLUDE_FREERTOS) - vSemaphoreCreateBinary(spi_dev->busy); - xSemaphoreGive(spi_dev->busy); -#endif - - /* Disable callback function */ - spi_dev->callback = NULL; - - /* Set rx/tx dummy bytes to a known value */ - spi_dev->rx_dummy_byte = 0xFF; - spi_dev->tx_dummy_byte = 0xFF; - - switch (spi_dev->cfg->init.SPI_NSS) { - case SPI_NSS_Soft: - if (spi_dev->cfg->init.SPI_Mode == SPI_Mode_Master) { - /* We're a master in soft NSS mode, make sure we see NSS high at all times. */ - SPI_NSSInternalSoftwareConfig(spi_dev->cfg->regs, SPI_NSSInternalSoft_Set); - /* Since we're driving the SSEL pin in software, ensure that the slave is deselected */ - GPIO_SetBits(spi_dev->cfg->ssel.gpio, spi_dev->cfg->ssel.init.GPIO_Pin); - GPIO_Init(spi_dev->cfg->ssel.gpio, &(spi_dev->cfg->ssel.init)); - } else { - /* We're a slave in soft NSS mode, make sure we see NSS low at all times. */ - SPI_NSSInternalSoftwareConfig(spi_dev->cfg->regs, SPI_NSSInternalSoft_Reset); - } - break; - case SPI_NSS_Hard: - /* FIXME: Should this also call SPI_SSOutputCmd()? */ - GPIO_Init(spi_dev->cfg->ssel.gpio, &(spi_dev->cfg->ssel.init)); - break; - default: - PIOS_Assert(0); - } - - /* Initialize the GPIO pins */ - GPIO_Init(spi_dev->cfg->sclk.gpio, &(spi_dev->cfg->sclk.init)); - GPIO_Init(spi_dev->cfg->mosi.gpio, &(spi_dev->cfg->mosi.init)); - GPIO_Init(spi_dev->cfg->miso.gpio, &(spi_dev->cfg->miso.init)); - - /* Enable the associated peripheral clock */ - switch ((uint32_t) spi_dev->cfg->regs) { - case (uint32_t) SPI1: - /* Enable SPI peripheral clock (APB2 == high speed) */ - RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE); - break; - case (uint32_t) SPI2: - /* Enable SPI peripheral clock (APB1 == slow speed) */ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE); - break; - case (uint32_t) SPI3: - /* Enable SPI peripheral clock (APB1 == slow speed) */ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE); - break; - } - - /* Enable DMA clock */ - RCC_AHBPeriphClockCmd(spi_dev->cfg->dma.ahb_clk, ENABLE); - - /* Configure DMA for SPI Rx */ - DMA_Cmd(spi_dev->cfg->dma.rx.channel, DISABLE); - DMA_Init(spi_dev->cfg->dma.rx.channel, &(spi_dev->cfg->dma.rx.init)); - - /* Configure DMA for SPI Tx */ - DMA_Cmd(spi_dev->cfg->dma.tx.channel, DISABLE); - DMA_Init(spi_dev->cfg->dma.tx.channel, &(spi_dev->cfg->dma.tx.init)); - - /* Initialize the SPI block */ - SPI_Init(spi_dev->cfg->regs, &(spi_dev->cfg->init)); - - /* Configure CRC calculation */ - if (spi_dev->cfg->use_crc) { - SPI_CalculateCRC(spi_dev->cfg->regs, ENABLE); - } else { - SPI_CalculateCRC(spi_dev->cfg->regs, DISABLE); - } - - /* Enable SPI */ - SPI_Cmd(spi_dev->cfg->regs, ENABLE); - - /* Enable SPI interrupts to DMA */ - SPI_I2S_DMACmd(spi_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); - - /* Configure DMA interrupt */ - NVIC_Init(&(spi_dev->cfg->dma.irq.init)); - - *spi_id = (uint32_t)spi_dev; - return(0); - -out_fail: - return(-1); -} - -/** -* (Re-)initialises SPI peripheral clock rate -* -* \param[in] spi SPI number (0 or 1) -* \param[in] spi_prescaler configures the SPI speed: -*
    -*
  • PIOS_SPI_PRESCALER_2: sets clock rate 27.7~ nS @ 72 MHz (36 MBit/s) (only supported for spi==0, spi1 uses 4 instead) -*
  • PIOS_SPI_PRESCALER_4: sets clock rate 55.5~ nS @ 72 MHz (18 MBit/s) -*
  • PIOS_SPI_PRESCALER_8: sets clock rate 111.1~ nS @ 72 MHz (9 MBit/s) -*
  • PIOS_SPI_PRESCALER_16: sets clock rate 222.2~ nS @ 72 MHz (4.5 MBit/s) -*
  • PIOS_SPI_PRESCALER_32: sets clock rate 444.4~ nS @ 72 MHz (2.25 MBit/s) -*
  • PIOS_SPI_PRESCALER_64: sets clock rate 888.8~ nS @ 72 MHz (1.125 MBit/s) -*
  • PIOS_SPI_PRESCALER_128: sets clock rate 1.7~ nS @ 72 MHz (0.562 MBit/s) -*
  • PIOS_SPI_PRESCALER_256: sets clock rate 3.5~ nS @ 72 MHz (0.281 MBit/s) -*
-* \return 0 if no error -* \return -1 if disabled SPI port selected -* \return -3 if invalid spi_prescaler selected -*/ -int32_t PIOS_SPI_SetClockSpeed(uint32_t spi_id, SPIPrescalerTypeDef spi_prescaler) -{ - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - - bool valid = PIOS_SPI_validate(spi_dev); - PIOS_Assert(valid) - - SPI_InitTypeDef SPI_InitStructure; - - if (spi_prescaler >= 8) { - /* Invalid prescaler selected */ - return -3; - } - - /* Start with a copy of the default configuration for the peripheral */ - SPI_InitStructure = spi_dev->cfg->init; - - /* Adjust the prescaler for the peripheral's clock */ - SPI_InitStructure.SPI_BaudRatePrescaler = ((uint16_t) spi_prescaler & 7) << 3; - - /* Write back the new configuration */ - SPI_Init(spi_dev->cfg->regs, &SPI_InitStructure); - - PIOS_SPI_TransferByte(spi_id, 0xFF); - return 0; -} - -/** - * Claim the SPI bus semaphore. Calling the SPI functions does not require this - * \param[in] spi SPI number (0 or 1) - * \return 0 if no error - * \return -1 if timeout before claiming semaphore - */ -int32_t PIOS_SPI_ClaimBus(uint32_t spi_id) -{ -#if defined(PIOS_INCLUDE_FREERTOS) - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - - bool valid = PIOS_SPI_validate(spi_dev); - PIOS_Assert(valid) - - if (xSemaphoreTake(spi_dev->busy, 0xffff) != pdTRUE) - return -1; -#endif - return 0; -} - -/** - * Release the SPI bus semaphore. Calling the SPI functions does not require this - * \param[in] spi SPI number (0 or 1) - * \return 0 if no error - */ -int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) -{ -#if defined(PIOS_INCLUDE_FREERTOS) - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - - bool valid = PIOS_SPI_validate(spi_dev); - PIOS_Assert(valid) - - xSemaphoreGive(spi_dev->busy); -#endif - return 0; -} - -/** -* Controls the RC (Register Clock alias Chip Select) pin of a SPI port -* \param[in] spi SPI number (0 or 1) -* \param[in] pin_value 0 or 1 -* \return 0 if no error -*/ -int32_t PIOS_SPI_RC_PinSet(uint32_t spi_id, uint8_t pin_value) -{ - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - - bool valid = PIOS_SPI_validate(spi_dev); - PIOS_Assert(valid) - - if (pin_value) { - GPIO_SetBits(spi_dev->cfg->ssel.gpio, spi_dev->cfg->ssel.init.GPIO_Pin); - } else { - GPIO_ResetBits(spi_dev->cfg->ssel.gpio, spi_dev->cfg->ssel.init.GPIO_Pin); - } - - return 0; -} - -/** -* Transfers a byte to SPI output and reads back the return value from SPI input -* \param[in] spi SPI number (0 or 1) -* \param[in] b the byte which should be transfered -*/ -int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b) -{ - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - - bool valid = PIOS_SPI_validate(spi_dev); - PIOS_Assert(valid) - - uint8_t dummy; - uint8_t rx_byte; - - /* - * Procedure taken from STM32F10xxx Reference Manual section 23.3.5 - */ - - /* Make sure the RXNE flag is cleared by reading the DR register */ - dummy = spi_dev->cfg->regs->DR; - - /* Start the transfer */ - spi_dev->cfg->regs->DR = b; - - /* Wait until there is a byte to read */ - while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_RXNE)) ; - - /* Read the rx'd byte */ - rx_byte = spi_dev->cfg->regs->DR; - - /* Wait until the TXE goes high */ - while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_TXE)) ; - - /* Wait for SPI transfer to have fully completed */ - while (spi_dev->cfg->regs->SR & SPI_I2S_FLAG_BSY) ; - - /* Return received byte */ - return rx_byte; -} - -/** -* Transfers a block of bytes via DMA. -* \param[in] spi SPI number (0 or 1) -* \param[in] send_buffer pointer to buffer which should be sent.
-* If NULL, 0xff (all-one) will be sent. -* \param[in] receive_buffer pointer to buffer which should get the received values.
-* If NULL, received bytes will be discarded. -* \param[in] len number of bytes which should be transfered -* \param[in] callback pointer to callback function which will be executed -* from DMA channel interrupt once the transfer is finished. -* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will -* block until the transfer is finished. -* \return >= 0 if no error during transfer -* \return -1 if disabled SPI port selected -* \return -3 if function has been called during an ongoing DMA transfer -*/ -int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback) -{ - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - - bool valid = PIOS_SPI_validate(spi_dev); - PIOS_Assert(valid) - - DMA_InitTypeDef dma_init; - - /* Exit if ongoing transfer */ - if (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)) { - return -3; - } - - /* Disable the SPI peripheral */ - SPI_Cmd(spi_dev->cfg->regs, DISABLE); - - /* Disable the DMA channels */ - DMA_Cmd(spi_dev->cfg->dma.rx.channel, DISABLE); - DMA_Cmd(spi_dev->cfg->dma.tx.channel, DISABLE); - - /* Set callback function */ - spi_dev->callback = callback; - - /* - * Configure Rx channel - */ - - /* Start with the default configuration for this peripheral */ - dma_init = spi_dev->cfg->dma.rx.init; - - if (receive_buffer != NULL) { - /* Enable memory addr. increment - bytes written into receive buffer */ - dma_init.DMA_MemoryBaseAddr = (uint32_t) receive_buffer; - dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; - } else { - /* Disable memory addr. increment - bytes written into dummy buffer */ - spi_dev->rx_dummy_byte = 0xFF; - dma_init.DMA_MemoryBaseAddr = (uint32_t) &spi_dev->rx_dummy_byte; - dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable; - } - if (spi_dev->cfg->use_crc) { - /* Make sure the CRC error flag is cleared before we start */ - SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR); - } - - dma_init.DMA_BufferSize = len; - DMA_Init(spi_dev->cfg->dma.rx.channel, &(dma_init)); - - /* - * Configure Tx channel - */ - - /* Start with the default configuration for this peripheral */ - dma_init = spi_dev->cfg->dma.tx.init; - - if (send_buffer != NULL) { - /* Enable memory addr. increment - bytes written into receive buffer */ - dma_init.DMA_MemoryBaseAddr = (uint32_t) send_buffer; - dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; - } else { - /* Disable memory addr. increment - bytes written into dummy buffer */ - spi_dev->tx_dummy_byte = 0xFF; - dma_init.DMA_MemoryBaseAddr = (uint32_t) &spi_dev->tx_dummy_byte; - dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable; - } - - if (spi_dev->cfg->use_crc) { - /* The last byte of the payload will be replaced with the CRC8 */ - dma_init.DMA_BufferSize = len - 1; - } else { - dma_init.DMA_BufferSize = len; - } - - DMA_Init(spi_dev->cfg->dma.tx.channel, &(dma_init)); - - /* Enable DMA interrupt if callback function active */ - DMA_ITConfig(spi_dev->cfg->dma.rx.channel, DMA_IT_TC, (callback != NULL) ? ENABLE : DISABLE); - - /* Flush out the CRC registers */ - SPI_CalculateCRC(spi_dev->cfg->regs, DISABLE); - (void)SPI_GetCRC(spi_dev->cfg->regs, SPI_CRC_Rx); - SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR); - - /* Make sure to flush out the receive buffer */ - (void)SPI_I2S_ReceiveData(spi_dev->cfg->regs); - - if (spi_dev->cfg->use_crc) { - /* Need a 0->1 transition to reset the CRC logic */ - SPI_CalculateCRC(spi_dev->cfg->regs, ENABLE); - } - - /* Start DMA transfers */ - DMA_Cmd(spi_dev->cfg->dma.rx.channel, ENABLE); - DMA_Cmd(spi_dev->cfg->dma.tx.channel, ENABLE); - - /* Reenable the SPI device */ - SPI_Cmd(spi_dev->cfg->regs, ENABLE); - - if (callback) { - /* User has requested a callback, don't wait for the transfer to complete. */ - return 0; - } - - /* Wait until all bytes have been transmitted/received */ - while (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)); - - /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ - while (!(SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE))); - - /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ - while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)); - - /* Check the CRC on the transfer if enabled. */ - if (spi_dev->cfg->use_crc) { - /* Check the SPI CRC error flag */ - if (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_FLAG_CRCERR)) { - return -4; - } - } - - /* No error */ - return 0; -} - -/** -* Check if a transfer is in progress -* \param[in] spi SPI number (0 or 1) -* \return >= 0 if no transfer is in progress -* \return -1 if disabled SPI port selected -* \return -2 if unsupported SPI port selected -* \return -3 if function has been called during an ongoing DMA transfer -*/ -int32_t PIOS_SPI_Busy(uint32_t spi_id) -{ - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - - bool valid = PIOS_SPI_validate(spi_dev); - PIOS_Assert(valid) - - /* DMA buffer has data or SPI transmit register not empty or SPI is busy*/ - if (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel) || - !SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE) || - SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)) - { - return -3; - } - - return(0); -} - - -void PIOS_SPI_IRQ_Handler(uint32_t spi_id) -{ - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - - bool valid = PIOS_SPI_validate(spi_dev); - PIOS_Assert(valid) - - DMA_ClearFlag(spi_dev->cfg->dma.irq.flags); - - /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ - while (!(SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE))) ; - - /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ - while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)) ; - - if (spi_dev->callback != NULL) { - bool crc_ok = TRUE; - uint8_t crc_val; - - if (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_FLAG_CRCERR)) { - crc_ok = FALSE; - SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR); - } - crc_val = SPI_GetCRC(spi_dev->cfg->regs, SPI_CRC_Rx); - spi_dev->callback(crc_ok, crc_val); - } -} - -#endif - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_SPI SPI Functions + * @brief PIOS interface to read and write from SPI ports + * @{ + * + * @file pios_spi.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Hardware Abstraction Layer for SPI ports of STM32 + * @see The GNU Public License (GPL) Version 3 + * @notes + * + * Note that additional chip select lines can be easily added by using + * the remaining free GPIOs of the core module. Shared SPI ports should be + * arbitrated with (FreeRTOS based) Mutexes to avoid collisions! + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include + +#if defined(PIOS_INCLUDE_SPI) + +#include + +static bool PIOS_SPI_validate(struct pios_spi_dev * com_dev) +{ + /* Should check device magic here */ + return(true); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_spi_dev * PIOS_SPI_alloc(void) +{ + return (pvPortMalloc(sizeof(struct pios_spi_dev))); +} +#else +static struct pios_spi_dev pios_spi_devs[PIOS_SPI_MAX_DEVS]; +static uint8_t pios_spi_num_devs; +static struct pios_spi_dev * PIOS_SPI_alloc(void) +{ + if (pios_spi_num_devs >= PIOS_SPI_MAX_DEVS) { + return (NULL); + } + + return (&pios_spi_devs[pios_spi_num_devs++]); +} +#endif + +/** +* Initialises SPI pins +* \param[in] mode currently only mode 0 supported +* \return < 0 if initialisation failed + */ +int32_t PIOS_SPI_Init(uint32_t * spi_id, const struct pios_spi_cfg * cfg) +{ + uint32_t init_ssel = 0; + + PIOS_Assert(spi_id); + PIOS_Assert(cfg); + + struct pios_spi_dev * spi_dev; + + spi_dev = (struct pios_spi_dev *) PIOS_SPI_alloc(); + if (!spi_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + spi_dev->cfg = cfg; + +#if defined(PIOS_INCLUDE_FREERTOS) + vSemaphoreCreateBinary(spi_dev->busy); + xSemaphoreGive(spi_dev->busy); +#else + spi_dev->busy = 0; +#endif + + /* Disable callback function */ + spi_dev->callback = NULL; + + /* Set rx/tx dummy bytes to a known value */ + spi_dev->rx_dummy_byte = 0xFF; + spi_dev->tx_dummy_byte = 0xFF; + + switch (spi_dev->cfg->init.SPI_NSS) { + case SPI_NSS_Soft: + if (spi_dev->cfg->init.SPI_Mode == SPI_Mode_Master) { + /* We're a master in soft NSS mode, make sure we see NSS high at all times. */ + SPI_NSSInternalSoftwareConfig(spi_dev->cfg->regs, SPI_NSSInternalSoft_Set); + /* Init as many slave selects as the config advertises. */ + init_ssel = spi_dev->cfg->slave_count; + } else { + /* We're a slave in soft NSS mode, make sure we see NSS low at all times. */ + SPI_NSSInternalSoftwareConfig(spi_dev->cfg->regs, SPI_NSSInternalSoft_Reset); + } + break; + case SPI_NSS_Hard: + /* only legal for single-slave config */ + PIOS_Assert(spi_dev->cfg->slave_count == 1); + init_ssel = 1; + /* FIXME: Should this also call SPI_SSOutputCmd()? */ + break; + + default: + PIOS_Assert(0); + } + + /* Initialize the GPIO pins */ + GPIO_Init(spi_dev->cfg->sclk.gpio, &(spi_dev->cfg->sclk.init)); + GPIO_Init(spi_dev->cfg->mosi.gpio, &(spi_dev->cfg->mosi.init)); + GPIO_Init(spi_dev->cfg->miso.gpio, &(spi_dev->cfg->miso.init)); + for (uint32_t i = 0; i < init_ssel; i++) { + /* Since we're driving the SSEL pin in software, ensure that the slave is deselected */ + /* XXX multi-slave support - maybe have another SPI_NSS_ mode? */ + GPIO_SetBits(spi_dev->cfg->ssel[i].gpio, spi_dev->cfg->ssel[i].init.GPIO_Pin); + GPIO_Init(spi_dev->cfg->ssel[i].gpio, (GPIO_InitTypeDef*)&(spi_dev->cfg->ssel[i].init)); + } + + /* Enable the associated peripheral clock */ + switch ((uint32_t) spi_dev->cfg->regs) { + case (uint32_t) SPI1: + /* Enable SPI peripheral clock (APB2 == high speed) */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE); + break; + case (uint32_t) SPI2: + /* Enable SPI peripheral clock (APB1 == slow speed) */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE); + break; + case (uint32_t) SPI3: + /* Enable SPI peripheral clock (APB1 == slow speed) */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE); + break; + } + + /* Enable DMA clock */ + RCC_AHBPeriphClockCmd(spi_dev->cfg->dma.ahb_clk, ENABLE); + + /* Configure DMA for SPI Rx */ + DMA_Cmd(spi_dev->cfg->dma.rx.channel, DISABLE); + DMA_Init(spi_dev->cfg->dma.rx.channel, &(spi_dev->cfg->dma.rx.init)); + + /* Configure DMA for SPI Tx */ + DMA_Cmd(spi_dev->cfg->dma.tx.channel, DISABLE); + DMA_Init(spi_dev->cfg->dma.tx.channel, &(spi_dev->cfg->dma.tx.init)); + + /* Initialize the SPI block */ + SPI_Init(spi_dev->cfg->regs, &(spi_dev->cfg->init)); + + /* Configure CRC calculation */ + if (spi_dev->cfg->use_crc) { + SPI_CalculateCRC(spi_dev->cfg->regs, ENABLE); + } else { + SPI_CalculateCRC(spi_dev->cfg->regs, DISABLE); + } + + /* Enable SPI */ + SPI_Cmd(spi_dev->cfg->regs, ENABLE); + + /* Enable SPI interrupts to DMA */ + SPI_I2S_DMACmd(spi_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); + + /* Configure DMA interrupt */ + NVIC_Init(&(spi_dev->cfg->dma.irq.init)); + + *spi_id = (uint32_t)spi_dev; + return(0); + +out_fail: + return(-1); +} + +/** +* (Re-)initialises SPI peripheral clock rate +* +* \param[in] spi SPI number (0 or 1) +* \param[in] spi_prescaler configures the SPI speed: +*
    +*
  • PIOS_SPI_PRESCALER_2: sets clock rate 27.7~ nS @ 72 MHz (36 MBit/s) (only supported for spi==0, spi1 uses 4 instead) +*
  • PIOS_SPI_PRESCALER_4: sets clock rate 55.5~ nS @ 72 MHz (18 MBit/s) +*
  • PIOS_SPI_PRESCALER_8: sets clock rate 111.1~ nS @ 72 MHz (9 MBit/s) +*
  • PIOS_SPI_PRESCALER_16: sets clock rate 222.2~ nS @ 72 MHz (4.5 MBit/s) +*
  • PIOS_SPI_PRESCALER_32: sets clock rate 444.4~ nS @ 72 MHz (2.25 MBit/s) +*
  • PIOS_SPI_PRESCALER_64: sets clock rate 888.8~ nS @ 72 MHz (1.125 MBit/s) +*
  • PIOS_SPI_PRESCALER_128: sets clock rate 1.7~ nS @ 72 MHz (0.562 MBit/s) +*
  • PIOS_SPI_PRESCALER_256: sets clock rate 3.5~ nS @ 72 MHz (0.281 MBit/s) +*
+* \return 0 if no error +* \return -1 if disabled SPI port selected +* \return -3 if invalid spi_prescaler selected +*/ +int32_t PIOS_SPI_SetClockSpeed(uint32_t spi_id, SPIPrescalerTypeDef spi_prescaler) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + SPI_InitTypeDef SPI_InitStructure; + + if (spi_prescaler >= 8) { + /* Invalid prescaler selected */ + return -3; + } + + /* Start with a copy of the default configuration for the peripheral */ + SPI_InitStructure = spi_dev->cfg->init; + + /* Adjust the prescaler for the peripheral's clock */ + SPI_InitStructure.SPI_BaudRatePrescaler = ((uint16_t) spi_prescaler & 7) << 3; + + /* Write back the new configuration */ + SPI_Init(spi_dev->cfg->regs, &SPI_InitStructure); + + PIOS_SPI_TransferByte(spi_id, 0xFF); + return 0; +} + +/** + * Claim the SPI bus semaphore. Calling the SPI functions does not require this + * \param[in] spi SPI number (0 or 1) + * \return 0 if no error + * \return -1 if timeout before claiming semaphore + */ +int32_t PIOS_SPI_ClaimBus(uint32_t spi_id) +{ +#if defined(PIOS_INCLUDE_FREERTOS) + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + if (xSemaphoreTake(spi_dev->busy, 0xffff) != pdTRUE) + return -1; +#else + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + uint32_t timeout = 0xffff; + while((PIOS_SPI_Busy(spi_id) || spi_dev->busy) && --timeout); + if(timeout == 0) //timed out + return -1; + + PIOS_IRQ_Disable(); + if(spi_dev->busy) + return -1; + spi_dev->busy = 1; + PIOS_IRQ_Enable(); +#endif + return 0; +} + +/** + * Claim the SPI bus semaphore from an ISR. Has no timeout. + * \param[in] spi SPI number (0 or 1) + * \return 0 if no error + * \return -1 if timeout before claiming semaphore + */ +int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id) +{ +#if defined(PIOS_INCLUDE_FREERTOS) + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + if (xQueueGenericReceive(( xQueueHandle ) spi_dev->busy, NULL, 0x0000 , pdFALSE ) != pdTRUE) + return -1; +#endif + return 0; +} + +/** + * Release the SPI bus semaphore. Calling the SPI functions does not require this + * \param[in] spi SPI number (0 or 1) + * \return 0 if no error + */ +int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) +{ +#if defined(PIOS_INCLUDE_FREERTOS) + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + xSemaphoreGive(spi_dev->busy); +#else + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + PIOS_IRQ_Disable(); + spi_dev->busy = 0; + PIOS_IRQ_Enable(); + +#endif + return 0; +} + +/** + * Controls the RC (Register Clock alias Chip Select) pin of a SPI port + * \param[in] spi SPI number (0 or 1) + * \param[in] pin_value 0 or 1 + * \return 0 if no error + */ +int32_t PIOS_SPI_RC_PinSet(uint32_t spi_id, uint32_t slave_id, uint8_t pin_value) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + PIOS_Assert(slave_id <= spi_dev->cfg->slave_count) + + /* XXX multi-slave support? */ + if (pin_value) { + GPIO_SetBits(spi_dev->cfg->ssel[slave_id].gpio, spi_dev->cfg->ssel[slave_id].init.GPIO_Pin); + } else { + GPIO_ResetBits(spi_dev->cfg->ssel[slave_id].gpio, spi_dev->cfg->ssel[slave_id].init.GPIO_Pin); + } + + return 0; +} + +/** +* Transfers a byte to SPI output and reads back the return value from SPI input +* \param[in] spi SPI number (0 or 1) +* \param[in] b the byte which should be transfered +*/ +static uint8_t dummy; +int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + uint8_t rx_byte; + + /* + * Procedure taken from STM32F10xxx Reference Manual section 23.3.5 + */ + + /* Make sure the RXNE flag is cleared by reading the DR register */ + dummy = spi_dev->cfg->regs->DR; + + /* Start the transfer */ + spi_dev->cfg->regs->DR = b; + + /* Wait until there is a byte to read */ + while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_RXNE)) ; + + /* Read the rx'd byte */ + rx_byte = spi_dev->cfg->regs->DR; + + /* Wait until the TXE goes high */ + while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_TXE)) ; + + /* Wait for SPI transfer to have fully completed */ + while (spi_dev->cfg->regs->SR & SPI_I2S_FLAG_BSY) ; + + /* Return received byte */ + return rx_byte; +} + +/** +* Transfers a block of bytes via DMA. +* \param[in] spi SPI number (0 or 1) +* \param[in] send_buffer pointer to buffer which should be sent.
+* If NULL, 0xff (all-one) will be sent. +* \param[in] receive_buffer pointer to buffer which should get the received values.
+* If NULL, received bytes will be discarded. +* \param[in] len number of bytes which should be transfered +* \param[in] callback pointer to callback function which will be executed +* from DMA channel interrupt once the transfer is finished. +* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will +* block until the transfer is finished. +* \return >= 0 if no error during transfer +* \return -1 if disabled SPI port selected +* \return -3 if function has been called during an ongoing DMA transfer +*/ +int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + DMA_InitTypeDef dma_init; + + /* Exit if ongoing transfer */ + if (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)) { + return -3; + } + + /* Disable the SPI peripheral */ + SPI_Cmd(spi_dev->cfg->regs, DISABLE); + + /* Disable the DMA channels */ + DMA_Cmd(spi_dev->cfg->dma.rx.channel, DISABLE); + DMA_Cmd(spi_dev->cfg->dma.tx.channel, DISABLE); + + /* Set callback function */ + spi_dev->callback = callback; + + /* + * Configure Rx channel + */ + + /* Start with the default configuration for this peripheral */ + dma_init = spi_dev->cfg->dma.rx.init; + + if (receive_buffer != NULL) { + /* Enable memory addr. increment - bytes written into receive buffer */ + dma_init.DMA_MemoryBaseAddr = (uint32_t) receive_buffer; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; + } else { + /* Disable memory addr. increment - bytes written into dummy buffer */ + spi_dev->rx_dummy_byte = 0xFF; + dma_init.DMA_MemoryBaseAddr = (uint32_t) &spi_dev->rx_dummy_byte; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable; + } + if (spi_dev->cfg->use_crc) { + /* Make sure the CRC error flag is cleared before we start */ + SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR); + } + + dma_init.DMA_BufferSize = len; + DMA_Init(spi_dev->cfg->dma.rx.channel, &(dma_init)); + + /* + * Configure Tx channel + */ + + /* Start with the default configuration for this peripheral */ + dma_init = spi_dev->cfg->dma.tx.init; + + if (send_buffer != NULL) { + /* Enable memory addr. increment - bytes written into receive buffer */ + dma_init.DMA_MemoryBaseAddr = (uint32_t) send_buffer; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; + } else { + /* Disable memory addr. increment - bytes written into dummy buffer */ + spi_dev->tx_dummy_byte = 0xFF; + dma_init.DMA_MemoryBaseAddr = (uint32_t) &spi_dev->tx_dummy_byte; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable; + } + + if (spi_dev->cfg->use_crc) { + /* The last byte of the payload will be replaced with the CRC8 */ + dma_init.DMA_BufferSize = len - 1; + } else { + dma_init.DMA_BufferSize = len; + } + + DMA_Init(spi_dev->cfg->dma.tx.channel, &(dma_init)); + + /* Enable DMA interrupt if callback function active */ + DMA_ITConfig(spi_dev->cfg->dma.rx.channel, DMA_IT_TC, (callback != NULL) ? ENABLE : DISABLE); + + /* Flush out the CRC registers */ + SPI_CalculateCRC(spi_dev->cfg->regs, DISABLE); + (void)SPI_GetCRC(spi_dev->cfg->regs, SPI_CRC_Rx); + SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR); + + /* Make sure to flush out the receive buffer */ + (void)SPI_I2S_ReceiveData(spi_dev->cfg->regs); + + if (spi_dev->cfg->use_crc) { + /* Need a 0->1 transition to reset the CRC logic */ + SPI_CalculateCRC(spi_dev->cfg->regs, ENABLE); + } + + /* Start DMA transfers */ + DMA_Cmd(spi_dev->cfg->dma.rx.channel, ENABLE); + DMA_Cmd(spi_dev->cfg->dma.tx.channel, ENABLE); + + /* Reenable the SPI device */ + SPI_Cmd(spi_dev->cfg->regs, ENABLE); + + if (callback) { + /* User has requested a callback, don't wait for the transfer to complete. */ + return 0; + } + + /* Wait until all bytes have been transmitted/received */ + while (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)); + + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (!(SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE))); + + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)); + + /* Check the CRC on the transfer if enabled. */ + if (spi_dev->cfg->use_crc) { + /* Check the SPI CRC error flag */ + if (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_FLAG_CRCERR)) { + return -4; + } + } + + /* No error */ + return 0; +} + +/** +* Check if a transfer is in progress +* \param[in] spi SPI number (0 or 1) +* \return >= 0 if no transfer is in progress +* \return -1 if disabled SPI port selected +* \return -2 if unsupported SPI port selected +* \return -3 if function has been called during an ongoing DMA transfer +*/ +int32_t PIOS_SPI_Busy(uint32_t spi_id) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + /* DMA buffer has data or SPI transmit register not empty or SPI is busy*/ + if (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel) || + !SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE) || + SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)) + { + return -3; + } + + return(0); +} + +void PIOS_SPI_SetPrescalar(uint32_t spi_id, uint32_t prescaler) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid); + PIOS_Assert(IS_SPI_BAUDRATE_PRESCALER(prescaler)); + + spi_dev->cfg->regs->CR1 = (spi_dev->cfg->regs->CR1 & ~0x0038) | prescaler; +} + +void PIOS_SPI_IRQ_Handler(uint32_t spi_id) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + DMA_ClearFlag(spi_dev->cfg->dma.irq.flags); + + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (!(SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE))) ; + + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)) ; + + if (spi_dev->callback != NULL) { + bool crc_ok = TRUE; + uint8_t crc_val; + + if (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_FLAG_CRCERR)) { + crc_ok = FALSE; + SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR); + } + crc_val = SPI_GetCRC(spi_dev->cfg->regs, SPI_CRC_Rx); + spi_dev->callback(crc_ok, crc_val); + } +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F10x/pios_sys.c b/flight/PiOS/STM32F10x/pios_sys.c index 04d79c45b..6b59afbad 100644 --- a/flight/PiOS/STM32F10x/pios_sys.c +++ b/flight/PiOS/STM32F10x/pios_sys.c @@ -118,8 +118,8 @@ uint32_t PIOS_SYS_getCPUFlashSize(void) /** * Returns the serial number as a string -* param[out] str pointer to a string which can store at least 32 digits + zero terminator! -* (24 digits returned for STM32) +* param[out] uint8_t pointer to a string which can store at least 12 bytes +* (12 bytes returned for STM32) * return < 0 if feature not supported */ int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array) @@ -127,7 +127,7 @@ int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array) int i; /* Stored in the so called "electronic signature" */ - for (i = 0; i < 12; ++i) { + for (i = 0; i < PIOS_SYS_SERIAL_NUM_BINARY_LEN; ++i) { uint8_t b = MEM8(0x1ffff7e8 + i); array[i] = b; @@ -148,7 +148,7 @@ int32_t PIOS_SYS_SerialNumberGet(char *str) int i; /* Stored in the so called "electronic signature" */ - for (i = 0; i < 24; ++i) { + for (i = 0; i < PIOS_SYS_SERIAL_NUM_ASCII_LEN; ++i) { uint8_t b = MEM8(0x1ffff7e8 + (i / 2)); if (!(i & 1)) b >>= 4; diff --git a/flight/PiOS/STM32F10x/pios_usb.c b/flight/PiOS/STM32F10x/pios_usb.c index 15decfca1..edac4611a 100644 --- a/flight/PiOS/STM32F10x/pios_usb.c +++ b/flight/PiOS/STM32F10x/pios_usb.c @@ -40,7 +40,7 @@ #if defined(PIOS_INCLUDE_USB_HID) /* Rx/Tx status */ -static uint8_t transfer_possible = 0; +static bool transfer_possible = false; enum pios_usb_dev_magic { PIOS_USB_DEV_MAGIC = 0x17365904, @@ -51,12 +51,20 @@ struct pios_usb_dev { const struct pios_usb_cfg * cfg; }; -#if 0 -static bool PIOS_USB_validate(struct pios_usb_dev * usb_dev) +/** + * @brief Validate the usb device structure + * @returns 0 if valid device or -1 otherwise + */ +static int32_t PIOS_USB_validate(struct pios_usb_dev * usb_dev) { - return (usb_dev->magic == PIOS_USB_DEV_MAGIC); + if(usb_dev == NULL) + return -1; + + if (usb_dev->magic != PIOS_USB_DEV_MAGIC) + return -1; + + return 0; } -#endif #if defined(PIOS_INCLUDE_FREERTOS) static struct pios_usb_dev * PIOS_USB_alloc(void) @@ -140,11 +148,11 @@ out_fail: * \return < 0 on errors * \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions */ -int32_t PIOS_USB_ChangeConnectionState(uint32_t Connected) +int32_t PIOS_USB_ChangeConnectionState(bool Connected) { // In all cases: re-initialise USB HID driver if (Connected) { - transfer_possible = 1; + transfer_possible = true; //TODO: Check SetEPRxValid(ENDP1); @@ -153,7 +161,7 @@ int32_t PIOS_USB_ChangeConnectionState(uint32_t Connected) #endif } else { // Cable disconnected: disable transfers - transfer_possible = 0; + transfer_possible = false; #if defined(USB_LED_OFF) USB_LED_OFF; // turn the USB led off @@ -199,6 +207,16 @@ int32_t PIOS_USB_Reenumerate() return 0; } +bool PIOS_USB_CableConnected(uint8_t id) +{ + struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_com_id; + + if (PIOS_USB_validate(usb_dev) != 0) + return false; + + return usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin; +} + /** * This function returns the connection status of the USB HID interface * \return 1: interface available @@ -207,7 +225,12 @@ int32_t PIOS_USB_Reenumerate() */ bool PIOS_USB_CheckAvailable(uint8_t id) { - return (PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) != 0 && transfer_possible ? 1 : 0; + struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_com_id; + + if (PIOS_USB_validate(usb_dev) != 0) + return false; + + return PIOS_USB_CableConnected(id) && transfer_possible; } #endif diff --git a/flight/PiOS/STM32F10x/pios_usb_cdc.c b/flight/PiOS/STM32F10x/pios_usb_cdc.c index 4bb1303d9..7a9bc0b23 100644 --- a/flight/PiOS/STM32F10x/pios_usb_cdc.c +++ b/flight/PiOS/STM32F10x/pios_usb_cdc.c @@ -38,6 +38,9 @@ #include "pios_usb_cdc_priv.h" #include "pios_usb_board_data.h" /* PIOS_BOARD_*_DATA_LENGTH */ +/* STM32 USB Library Definitions */ +#include "usb_lib.h" + static void PIOS_USB_CDC_RegisterTxCallback(uint32_t usbcdc_id, pios_com_callback tx_out_cb, uint32_t context); static void PIOS_USB_CDC_RegisterRxCallback(uint32_t usbcdc_id, pios_com_callback rx_in_cb, uint32_t context); static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, uint16_t tx_bytes_avail); @@ -312,6 +315,7 @@ static void PIOS_USB_CDC_DATA_EP_OUT_Callback(void) #endif /* PIOS_INCLUDE_FREERTOS */ } +static uint16_t control_line_state; RESULT PIOS_USB_CDC_SetControlLineState(void) { struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; @@ -319,8 +323,6 @@ RESULT PIOS_USB_CDC_SetControlLineState(void) bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); PIOS_Assert(valid); - static uint16_t control_line_state; - uint8_t wValue0 = pInformation->USBwValue0; uint8_t wValue1 = pInformation->USBwValue1; diff --git a/flight/PiOS/STM32F10x/pios_usb_hid.c b/flight/PiOS/STM32F10x/pios_usb_hid.c index e70c93046..72a08b7a7 100644 --- a/flight/PiOS/STM32F10x/pios_usb_hid.c +++ b/flight/PiOS/STM32F10x/pios_usb_hid.c @@ -38,6 +38,9 @@ #include "pios_usb_hid_priv.h" #include "pios_usb_board_data.h" /* PIOS_BOARD_*_DATA_LENGTH */ +/* STM32 USB Library Definitions */ +#include "usb_lib.h" + static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbhid_id, pios_com_callback tx_out_cb, uint32_t context); static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbhid_id, pios_com_callback rx_in_cb, uint32_t context); static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, uint16_t tx_bytes_avail); diff --git a/flight/PiOS/STM32F10x/pios_usbhook.c b/flight/PiOS/STM32F10x/pios_usbhook.c index 7800faed1..cb3220227 100644 --- a/flight/PiOS/STM32F10x/pios_usbhook.c +++ b/flight/PiOS/STM32F10x/pios_usbhook.c @@ -36,6 +36,9 @@ #include "pios_usb_cdc_priv.h" /* PIOS_USB_CDC_* */ #include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */ +/* STM32 USB Library Definitions */ +#include "usb_lib.h" + static ONE_DESCRIPTOR Device_Descriptor; void PIOS_USBHOOK_RegisterDevice(const uint8_t * desc, uint16_t desc_size) @@ -62,17 +65,17 @@ void PIOS_USBHOOK_RegisterString(enum usb_string_desc string_id, const uint8_t * } } -static ONE_DESCRIPTOR Hid_Interface_Descriptor; +static ONE_DESCRIPTOR Hid_Descriptor; -void PIOS_USBHOOK_RegisterHidInterface(const uint8_t * desc, uint16_t desc_size) +void PIOS_USB_HID_RegisterHidDescriptor(const uint8_t * desc, uint16_t desc_size) { - Hid_Interface_Descriptor.Descriptor = desc; - Hid_Interface_Descriptor.Descriptor_Size = desc_size; + Hid_Descriptor.Descriptor = desc; + Hid_Descriptor.Descriptor_Size = desc_size; } static ONE_DESCRIPTOR Hid_Report_Descriptor; -void PIOS_USBHOOK_RegisterHidReport(const uint8_t * desc, uint16_t desc_size) +void PIOS_USB_HID_RegisterHidReport(const uint8_t * desc, uint16_t desc_size) { Hid_Report_Descriptor.Descriptor = desc; Hid_Report_Descriptor.Descriptor_Size = desc_size; @@ -290,6 +293,8 @@ static void PIOS_USBHOOK_Status_Out(void) * Output : None. * Return : USB_UNSUPPORT or USB_SUCCESS. *******************************************************************************/ +extern const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length); + static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo) { const uint8_t *(*CopyRoutine) (uint16_t); @@ -299,7 +304,11 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo) switch (Type_Recipient) { case (STANDARD_REQUEST | INTERFACE_RECIPIENT): switch (pInformation->USBwIndex0) { +#if defined(PIOS_INCLUDE_USB_CDC) + case 2: /* HID Interface */ +#else case 0: /* HID Interface */ +#endif switch (RequestNo) { case GET_DESCRIPTOR: switch (pInformation->USBwValue1) { @@ -316,25 +325,29 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo) case (CLASS_REQUEST | INTERFACE_RECIPIENT): switch (pInformation->USBwIndex0) { +#if defined(PIOS_INCLUDE_USB_CDC) + case 2: /* HID Interface */ +#else case 0: /* HID Interface */ +#endif switch (RequestNo) { - case GET_PROTOCOL: + case USB_HID_REQ_GET_PROTOCOL: CopyRoutine = PIOS_USBHOOK_GetProtocolValue; break; } break; #if defined(PIOS_INCLUDE_USB_CDC) - case 1: /* CDC Call Control Interface */ + case 0: /* CDC Call Control Interface */ switch (RequestNo) { - case GET_LINE_CODING: - CopyRoutine = PIOS_USB_CDC_GetLineCoding; + case USB_CDC_REQ_GET_LINE_CODING: + //CopyRoutine = PIOS_USB_CDC_GetLineCoding; break; } break; - case 2: /* CDC Data Interface */ + case 1: /* CDC Data Interface */ switch (RequestNo) { case 0: break; @@ -363,14 +376,21 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo) * Output : None. * Return : USB_UNSUPPORT or USB_SUCCESS. *******************************************************************************/ +extern RESULT PIOS_USB_CDC_SetControlLineState(void); +extern RESULT PIOS_USB_CDC_SetLineCoding(void); + static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo) { switch (Type_Recipient) { case (CLASS_REQUEST | INTERFACE_RECIPIENT): switch (pInformation->USBwIndex0) { +#if defined(PIOS_INCLUDE_USB_CDC) + case 2: /* HID */ +#else case 0: /* HID */ +#endif switch (RequestNo) { - case SET_PROTOCOL: + case USB_HID_REQ_SET_PROTOCOL: return PIOS_USBHOOK_SetProtocol(); break; } @@ -378,12 +398,12 @@ static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo) break; #if defined(PIOS_INCLUDE_USB_CDC) - case 1: /* CDC Call Control Interface */ + case 0: /* CDC Call Control Interface */ switch (RequestNo) { - case SET_LINE_CODING: + case USB_CDC_REQ_SET_LINE_CODING: return PIOS_USB_CDC_SetLineCoding(); break; - case SET_CONTROL_LINE_STATE: + case USB_CDC_REQ_SET_CONTROL_LINE_STATE: return PIOS_USB_CDC_SetControlLineState(); break; } @@ -460,7 +480,7 @@ static const uint8_t *PIOS_USBHOOK_GetReportDescriptor(uint16_t Length) *******************************************************************************/ static const uint8_t *PIOS_USBHOOK_GetHIDDescriptor(uint16_t Length) { - return Standard_GetDescriptorData(Length, &Hid_Interface_Descriptor); + return Standard_GetDescriptorData(Length, &Hid_Descriptor); } /******************************************************************************* diff --git a/flight/PiOS/STM32F10x/pios_wdg.c b/flight/PiOS/STM32F10x/pios_wdg.c index e0b5b58d9..c8f41bf29 100644 --- a/flight/PiOS/STM32F10x/pios_wdg.c +++ b/flight/PiOS/STM32F10x/pios_wdg.c @@ -73,6 +73,7 @@ uint16_t PIOS_WDG_Init() // watchdog flags now stored in backup registers PWR_BackupAccessCmd(ENABLE); + BKP_WriteBackupRegister(PIOS_WDG_REGISTER, 0x0); wdg_configuration.bootup_flags = BKP_ReadBackupRegister(PIOS_WDG_REGISTER); #endif return delay; diff --git a/flight/PiOS/STM32F10x/startup_stm32f10x_HD.S b/flight/PiOS/STM32F10x/startup_stm32f10x_HD.S index a512f98a7..83b2a82c2 100644 --- a/flight/PiOS/STM32F10x/startup_stm32f10x_HD.S +++ b/flight/PiOS/STM32F10x/startup_stm32f10x_HD.S @@ -66,12 +66,6 @@ defined in linker script */ .type Reset_Handler, %function Reset_Handler: -/* FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is - required, then adjust the Register Addresses */ - bl SystemInit_ExtMemCtl -/* restore original stack pointer */ - LDR r0, =_estack - MSR msp, r0 /* Copy the data segment initializers from flash to SRAM */ movs r1, #0 b LoopCopyDataInit @@ -140,7 +134,7 @@ Infinite_Loop: g_pfnVectors: - .word Initial_spTop + .word _estack .word Reset_Handler .word NMI_Handler .word HardFault_Handler diff --git a/flight/PiOS/STM32F10x/startup_stm32f10x_MD_PX.S b/flight/PiOS/STM32F10x/startup_stm32f10x_MD_PX.S new file mode 100644 index 000000000..828462ab6 --- /dev/null +++ b/flight/PiOS/STM32F10x/startup_stm32f10x_MD_PX.S @@ -0,0 +1,427 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team / Angus Peart + * @version V3.1.2 + * @date 09/28/2009 + * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ******************************************************************************* + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2009 STMicroelectronics

+ */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler +.global xPortIncreaseHeapSize +.global Stack_Change + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* + * From COrtex-M3 reference manual: + * - Handler IRQ always use SP_main + * - Process use SP_main or SP_process + * Here, we will use beginning of SRAM for IRQ (SP_main) + * and end of heap for initialization (SP_process). + * Once the schedule starts, all threads will use their own stack + * from heap and NOBOBY should use SP_process again. + */ + /* Do set/reset the stack pointers */ + LDR r0, =_irq_stack_top + MSR msp, r0 + LDR r2, =_init_stack_top + MSR psp, r2 + /* check if irq and init stack are the same */ + /* if they are, we don't do stack swap */ + /* and lets bypass the monitoring as well for now */ + cmp r0, r2 + beq SectionBssInit +/* DO + * - stay in thread process mode + * - stay in privilege level + * - use process stack + */ + movs r0, #2 + MSR control, r0 + ISB +/* Fill IRQ stack for watermark monitoring */ + ldr r2, =_irq_stack_end + b LoopFillIRQStack + +FillIRQStack: + movw r3, #0xA5A5 + str r3, [r2], #4 + +LoopFillIRQStack: + ldr r3, = _irq_stack_top + cmp r2, r3 + bcc FillIRQStack + +SectionBssInit: +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the application's entry point.*/ + bl main +/* will never return here */ + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that swaps stack (from end of heap to irq_stack). + * Also reclaim the heap that was used as a stack. + * @param None + * @retval : None +*/ + .section .text.Stack_Change + .weak Stack_Change + .type Stack_Change, %function +Stack_Change: + mov r4, lr +/* Switches stack back momentarily to MSP */ + movs r0, #0 + msr control, r0 +Heap_Reclaim: +/* add heap_post_rtos to the heap (if the capability/function exist) */ +/* Also claim the unused memory (between end of heap to end of memory */ +/* CAREFULL: the heap section must be the last section in RAM in order this to work */ + ldr r0, = _init_stack_size + ldr r1, = _eheap_post_rtos + ldr r2, = _eram + subs r2, r2, r1 + adds r0, r0, r2 + bl xPortIncreaseHeapSize + bx r4 + .size Stack_Change, .-Stack_Change + + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _irq_stack_top + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word vPortSVCHandler + .word DebugMon_Handler + .word 0 + .word xPortPendSVHandler + .word xPortSysTickHandler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + diff --git a/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Include/stm32f4xx.h b/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Include/stm32f4xx.h new file mode 100644 index 000000000..86a85e778 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Include/stm32f4xx.h @@ -0,0 +1,6999 @@ +/** + ****************************************************************************** + * @file stm32f4xx.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief CMSIS Cortex-M4 Device Peripheral Access Layer Header File. + * This file contains all the peripheral register's definitions, bits + * definitions and memory mapping for STM32F4xx devices. + * + * The file is the unique include file that the application programmer + * is using in the C source code, usually in main.c. This file contains: + * - Configuration section that allows to select: + * - The device used in the target application + * - To use or not the peripheral’s drivers in application code(i.e. + * code will be based on direct access to peripheral’s registers + * rather than drivers API), this option is controlled by + * "#define USE_STDPERIPH_DRIVER" + * - To change few application-specific parameters such as the HSE + * crystal frequency + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral’s registers hardware + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f4xx + * @{ + */ + +#ifndef __STM32F4xx_H +#define __STM32F4xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + +/** @addtogroup Library_configuration_section + * @{ + */ + +/* Uncomment the line below according to the target STM32 device used in your + application + */ + +#if !defined (STM32F4XX) + #define STM32F4XX +#endif + +/* Tip: To avoid modifying this file each time you need to switch between these + devices, you can define the device in your toolchain compiler preprocessor. + */ + +#if !defined (STM32F4XX) + #error "Please select first the target STM32F4XX device used in your application (in stm32f4xx.h file)" +#endif + +#if !defined (USE_STDPERIPH_DRIVER) +/** + * @brief Comment the line below if you will not use the peripherals drivers. + In this case, these drivers will not be included and the application code will + be based on direct access to peripherals registers + */ + /*#define USE_STDPERIPH_DRIVER*/ +#endif /* USE_STDPERIPH_DRIVER */ + +/** + * @brief In the following line adjust the value of External High Speed oscillator (HSE) + used in your application + + Tip: To avoid modifying this file each time you need to use different HSE, you + can define the HSE value in your toolchain compiler preprocessor. + */ + +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +/** + * @brief In the following line adjust the External High Speed oscillator (HSE) Startup + Timeout value + */ +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint16_t)0x0500) /*!< Time out for HSE start up */ +#endif /* HSE_STARTUP_TIMEOUT */ + +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief STM32F4XX Standard Peripherals Library version number V1.0.0 + */ +#define __STM32F4XX_STDPERIPH_VERSION_MAIN (0x01) /*!< [31:24] main version */ +#define __STM32F4XX_STDPERIPH_VERSION_SUB1 (0x00) /*!< [23:16] sub1 version */ +#define __STM32F4XX_STDPERIPH_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */ +#define __STM32F4XX_STDPERIPH_VERSION_RC (0x00) /*!< [7:0] release candidate */ +#define __STM32F4XX_STDPERIPH_VERSION ((__STM32F4XX_STDPERIPH_VERSION_MAIN << 24)\ + |(__STM32F4XX_STDPERIPH_VERSION_SUB1 << 16)\ + |(__STM32F4XX_STDPERIPH_VERSION_SUB2 << 8)\ + |(__STM32F4XX_STDPERIPH_VERSION_RC)) + +/** + * @} + */ + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ + +/** + * @brief Configuration of the Cortex-M4 Processor and Core Peripherals + */ +#define __CM4_REV 0x0001 /*!< Core revision r0p1 */ +#define __MPU_PRESENT 1 /*!< STM32F4XX provides an MPU */ +#define __NVIC_PRIO_BITS 4 /*!< STM32F4XX uses 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ +#define __FPU_PRESENT 1 /*!< FPU present */ + +/** + * @brief STM32F4XX Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ +typedef enum IRQn +{ +/****** Cortex-M4 Processor Exceptions Numbers ****************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M4 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M4 Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M4 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M4 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M4 System Tick Interrupt */ +/****** STM32 specific Interrupt Numbers **********************************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ + TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ + RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ + FLASH_IRQn = 4, /*!< FLASH global Interrupt */ + RCC_IRQn = 5, /*!< RCC global Interrupt */ + EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ + EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ + EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ + EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ + EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ + DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ + DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ + DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ + DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ + DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ + DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ + DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ + ADC_IRQn = 18, /*!< ADC1, ADC2 and ADC3 global Interrupts */ + CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ + CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ + TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ + TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ + OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ + TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ + TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ + TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ + TIM7_IRQn = 55, /*!< TIM7 global interrupt */ + DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ + DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ + DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ + DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ + DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ + ETH_IRQn = 61, /*!< Ethernet global Interrupt */ + ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ + CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ + CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ + CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ + CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ + OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ + DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ + DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ + DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ + USART6_IRQn = 71, /*!< USART6 global interrupt */ + I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ + I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ + OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ + OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ + OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ + OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ + DCMI_IRQn = 78, /*!< DCMI global interrupt */ + CRYP_IRQn = 79, /*!< CRYP crypto global interrupt */ + HASH_RNG_IRQn = 80, /*!< Hash and Rng global interrupt */ + FPU_IRQn = 81 /*!< FPU global interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ +#include "system_stm32f4xx.h" +#include + +/** @addtogroup Exported_types + * @{ + */ +/*!< STM32F10x Standard Peripheral Library old types (maintained for legacy purpose) */ +typedef int32_t s32; +typedef int16_t s16; +typedef int8_t s8; + +typedef const int32_t sc32; /*!< Read Only */ +typedef const int16_t sc16; /*!< Read Only */ +typedef const int8_t sc8; /*!< Read Only */ + +typedef __IO int32_t vs32; +typedef __IO int16_t vs16; +typedef __IO int8_t vs8; + +typedef __I int32_t vsc32; /*!< Read Only */ +typedef __I int16_t vsc16; /*!< Read Only */ +typedef __I int8_t vsc8; /*!< Read Only */ + +typedef uint32_t u32; +typedef uint16_t u16; +typedef uint8_t u8; + +typedef const uint32_t uc32; /*!< Read Only */ +typedef const uint16_t uc16; /*!< Read Only */ +typedef const uint8_t uc8; /*!< Read Only */ + +typedef __IO uint32_t vu32; +typedef __IO uint16_t vu16; +typedef __IO uint8_t vu8; + +typedef __I uint32_t vuc32; /*!< Read Only */ +typedef __I uint16_t vuc16; /*!< Read Only */ +typedef __I uint8_t vuc8; /*!< Read Only */ + +typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus; + +typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; +#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) + +typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus; + +/** + * @} + */ + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ + __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ + __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ + __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ + __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ + __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ + __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ + __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ + __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ + __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ + __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ + __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ + __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ + __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ + __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ + __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ + __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ + __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ + __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ + __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ +} ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ + __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ + __IO uint32_t CDR; /*!< ADC common regular data register for dual + AND triple modes, Address offset: ADC1 base address + 0x308 */ +} ADC_Common_TypeDef; + + +/** + * @brief Controller Area Network TxMailBox + */ + +typedef struct +{ + __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ + __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ + __IO uint32_t TDLR; /*!< CAN mailbox data low register */ + __IO uint32_t TDHR; /*!< CAN mailbox data high register */ +} CAN_TxMailBox_TypeDef; + +/** + * @brief Controller Area Network FIFOMailBox + */ + +typedef struct +{ + __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +/** + * @brief Controller Area Network FilterRegister + */ + +typedef struct +{ + __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ + __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ +} CAN_FilterRegister_TypeDef; + +/** + * @brief Controller Area Network + */ + +typedef struct +{ + __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ + __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ + __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ + __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ + __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ + __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ + __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ + __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ + uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ + CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ + CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ + uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ + __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ + __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ + uint32_t RESERVED2; /*!< Reserved, 0x208 */ + __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ + uint32_t RESERVED3; /*!< Reserved, 0x210 */ + __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ + uint32_t RESERVED4; /*!< Reserved, 0x218 */ + __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ + uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ + CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ +} CAN_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + uint8_t RESERVED0; /*!< Reserved, 0x05 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ +} CRC_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ + __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ + __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ + __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ + __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ + __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ + __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ + __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ + __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ + __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ + __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ + __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ + __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ + __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ +} DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ + __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ + __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ + __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ +}DBGMCU_TypeDef; + +/** + * @brief DCMI + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DCMI control register 1, Address offset: 0x00 */ + __IO uint32_t SR; /*!< DCMI status register, Address offset: 0x04 */ + __IO uint32_t RISR; /*!< DCMI raw interrupt status register, Address offset: 0x08 */ + __IO uint32_t IER; /*!< DCMI interrupt enable register, Address offset: 0x0C */ + __IO uint32_t MISR; /*!< DCMI masked interrupt status register, Address offset: 0x10 */ + __IO uint32_t ICR; /*!< DCMI interrupt clear register, Address offset: 0x14 */ + __IO uint32_t ESCR; /*!< DCMI embedded synchronization code register, Address offset: 0x18 */ + __IO uint32_t ESUR; /*!< DCMI embedded synchronization unmask register, Address offset: 0x1C */ + __IO uint32_t CWSTRTR; /*!< DCMI crop window start, Address offset: 0x20 */ + __IO uint32_t CWSIZER; /*!< DCMI crop window size, Address offset: 0x24 */ + __IO uint32_t DR; /*!< DCMI data register, Address offset: 0x28 */ +} DCMI_TypeDef; + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DMA stream x configuration register */ + __IO uint32_t NDTR; /*!< DMA stream x number of data register */ + __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ + __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ + __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ + __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ +} DMA_Stream_TypeDef; + +typedef struct +{ + __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ + __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ + __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ + __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ +} DMA_TypeDef; + +/** + * @brief Ethernet MAC + */ + +typedef struct +{ + __IO uint32_t MACCR; + __IO uint32_t MACFFR; + __IO uint32_t MACHTHR; + __IO uint32_t MACHTLR; + __IO uint32_t MACMIIAR; + __IO uint32_t MACMIIDR; + __IO uint32_t MACFCR; + __IO uint32_t MACVLANTR; /* 8 */ + uint32_t RESERVED0[2]; + __IO uint32_t MACRWUFFR; /* 11 */ + __IO uint32_t MACPMTCSR; + uint32_t RESERVED1[2]; + __IO uint32_t MACSR; /* 15 */ + __IO uint32_t MACIMR; + __IO uint32_t MACA0HR; + __IO uint32_t MACA0LR; + __IO uint32_t MACA1HR; + __IO uint32_t MACA1LR; + __IO uint32_t MACA2HR; + __IO uint32_t MACA2LR; + __IO uint32_t MACA3HR; + __IO uint32_t MACA3LR; /* 24 */ + uint32_t RESERVED2[40]; + __IO uint32_t MMCCR; /* 65 */ + __IO uint32_t MMCRIR; + __IO uint32_t MMCTIR; + __IO uint32_t MMCRIMR; + __IO uint32_t MMCTIMR; /* 69 */ + uint32_t RESERVED3[14]; + __IO uint32_t MMCTGFSCCR; /* 84 */ + __IO uint32_t MMCTGFMSCCR; + uint32_t RESERVED4[5]; + __IO uint32_t MMCTGFCR; + uint32_t RESERVED5[10]; + __IO uint32_t MMCRFCECR; + __IO uint32_t MMCRFAECR; + uint32_t RESERVED6[10]; + __IO uint32_t MMCRGUFCR; + uint32_t RESERVED7[334]; + __IO uint32_t PTPTSCR; + __IO uint32_t PTPSSIR; + __IO uint32_t PTPTSHR; + __IO uint32_t PTPTSLR; + __IO uint32_t PTPTSHUR; + __IO uint32_t PTPTSLUR; + __IO uint32_t PTPTSAR; + __IO uint32_t PTPTTHR; + __IO uint32_t PTPTTLR; + __IO uint32_t RESERVED8; + __IO uint32_t PTPTSSR; + uint32_t RESERVED9[565]; + __IO uint32_t DMABMR; + __IO uint32_t DMATPDR; + __IO uint32_t DMARPDR; + __IO uint32_t DMARDLAR; + __IO uint32_t DMATDLAR; + __IO uint32_t DMASR; + __IO uint32_t DMAOMR; + __IO uint32_t DMAIER; + __IO uint32_t DMAMFBOCR; + __IO uint32_t DMARSWTR; + uint32_t RESERVED10[8]; + __IO uint32_t DMACHTDR; + __IO uint32_t DMACHRDR; + __IO uint32_t DMACHTBAR; + __IO uint32_t DMACHRBAR; +} ETH_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ + __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ + __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ + __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ + __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ + __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ +} EXTI_TypeDef; + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ + __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ + __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ + __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ + __IO uint32_t OPTCR; /*!< FLASH option control register, Address offset: 0x14 */ +} FLASH_TypeDef; + +/** + * @brief Flexible Static Memory Controller + */ + +typedef struct +{ + __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ +} FSMC_Bank1_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ +} FSMC_Bank1E_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank2 + */ + +typedef struct +{ + __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ + __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ + __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ + __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ + uint32_t RESERVED0; /*!< Reserved, 0x70 */ + __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ +} FSMC_Bank2_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank3 + */ + +typedef struct +{ + __IO uint32_t PCR3; /*!< NAND Flash control register 3, Address offset: 0x80 */ + __IO uint32_t SR3; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ + __IO uint32_t PMEM3; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ + __IO uint32_t PATT3; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ + uint32_t RESERVED0; /*!< Reserved, 0x90 */ + __IO uint32_t ECCR3; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ +} FSMC_Bank3_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank4 + */ + +typedef struct +{ + __IO uint32_t PCR4; /*!< PC Card control register 4, Address offset: 0xA0 */ + __IO uint32_t SR4; /*!< PC Card FIFO status and interrupt register 4, Address offset: 0xA4 */ + __IO uint32_t PMEM4; /*!< PC Card Common memory space timing register 4, Address offset: 0xA8 */ + __IO uint32_t PATT4; /*!< PC Card Attribute memory space timing register 4, Address offset: 0xAC */ + __IO uint32_t PIO4; /*!< PC Card I/O space timing register 4, Address offset: 0xB0 */ +} FSMC_Bank4_TypeDef; + +/** + * @brief General Purpose I/O + */ + +typedef struct +{ + __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ + __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ + __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ + __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ + __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ + __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ + __IO uint16_t BSRRL; /*!< GPIO port bit set/reset low register, Address offset: 0x18 */ + __IO uint16_t BSRRH; /*!< GPIO port bit set/reset high register, Address offset: 0x1A */ + __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ + __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ +} GPIO_TypeDef; + +/** + * @brief System configuration controller + */ + +typedef struct +{ + __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ + __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ + __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ + uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */ + __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ +} SYSCFG_TypeDef; + +/** + * @brief Inter-integrated Circuit Interface + */ + +typedef struct +{ + __IO uint16_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ + uint16_t RESERVED0; /*!< Reserved, 0x02 */ + __IO uint16_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint16_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ + uint16_t RESERVED2; /*!< Reserved, 0x0A */ + __IO uint16_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ + uint16_t RESERVED3; /*!< Reserved, 0x0E */ + __IO uint16_t DR; /*!< I2C Data register, Address offset: 0x10 */ + uint16_t RESERVED4; /*!< Reserved, 0x12 */ + __IO uint16_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ + uint16_t RESERVED5; /*!< Reserved, 0x16 */ + __IO uint16_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ + uint16_t RESERVED6; /*!< Reserved, 0x1A */ + __IO uint16_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ + uint16_t RESERVED7; /*!< Reserved, 0x1E */ + __IO uint16_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ + uint16_t RESERVED8; /*!< Reserved, 0x22 */ +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ + __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ + __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ +} IWDG_TypeDef; + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ + __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ +} PWR_TypeDef; + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ + __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ + __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ + __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ + __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ + __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ + __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ + uint32_t RESERVED0; /*!< Reserved, 0x1C */ + __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ + __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ + uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ + __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ + __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ + __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ + uint32_t RESERVED2; /*!< Reserved, 0x3C */ + __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ + __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ + uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ + __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ + __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ + __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ + uint32_t RESERVED4; /*!< Reserved, 0x5C */ + __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ + __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ + uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ + __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ + __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ + uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ + __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ + __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ +} RCC_TypeDef; + +/** + * @brief Real-Time Clock + */ + +typedef struct +{ + __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ + __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ + __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ + __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ + __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ + __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ + __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ + __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ + __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ + __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ + __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ + __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ + __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ + __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ + __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ + __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ + __IO uint32_t ALRMASSR;/*!< RTC alarm A sub second register, Address offset: 0x44 */ + __IO uint32_t ALRMBSSR;/*!< RTC alarm B sub second register, Address offset: 0x48 */ + uint32_t RESERVED7; /*!< Reserved, 0x4C */ + __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ + __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ + __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ + __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ + __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ + __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ + __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ + __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ + __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ + __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ + __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ + __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ + __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ + __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ + __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ + __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ + __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ + __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ + __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ + __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ +} RTC_TypeDef; + +/** + * @brief SD host Interface + */ + +typedef struct +{ + __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ + __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ + __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ + __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ + __I uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ + __I uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ + __I uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ + __I uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ + __I uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ + __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ + __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ + __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ + __I uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ + __I uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ + __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ + __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ + uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ + __I uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ + uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ + __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ +} SDIO_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint16_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ + uint16_t RESERVED0; /*!< Reserved, 0x02 */ + __IO uint16_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint16_t SR; /*!< SPI status register, Address offset: 0x08 */ + uint16_t RESERVED2; /*!< Reserved, 0x0A */ + __IO uint16_t DR; /*!< SPI data register, Address offset: 0x0C */ + uint16_t RESERVED3; /*!< Reserved, 0x0E */ + __IO uint16_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ + uint16_t RESERVED4; /*!< Reserved, 0x12 */ + __IO uint16_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ + uint16_t RESERVED5; /*!< Reserved, 0x16 */ + __IO uint16_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ + uint16_t RESERVED6; /*!< Reserved, 0x1A */ + __IO uint16_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ + uint16_t RESERVED7; /*!< Reserved, 0x1E */ + __IO uint16_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ + uint16_t RESERVED8; /*!< Reserved, 0x22 */ +} SPI_TypeDef; + +/** + * @brief TIM + */ + +typedef struct +{ + __IO uint16_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ + uint16_t RESERVED0; /*!< Reserved, 0x02 */ + __IO uint16_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint16_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ + uint16_t RESERVED2; /*!< Reserved, 0x0A */ + __IO uint16_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ + uint16_t RESERVED3; /*!< Reserved, 0x0E */ + __IO uint16_t SR; /*!< TIM status register, Address offset: 0x10 */ + uint16_t RESERVED4; /*!< Reserved, 0x12 */ + __IO uint16_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ + uint16_t RESERVED5; /*!< Reserved, 0x16 */ + __IO uint16_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ + uint16_t RESERVED6; /*!< Reserved, 0x1A */ + __IO uint16_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ + uint16_t RESERVED7; /*!< Reserved, 0x1E */ + __IO uint16_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ + uint16_t RESERVED8; /*!< Reserved, 0x22 */ + __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ + __IO uint16_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ + uint16_t RESERVED9; /*!< Reserved, 0x2A */ + __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ + __IO uint16_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ + uint16_t RESERVED10; /*!< Reserved, 0x32 */ + __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ + __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ + __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ + __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ + __IO uint16_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ + uint16_t RESERVED11; /*!< Reserved, 0x46 */ + __IO uint16_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ + uint16_t RESERVED12; /*!< Reserved, 0x4A */ + __IO uint16_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ + uint16_t RESERVED13; /*!< Reserved, 0x4E */ + __IO uint16_t OR; /*!< TIM option register, Address offset: 0x50 */ + uint16_t RESERVED14; /*!< Reserved, 0x52 */ +} TIM_TypeDef; + +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ + +typedef struct +{ + __IO uint16_t SR; /*!< USART Status register, Address offset: 0x00 */ + uint16_t RESERVED0; /*!< Reserved, 0x02 */ + __IO uint16_t DR; /*!< USART Data register, Address offset: 0x04 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint16_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ + uint16_t RESERVED2; /*!< Reserved, 0x0A */ + __IO uint16_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ + uint16_t RESERVED3; /*!< Reserved, 0x0E */ + __IO uint16_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ + uint16_t RESERVED4; /*!< Reserved, 0x12 */ + __IO uint16_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ + uint16_t RESERVED5; /*!< Reserved, 0x16 */ + __IO uint16_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ + uint16_t RESERVED6; /*!< Reserved, 0x1A */ +} USART_TypeDef; + +/** + * @brief Window WATCHDOG + */ + +typedef struct +{ + __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ + __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ + __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ +} WWDG_TypeDef; + +/** + * @brief Crypto Processor + */ + +typedef struct +{ + __IO uint32_t CR; /*!< CRYP control register, Address offset: 0x00 */ + __IO uint32_t SR; /*!< CRYP status register, Address offset: 0x04 */ + __IO uint32_t DR; /*!< CRYP data input register, Address offset: 0x08 */ + __IO uint32_t DOUT; /*!< CRYP data output register, Address offset: 0x0C */ + __IO uint32_t DMACR; /*!< CRYP DMA control register, Address offset: 0x10 */ + __IO uint32_t IMSCR; /*!< CRYP interrupt mask set/clear register, Address offset: 0x14 */ + __IO uint32_t RISR; /*!< CRYP raw interrupt status register, Address offset: 0x18 */ + __IO uint32_t MISR; /*!< CRYP masked interrupt status register, Address offset: 0x1C */ + __IO uint32_t K0LR; /*!< CRYP key left register 0, Address offset: 0x20 */ + __IO uint32_t K0RR; /*!< CRYP key right register 0, Address offset: 0x24 */ + __IO uint32_t K1LR; /*!< CRYP key left register 1, Address offset: 0x28 */ + __IO uint32_t K1RR; /*!< CRYP key right register 1, Address offset: 0x2C */ + __IO uint32_t K2LR; /*!< CRYP key left register 2, Address offset: 0x30 */ + __IO uint32_t K2RR; /*!< CRYP key right register 2, Address offset: 0x34 */ + __IO uint32_t K3LR; /*!< CRYP key left register 3, Address offset: 0x38 */ + __IO uint32_t K3RR; /*!< CRYP key right register 3, Address offset: 0x3C */ + __IO uint32_t IV0LR; /*!< CRYP initialization vector left-word register 0, Address offset: 0x40 */ + __IO uint32_t IV0RR; /*!< CRYP initialization vector right-word register 0, Address offset: 0x44 */ + __IO uint32_t IV1LR; /*!< CRYP initialization vector left-word register 1, Address offset: 0x48 */ + __IO uint32_t IV1RR; /*!< CRYP initialization vector right-word register 1, Address offset: 0x4C */ +} CRYP_TypeDef; + +/** + * @brief HASH + */ + +typedef struct +{ + __IO uint32_t CR; /*!< HASH control register, Address offset: 0x00 */ + __IO uint32_t DIN; /*!< HASH data input register, Address offset: 0x04 */ + __IO uint32_t STR; /*!< HASH start register, Address offset: 0x08 */ + __IO uint32_t HR[5]; /*!< HASH digest registers, Address offset: 0x0C-0x1C */ + __IO uint32_t IMR; /*!< HASH interrupt enable register, Address offset: 0x20 */ + __IO uint32_t SR; /*!< HASH status register, Address offset: 0x24 */ + uint32_t RESERVED[52]; /*!< Reserved, 0x28-0xF4 */ + __IO uint32_t CSR[51]; /*!< HASH context swap registers, Address offset: 0x0F8-0x1C0 */ +} HASH_TypeDef; + +/** + * @brief HASH + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ + __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ + __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ +} RNG_TypeDef; + +/** + * @} + */ + +/** @addtogroup Peripheral_memory_map + * @{ + */ +#define FLASH_BASE ((uint32_t)0x08000000) /*!< FLASH(up to 1 MB) base address in the alias region */ +#define CCMDATARAM_BASE ((uint32_t)0x10000000) /*!< CCM(core coupled memory) data RAM(64 KB) base address in the alias region */ +#define SRAM1_BASE ((uint32_t)0x20000000) /*!< SRAM1(112 KB) base address in the alias region */ +#define SRAM2_BASE ((uint32_t)0x2001C000) /*!< SRAM2(16 KB) base address in the alias region */ +#define PERIPH_BASE ((uint32_t)0x40000000) /*!< Peripheral base address in the alias region */ +#define BKPSRAM_BASE ((uint32_t)0x40024000) /*!< Backup SRAM(4 KB) base address in the alias region */ +#define FSMC_R_BASE ((uint32_t)0xA0000000) /*!< FSMC registers base address */ + +#define CCMDATARAM_BB_BASE ((uint32_t)0x12000000) /*!< CCM(core coupled memory) data RAM(64 KB) base address in the bit-band region */ +#define SRAM1_BB_BASE ((uint32_t)0x22000000) /*!< SRAM1(112 KB) base address in the bit-band region */ +#define SRAM2_BB_BASE ((uint32_t)0x2201C000) /*!< SRAM2(16 KB) base address in the bit-band region */ +#define PERIPH_BB_BASE ((uint32_t)0x42000000) /*!< Peripheral base address in the bit-band region */ +#define BKPSRAM_BB_BASE ((uint32_t)0x42024000) /*!< Backup SRAM(4 KB) base address in the bit-band region */ + +/* Legacy defines */ +#define SRAM_BASE SRAM1_BASE +#define SRAM_BB_BASE SRAM1_BB_BASE + + +/*!< Peripheral memory map */ +#define APB1PERIPH_BASE PERIPH_BASE +#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000) +#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000) +#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000) + +/*!< APB1 peripherals */ +#define TIM2_BASE (APB1PERIPH_BASE + 0x0000) +#define TIM3_BASE (APB1PERIPH_BASE + 0x0400) +#define TIM4_BASE (APB1PERIPH_BASE + 0x0800) +#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TIM6_BASE (APB1PERIPH_BASE + 0x1000) +#define TIM7_BASE (APB1PERIPH_BASE + 0x1400) +#define TIM12_BASE (APB1PERIPH_BASE + 0x1800) +#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TIM14_BASE (APB1PERIPH_BASE + 0x2000) +#define RTC_BASE (APB1PERIPH_BASE + 0x2800) +#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00) +#define IWDG_BASE (APB1PERIPH_BASE + 0x3000) +#define I2S2ext_BASE (APB1PERIPH_BASE + 0x3400) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define I2S3ext_BASE (APB1PERIPH_BASE + 0x4000) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define PWR_BASE (APB1PERIPH_BASE + 0x7000) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) + +/*!< APB2 peripherals */ +#define TIM1_BASE (APB2PERIPH_BASE + 0x0000) +#define TIM8_BASE (APB2PERIPH_BASE + 0x0400) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200) +#define ADC_BASE (APB2PERIPH_BASE + 0x2300) +#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800) +#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00) +#define TIM9_BASE (APB2PERIPH_BASE + 0x4000) +#define TIM10_BASE (APB2PERIPH_BASE + 0x4400) +#define TIM11_BASE (APB2PERIPH_BASE + 0x4800) + +/*!< AHB1 peripherals */ +#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000) +#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400) +#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800) +#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00) +#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000) +#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400) +#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800) +#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00) +#define GPIOI_BASE (AHB1PERIPH_BASE + 0x2000) +#define CRC_BASE (AHB1PERIPH_BASE + 0x3000) +#define RCC_BASE (AHB1PERIPH_BASE + 0x3800) +#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00) +#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000) +#define DMA1_Stream0_BASE (DMA1_BASE + 0x010) +#define DMA1_Stream1_BASE (DMA1_BASE + 0x028) +#define DMA1_Stream2_BASE (DMA1_BASE + 0x040) +#define DMA1_Stream3_BASE (DMA1_BASE + 0x058) +#define DMA1_Stream4_BASE (DMA1_BASE + 0x070) +#define DMA1_Stream5_BASE (DMA1_BASE + 0x088) +#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0) +#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8) +#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400) +#define DMA2_Stream0_BASE (DMA2_BASE + 0x010) +#define DMA2_Stream1_BASE (DMA2_BASE + 0x028) +#define DMA2_Stream2_BASE (DMA2_BASE + 0x040) +#define DMA2_Stream3_BASE (DMA2_BASE + 0x058) +#define DMA2_Stream4_BASE (DMA2_BASE + 0x070) +#define DMA2_Stream5_BASE (DMA2_BASE + 0x088) +#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0) +#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8) +#define ETH_BASE (AHB1PERIPH_BASE + 0x8000) +#define ETH_MAC_BASE (ETH_BASE) +#define ETH_MMC_BASE (ETH_BASE + 0x0100) +#define ETH_PTP_BASE (ETH_BASE + 0x0700) +#define ETH_DMA_BASE (ETH_BASE + 0x1000) + +/*!< AHB2 peripherals */ +#define DCMI_BASE (AHB2PERIPH_BASE + 0x50000) +#define CRYP_BASE (AHB2PERIPH_BASE + 0x60000) +#define HASH_BASE (AHB2PERIPH_BASE + 0x60400) +#define RNG_BASE (AHB2PERIPH_BASE + 0x60800) + +/*!< FSMC Bankx registers base address */ +#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000) +#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104) +#define FSMC_Bank2_R_BASE (FSMC_R_BASE + 0x0060) +#define FSMC_Bank3_R_BASE (FSMC_R_BASE + 0x0080) +#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0) + +/* Debug MCU registers base address */ +#define DBGMCU_BASE ((uint32_t )0xE0042000) + +/** + * @} + */ + +/** @addtogroup Peripheral_declaration + * @{ + */ +#define TIM2 ((TIM_TypeDef *) TIM2_BASE) +#define TIM3 ((TIM_TypeDef *) TIM3_BASE) +#define TIM4 ((TIM_TypeDef *) TIM4_BASE) +#define TIM5 ((TIM_TypeDef *) TIM5_BASE) +#define TIM6 ((TIM_TypeDef *) TIM6_BASE) +#define TIM7 ((TIM_TypeDef *) TIM7_BASE) +#define TIM12 ((TIM_TypeDef *) TIM12_BASE) +#define TIM13 ((TIM_TypeDef *) TIM13_BASE) +#define TIM14 ((TIM_TypeDef *) TIM14_BASE) +#define RTC ((RTC_TypeDef *) RTC_BASE) +#define WWDG ((WWDG_TypeDef *) WWDG_BASE) +#define IWDG ((IWDG_TypeDef *) IWDG_BASE) +#define I2S2ext ((SPI_TypeDef *) I2S2ext_BASE) +#define SPI2 ((SPI_TypeDef *) SPI2_BASE) +#define SPI3 ((SPI_TypeDef *) SPI3_BASE) +#define I2S3ext ((SPI_TypeDef *) I2S3ext_BASE) +#define USART2 ((USART_TypeDef *) USART2_BASE) +#define USART3 ((USART_TypeDef *) USART3_BASE) +#define UART4 ((USART_TypeDef *) UART4_BASE) +#define UART5 ((USART_TypeDef *) UART5_BASE) +#define I2C1 ((I2C_TypeDef *) I2C1_BASE) +#define I2C2 ((I2C_TypeDef *) I2C2_BASE) +#define I2C3 ((I2C_TypeDef *) I2C3_BASE) +#define CAN1 ((CAN_TypeDef *) CAN1_BASE) +#define CAN2 ((CAN_TypeDef *) CAN2_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define DAC ((DAC_TypeDef *) DAC_BASE) +#define TIM1 ((TIM_TypeDef *) TIM1_BASE) +#define TIM8 ((TIM_TypeDef *) TIM8_BASE) +#define USART1 ((USART_TypeDef *) USART1_BASE) +#define USART6 ((USART_TypeDef *) USART6_BASE) +#define ADC ((ADC_Common_TypeDef *) ADC_BASE) +#define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC2 ((ADC_TypeDef *) ADC2_BASE) +#define ADC3 ((ADC_TypeDef *) ADC3_BASE) +#define SDIO ((SDIO_TypeDef *) SDIO_BASE) +#define SPI1 ((SPI_TypeDef *) SPI1_BASE) +#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) +#define EXTI ((EXTI_TypeDef *) EXTI_BASE) +#define TIM9 ((TIM_TypeDef *) TIM9_BASE) +#define TIM10 ((TIM_TypeDef *) TIM10_BASE) +#define TIM11 ((TIM_TypeDef *) TIM11_BASE) +#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) +#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) +#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) +#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) +#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) +#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) +#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) +#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) +#define GPIOI ((GPIO_TypeDef *) GPIOI_BASE) +#define CRC ((CRC_TypeDef *) CRC_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define DMA1 ((DMA_TypeDef *) DMA1_BASE) +#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) +#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) +#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) +#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) +#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) +#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) +#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) +#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) +#define DMA2 ((DMA_TypeDef *) DMA2_BASE) +#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) +#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) +#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) +#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) +#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) +#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) +#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) +#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) +#define ETH ((ETH_TypeDef *) ETH_BASE) +#define DCMI ((DCMI_TypeDef *) DCMI_BASE) +#define CRYP ((CRYP_TypeDef *) CRYP_BASE) +#define HASH ((HASH_TypeDef *) HASH_BASE) +#define RNG ((RNG_TypeDef *) RNG_BASE) +#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) +#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) +#define FSMC_Bank2 ((FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE) +#define FSMC_Bank3 ((FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE) +#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + + /** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* Analog to Digital Converter */ +/* */ +/******************************************************************************/ +/******************** Bit definition for ADC_SR register ********************/ +#define ADC_SR_AWD ((uint8_t)0x01) /*!
© COPYRIGHT 2011 STMicroelectronics
+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f4xx_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32F4XX_H +#define __SYSTEM_STM32F4XX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup STM32F4xx_System_Includes + * @{ + */ + +/** + * @} + */ + + +/** @addtogroup STM32F4xx_System_Exported_types + * @{ + */ + +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ + + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32F4XX_H */ + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/system_stm32f4xx.c b/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/system_stm32f4xx.c new file mode 100644 index 000000000..bb7776d4b --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/system_stm32f4xx.c @@ -0,0 +1,553 @@ +/** + ****************************************************************************** + * @file system_stm32f4xx.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. + * This file contains the system clock configuration for STM32F4xx devices, + * and is generated by the clock configuration tool + * stm32f4xx_Clock_Configuration_V1.0.0.xls + * + * 1. This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier + * and Divider factors, AHB/APBx prescalers and Flash settings), + * depending on the configuration made in the clock xls tool. + * This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32f4xx.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * 2. After each device reset the HSI (16 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to + * configure the system clock before to branch to main program. + * + * 3. If the system clock source selected by user fails to startup, the SystemInit() + * function will do nothing and HSI still used as system clock source. User can + * add some code to deal with this issue inside the SetSysClock() function. + * + * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define + * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or + * through PLL, and you are using different crystal you have to adapt the HSE + * value to your own configuration. + * + * 5. This file configures the system clock as follows: + *============================================================================= + *============================================================================= + * Supported STM32F4xx device revision | Rev A + *----------------------------------------------------------------------------- + * System Clock source | PLL (HSE) + *----------------------------------------------------------------------------- + * SYSCLK(Hz) | 168000000 + *----------------------------------------------------------------------------- + * HCLK(Hz) | 168000000 + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 4 + *----------------------------------------------------------------------------- + * APB2 Prescaler | 2 + *----------------------------------------------------------------------------- + * HSE Frequency(Hz) | 8000000 + *----------------------------------------------------------------------------- + * PLL_M | 10 + *----------------------------------------------------------------------------- + * PLL_N | 420 + *----------------------------------------------------------------------------- + * PLL_P | 2 + *----------------------------------------------------------------------------- + * PLL_Q | 7 + *----------------------------------------------------------------------------- + * PLLI2S_N | NA + *----------------------------------------------------------------------------- + * PLLI2S_R | NA + *----------------------------------------------------------------------------- + * I2S input clock | NA + *----------------------------------------------------------------------------- + * VDD(V) | 3.3 + *----------------------------------------------------------------------------- + * Main regulator output voltage | Scale1 mode + *----------------------------------------------------------------------------- + * Flash Latency(WS) | 5 + *----------------------------------------------------------------------------- + * Prefetch Buffer | OFF + *----------------------------------------------------------------------------- + * Instruction cache | ON + *----------------------------------------------------------------------------- + * Data cache | ON + *----------------------------------------------------------------------------- + * Require 48MHz for USB OTG FS, | Enabled + * SDIO and RNG clock | + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f4xx_system + * @{ + */ + +/** @addtogroup STM32F4xx_System_Private_Includes + * @{ + */ + +#include "stm32f4xx.h" + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Defines + * @{ + */ + +/************************* Miscellaneous Configuration ************************/ +/*!< Uncomment the following line if you need to use external SRAM mounted + on STM324xG_EVAL board as data memory */ +/* #define DATA_IN_ExtSRAM */ + +/*!< Uncomment the following line if you need to relocate your vector Table in + Internal SRAM. */ +/* #define VECT_TAB_SRAM */ +#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ +/******************************************************************************/ + +/************************* PLL Parameters *************************************/ +/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */ +#define PLL_M 10 +#define PLL_N 420 + +/* SYSCLK = PLL_VCO / PLL_P */ +#define PLL_P 2 + +/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */ +#define PLL_Q 7 + +/******************************************************************************/ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Variables + * @{ + */ + + uint32_t SystemCoreClock = 168000000; + + __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes + * @{ + */ + +static void SetSysClock(void); +#ifdef DATA_IN_ExtSRAM + static void SystemInit_ExtMemCtl(void); +#endif /* DATA_IN_ExtSRAM */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system + * Initialize the Embedded Flash Interface, the PLL and update the + * SystemFrequency variable. + * @param None + * @retval None + */ +void SystemInit(void) +{ + /* FPU settings ------------------------------------------------------------*/ + #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ + #endif + + /* Reset the RCC clock configuration to the default reset state ------------*/ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset CFGR register */ + RCC->CFGR = 0x00000000; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset PLLCFGR register */ + RCC->PLLCFGR = 0x24003010; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Disable all interrupts */ + RCC->CIR = 0x00000000; + +#ifdef DATA_IN_ExtSRAM + SystemInit_ExtMemCtl(); +#endif /* DATA_IN_ExtSRAM */ + + /* Configure the System clock source, PLL Multiplier and Divider factors, + AHB/APBx prescalers and Flash settings ----------------------------------*/ + SetSysClock(); + + /* Configure the Vector Table location add offset address ------------------*/ +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ +#endif +} + +/** + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock (HCLK), it can + * be used by the user application to setup the SysTick timer or configure + * other parameters. + * + * @note Each time the core clock (HCLK) changes, this function must be called + * to update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value + * 25 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @param None + * @retval None + */ +void SystemCoreClockUpdate(void) +{ + uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* HSI used as system clock source */ + SystemCoreClock = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock source */ + SystemCoreClock = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock source */ + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N + SYSCLK = PLL_VCO / PLL_P + */ + pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22; + pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; + + if (pllsource != 0) + { + /* HSE used as PLL clock source */ + pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + } + else + { + /* HSI used as PLL clock source */ + pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + } + + pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; + SystemCoreClock = pllvco/pllp; + break; + default: + SystemCoreClock = HSI_VALUE; + break; + } + /* Compute HCLK frequency --------------------------------------------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK frequency */ + SystemCoreClock >>= tmp; +} + +/** + * @brief Configures the System clock source, PLL Multiplier and Divider factors, + * AHB/APBx prescalers and Flash settings + * @Note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). + * @param None + * @retval None + */ +static void SetSysClock(void) +{ +/******************************************************************************/ +/* PLL (clocked by HSE) used as System clock source */ +/******************************************************************************/ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Select regulator voltage output Scale 1 mode, System frequency up to 168 MHz */ + RCC->APB1ENR |= RCC_APB1ENR_PWREN; + PWR->CR |= PWR_CR_VOS; + + /* HCLK = SYSCLK / 1*/ + RCC->CFGR |= RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK / 2*/ + RCC->CFGR |= RCC_CFGR_PPRE2_DIV2; + + /* PCLK1 = HCLK / 4*/ + RCC->CFGR |= RCC_CFGR_PPRE1_DIV4; + + /* Configure the main PLL */ + RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | + (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24); + + /* Enable the main PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till the main PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Configure Flash prefetch, Instruction cache, Data cache and wait state */ + FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS; + + /* Select the main PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= RCC_CFGR_SW_PLL; + + /* Wait till the main PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL); + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + } + +} + +/** + * @brief Setup the external memory controller. Called in startup_stm32f4xx.s + * before jump to __main + * @param None + * @retval None + */ +#ifdef DATA_IN_ExtSRAM +/** + * @brief Setup the external memory controller. + * Called in startup_stm32f4xx.s before jump to main. + * This function configures the external SRAM mounted on STM324xG_EVAL board + * This SRAM will be used as program data memory (including heap and stack). + * @param None + * @retval None + */ +void SystemInit_ExtMemCtl(void) +{ +/*-- GPIOs Configuration -----------------------------------------------------*/ +/* + +-------------------+--------------------+------------------+------------------+ + + SRAM pins assignment + + +-------------------+--------------------+------------------+------------------+ + | PD0 <-> FSMC_D2 | PE0 <-> FSMC_NBL0 | PF0 <-> FSMC_A0 | PG0 <-> FSMC_A10 | + | PD1 <-> FSMC_D3 | PE1 <-> FSMC_NBL1 | PF1 <-> FSMC_A1 | PG1 <-> FSMC_A11 | + | PD4 <-> FSMC_NOE | PE3 <-> FSMC_A19 | PF2 <-> FSMC_A2 | PG2 <-> FSMC_A12 | + | PD5 <-> FSMC_NWE | PE4 <-> FSMC_A20 | PF3 <-> FSMC_A3 | PG3 <-> FSMC_A13 | + | PD8 <-> FSMC_D13 | PE7 <-> FSMC_D4 | PF4 <-> FSMC_A4 | PG4 <-> FSMC_A14 | + | PD9 <-> FSMC_D14 | PE8 <-> FSMC_D5 | PF5 <-> FSMC_A5 | PG5 <-> FSMC_A15 | + | PD10 <-> FSMC_D15 | PE9 <-> FSMC_D6 | PF12 <-> FSMC_A6 | PG9 <-> FSMC_NE2 | + | PD11 <-> FSMC_A16 | PE10 <-> FSMC_D7 | PF13 <-> FSMC_A7 |------------------+ + | PD12 <-> FSMC_A17 | PE11 <-> FSMC_D8 | PF14 <-> FSMC_A8 | + | PD13 <-> FSMC_A18 | PE12 <-> FSMC_D9 | PF15 <-> FSMC_A9 | + | PD14 <-> FSMC_D0 | PE13 <-> FSMC_D10 |------------------+ + | PD15 <-> FSMC_D1 | PE14 <-> FSMC_D11 | + | | PE15 <-> FSMC_D12 | + +-------------------+--------------------+ +*/ + /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */ + RCC->AHB1ENR = 0x00000078; + + /* Connect PDx pins to FSMC Alternate function */ + GPIOD->AFR[0] = 0x00cc00cc; + GPIOD->AFR[1] = 0xcc0ccccc; + /* Configure PDx pins in Alternate function mode */ + GPIOD->MODER = 0xaaaa0a0a; + /* Configure PDx pins speed to 100 MHz */ + GPIOD->OSPEEDR = 0xffff0f0f; + /* Configure PDx pins Output type to push-pull */ + GPIOD->OTYPER = 0x00000000; + /* No pull-up, pull-down for PDx pins */ + GPIOD->PUPDR = 0x00000000; + + /* Connect PEx pins to FSMC Alternate function */ + GPIOE->AFR[0] = 0xc00cc0cc; + GPIOE->AFR[1] = 0xcccccccc; + /* Configure PEx pins in Alternate function mode */ + GPIOE->MODER = 0xaaaa828a; + /* Configure PEx pins speed to 100 MHz */ + GPIOE->OSPEEDR = 0xffffc3cf; + /* Configure PEx pins Output type to push-pull */ + GPIOE->OTYPER = 0x00000000; + /* No pull-up, pull-down for PEx pins */ + GPIOE->PUPDR = 0x00000000; + + /* Connect PFx pins to FSMC Alternate function */ + GPIOF->AFR[0] = 0x00cccccc; + GPIOF->AFR[1] = 0xcccc0000; + /* Configure PFx pins in Alternate function mode */ + GPIOF->MODER = 0xaa000aaa; + /* Configure PFx pins speed to 100 MHz */ + GPIOF->OSPEEDR = 0xff000fff; + /* Configure PFx pins Output type to push-pull */ + GPIOF->OTYPER = 0x00000000; + /* No pull-up, pull-down for PFx pins */ + GPIOF->PUPDR = 0x00000000; + + /* Connect PGx pins to FSMC Alternate function */ + GPIOG->AFR[0] = 0x00cccccc; + GPIOG->AFR[1] = 0x000000c0; + /* Configure PGx pins in Alternate function mode */ + GPIOG->MODER = 0x00080aaa; + /* Configure PGx pins speed to 100 MHz */ + GPIOG->OSPEEDR = 0x000c0fff; + /* Configure PGx pins Output type to push-pull */ + GPIOG->OTYPER = 0x00000000; + /* No pull-up, pull-down for PGx pins */ + GPIOG->PUPDR = 0x00000000; + +/*-- FSMC Configuration ------------------------------------------------------*/ + /* Enable the FSMC interface clock */ + RCC->AHB3ENR = 0x00000001; + + /* Configure and enable Bank1_SRAM2 */ + FSMC_Bank1->BTCR[2] = 0x00001015; + FSMC_Bank1->BTCR[3] = 0x00010603; + FSMC_Bank1E->BWTR[2] = 0x0fffffff; +/* + Bank1_SRAM2 is configured as follow: + + p.FSMC_AddressSetupTime = 3; + p.FSMC_AddressHoldTime = 0; + p.FSMC_DataSetupTime = 6; + p.FSMC_BusTurnAroundDuration = 1; + p.FSMC_CLKDivision = 0; + p.FSMC_DataLatency = 0; + p.FSMC_AccessMode = FSMC_AccessMode_A; + + FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2; + FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable; + FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_PSRAM; + FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b; + FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; + FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; + FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable; + FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable; + FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p; + FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p; +*/ + +} +#endif /* DATA_IN_ExtSRAM */ + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/port.c b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/port.c new file mode 100644 index 000000000..a235531d1 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/port.c @@ -0,0 +1,364 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/*----------------------------------------------------------- + * Implementation of functions defined in portable.h for the ARM Cortex-M4F port. + *----------------------------------------------------------*/ + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" + +/* For backward compatibility, ensure configKERNEL_INTERRUPT_PRIORITY is +defined. The value should also ensure backward compatibility. +FreeRTOS.org versions prior to V4.4.0 did not include this definition. */ +#ifndef configKERNEL_INTERRUPT_PRIORITY + #define configKERNEL_INTERRUPT_PRIORITY 255 +#endif + +/* Constants required to manipulate the NVIC. */ +#define portNVIC_SYSTICK_CTRL ( ( volatile unsigned long *) 0xe000e010 ) +#define portNVIC_SYSTICK_LOAD ( ( volatile unsigned long *) 0xe000e014 ) +#define portNVIC_INT_CTRL ( ( volatile unsigned long *) 0xe000ed04 ) +#define portNVIC_SYSPRI2 ( ( volatile unsigned long *) 0xe000ed20 ) +#define portNVIC_SYSTICK_CLK 0x00000004 +#define portNVIC_SYSTICK_INT 0x00000002 +#define portNVIC_SYSTICK_ENABLE 0x00000001 +#define portNVIC_PENDSVSET 0x10000000 +#define portNVIC_PENDSV_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 16 ) +#define portNVIC_SYSTICK_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 24 ) + +/* Constants required to set up the initial stack. */ +#define portINITIAL_XPSR ( 0x01000000 ) +#define portINITIAL_EXC_RETURN ( 0xfffffffd ) /* return to thread mode, basic stack frame, FPU not used */ + +/* The priority used by the kernel is assigned to a variable to make access +from inline assembler easier. */ +const unsigned long ulKernelPriority = configKERNEL_INTERRUPT_PRIORITY; + +/* Each task maintains its own interrupt status in the critical nesting +variable. */ +static unsigned portBASE_TYPE uxCriticalNesting = 0xaaaaaaaa; + +/* + * Setup the timer to generate the tick interrupts. + */ +static void prvSetupTimerInterrupt( void ); + +/* + * Exception handlers. + */ +void xPortPendSVHandler( void ) __attribute__ (( naked )) __attribute__((no_instrument_function)); +void xPortSysTickHandler( void ) __attribute__((no_instrument_function)); +void vPortSVCHandler( void ) __attribute__ (( naked )) __attribute__((no_instrument_function)); + +/* + * Start first task is a separate function so it can be tested in isolation. + */ +void vPortStartFirstTask( void ) __attribute__ (( naked )) __attribute__((no_instrument_function)); + +/*-----------------------------------------------------------*/ + +/* + * See header file for description. + */ +portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, portSTACK_TYPE *pxStartOfStack, pdTASK_CODE pxCode, void *pvParameters ) +{ + /* + * Create a basic stack frame plus manual save area as would be + * saved by xPortPendSVHandler on entry, for a task that has not + * used the FPU. + * + * XXX if pxTopOfStack is not 8-byte aligned and the CPU is configured + * to adjust the stack to 8-byte boundaries, is this code safe? + */ + + /* automatically stacked state */ + *--pxTopOfStack = portINITIAL_XPSR; /* xPSR */ + *--pxTopOfStack = ( portSTACK_TYPE ) pxCode; /* pc (thread entrypoint) */ + *--pxTopOfStack = 0; /* lr */ + *--pxTopOfStack = 0; /* r12 */ + *--pxTopOfStack = 0; /* r3 */ + *--pxTopOfStack = 0; /* r2 */ + *--pxTopOfStack = 0; /* r1 */ + *--pxTopOfStack = ( portSTACK_TYPE ) pvParameters; /* r0 (void * passed to thread) */ + + /* manually stacked state */ + *--pxTopOfStack = 0; /* r11 */ + *--pxTopOfStack = ( portSTACK_TYPE ) pxStartOfStack;/* r10 (stack limit) */ + *--pxTopOfStack = 0; /* r9 */ + *--pxTopOfStack = 0; /* r8 */ + *--pxTopOfStack = 0; /* r7 */ + *--pxTopOfStack = 0; /* r6 */ + *--pxTopOfStack = 0; /* r5 */ + *--pxTopOfStack = 0; /* r4 */ + + /* exception return code */ + *--pxTopOfStack = portINITIAL_EXC_RETURN; + + return pxTopOfStack; +} +/*-----------------------------------------------------------*/ + +void vPortSVCHandler( void ) +{ + /* + * Start the first task. + */ + __asm volatile ( + " b context_restore \n" /* jump directly to the context restore path in xPortPendSVHandler */ + ); +} +/*-----------------------------------------------------------*/ + +void vPortStartFirstTask( void ) +{ + __asm volatile( + " ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */ + " ldr r0, [r0] \n" + " ldr r0, [r0] \n" + " msr msp, r0 \n" /* Set the msp back to the start of the stack. */ + " cpsie i \n" /* Globally enable interrupts. */ + " svc 0 \n" /* System call to start first task. */ + " nop \n" + ); +} +/*-----------------------------------------------------------*/ + +/* + * See header file for description. + */ +portBASE_TYPE xPortStartScheduler( void ) +{ + /* Make PendSV, CallSV and SysTick the same priroity as the kernel. */ + *(portNVIC_SYSPRI2) |= portNVIC_PENDSV_PRI; + *(portNVIC_SYSPRI2) |= portNVIC_SYSTICK_PRI; + + /* Start the timer that generates the tick ISR. Interrupts are disabled + here already. */ + prvSetupTimerInterrupt(); + + /* Initialise the critical nesting count ready for the first task. */ + uxCriticalNesting = 0; + + /* Start the first task. */ + vPortStartFirstTask(); + + /* Should not get here! */ + return 0; +} +/*-----------------------------------------------------------*/ + +void vPortEndScheduler( void ) +{ + /* It is unlikely that the CM3 port will require this function as there + is nothing to return to. */ +} +/*-----------------------------------------------------------*/ + +void vPortYieldFromISR( void ) +{ + /* Set a PendSV to request a context switch. */ + *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; +} +/*-----------------------------------------------------------*/ + +void vPortEnterCritical( void ) +{ + portDISABLE_INTERRUPTS(); + uxCriticalNesting++; +} +/*-----------------------------------------------------------*/ + +void vPortExitCritical( void ) +{ + uxCriticalNesting--; + if( uxCriticalNesting == 0 ) + { + portENABLE_INTERRUPTS(); + } +} +/*-----------------------------------------------------------*/ + +void xPortPendSVHandler( void ) +{ + /* This is a naked function. */ + /* + * XXX todo - check r0 against r10 for stack overflow detection? + */ + + /* + * Handle a PendSV exception, triggered by vPortYieldFromISR (etc). + * + * FP state saving is conditional on bit 4 of the EXC_RETURN value (lr). + * If the bit is 1, the frame saved by entry is a basic frame and FP + * state should not be saved. If the bit is 0, the frame saved is + * an extended frame and the high FP registers also need to be saved. + * + * Since the EXC_RETURN value is specific to the task, it is the last + * item stacked and the first to be popped when restoring a task's + * context. + */ + __asm volatile + ( + " mrs r0, psp \n" /* get the program stack pointer (base of automatic frame) in r0 */ + " \n" + " tst lr, 0x10 \n" /* check for extended stack frame */ + " bne 1f \n" /* skip FP register save if only a basic frame */ + " vstmdb r0!, {s16-s31} \n" /* stack the remaining FP registers */ + "1: \n" + " stmdb r0!, {r4-r11} \n" /* stack the remaining GP registers */ + " stmdb r0!, {lr} \n" /* stack the exception return code for use when resuming */ + " \n" + " ldr r3, 3f \n" /* pointer to pointer to current TCB in r3 */ + " ldr r2, [r3] \n" /* pointer to current TCB in r2 */ + " str r0, [r2] \n" /* save stack (context) pointer in the first member of the TCB */ + " \n" + " mov r0, %0 \n" /* switch to syscall interrupt priority */ + " msr basepri, r0 \n" + " \n" + " bl vTaskSwitchContext \n" /* handle the context switch call */ + " \n" + "context_restore: \n" /* branch target for vPortSVCHandler */ + " mov r0, #0 \n" /* reset to priority 0 */ + " msr basepri, r0 \n" + " \n" + " ldr r3, 3f \n" /* pointer to pointer to current TCB in r3 */ + " ldr r2, [r3] \n" /* pointer to current TCB in r2 */ + " ldr r0, [r2] \n" /* restore stack (context) pointer from the first member of the TCB */ + " \n" + " ldmia r0!, {lr} \n" /* pop the exception return code */ + " ldmia r0!, {r4-r11} \n" /* pop the manually-stacked GP registers */ + " tst lr, 0x10 \n" /* check for extended stack frame */ + " bne 2f \n" /* skip FP register pop if only a basic frame */ + " vldmia r0!, {s16-s31} \n" /* pop the manually-stacked FP registers */ + "2: \n" + " msr psp, r0 \n" /* reload the program stack pointer */ + " bx lr \n" /* perform an exception return as per the encoding in lr */ + " \n" + " .align 2 \n" + "3: .word pxCurrentTCB \n" + ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY) + ); +} +/*-----------------------------------------------------------*/ + +void xPortSysTickHandler( void ) +{ +unsigned long ulDummy; + + /* If using preemption, also force a context switch. */ + #if configUSE_PREEMPTION == 1 + *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; + #endif + + ulDummy = portSET_INTERRUPT_MASK_FROM_ISR(); + { + vTaskIncrementTick(); + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( ulDummy ); +} +/*-----------------------------------------------------------*/ + +/* + * Setup the systick timer to generate the tick interrupts at the required + * frequency. + */ +void prvSetupTimerInterrupt( void ) +{ + /* Configure SysTick to interrupt at the requested rate. */ + *(portNVIC_SYSTICK_LOAD) = ( configCPU_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL; + *(portNVIC_SYSTICK_CTRL) = portNVIC_SYSTICK_CLK | portNVIC_SYSTICK_INT | portNVIC_SYSTICK_ENABLE; +} +/*-----------------------------------------------------------*/ + +void __cyg_profile_func_enter(void *func, void *caller) __attribute__((naked, no_instrument_function)); +void __cyg_profile_func_exit(void *func, void *caller) __attribute__((naked, no_instrument_function)); +void __stack_overflow_trap(void) __attribute__((naked, no_instrument_function)); + +void +__stack_trap(void) +{ + /* if we get here, the stack has overflowed */ + asm ( "b ."); +} + +void +__cyg_profile_func_enter(void *func, void *caller) +{ + asm volatile ( + " mrs r2, ipsr \n" /* Check whether we are in interrupt mode */ + " cmp r2, #0 \n" /* since we don't switch r10 on interrupt entry, we */ + " bne 2f \n" /* can't detect overflow of the interrupt stack. */ + " \n" + " sub r2, sp, #68 \n" /* compute stack pointer as though we just stacked a full frame */ + " mrs r1, control \n" /* Test CONTROL.FPCA to see whether we also need room for the FP */ + " tst r1, #4 \n" /* context. */ + " beq 1f \n" + " sub r2, r2, #136 \n" /* subtract FP context frame size */ + "1: \n" + " cmp r2, r10 \n" /* compare stack with limit */ + " bgt 2f \n" /* stack is above limit and thus OK */ + " b __stack_trap \n" + "2: \n" + " bx lr \n" + ); +} + +void +__cyg_profile_func_exit(void *func, void *caller) +{ + asm volatile("bx lr"); +} + + diff --git a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/portmacro.h b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/portmacro.h new file mode 100644 index 000000000..f346841af --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/portmacro.h @@ -0,0 +1,156 @@ +/* + FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef PORTMACRO_H +#define PORTMACRO_H + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * Port specific definitions. + * + * The settings in this file configure FreeRTOS correctly for the + * given hardware and compiler. + * + * These settings should not be altered. + *----------------------------------------------------------- + */ + +/* Type definitions. */ +#define portCHAR char +#define portFLOAT float +#define portDOUBLE double +#define portLONG long +#define portSHORT short +#define portSTACK_TYPE unsigned portLONG +#define portBASE_TYPE long + +#if( configUSE_16_BIT_TICKS == 1 ) + typedef unsigned portSHORT portTickType; + #define portMAX_DELAY ( portTickType ) 0xffff +#else + typedef unsigned portLONG portTickType; + #define portMAX_DELAY ( portTickType ) 0xffffffff +#endif +/*-----------------------------------------------------------*/ + +/* Architecture specifics. */ +#define portSTACK_GROWTH ( -1 ) +#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) +#define portBYTE_ALIGNMENT 8 +/*-----------------------------------------------------------*/ + + +/* Scheduler utilities. */ +extern void vPortYieldFromISR( void ); + +#define portYIELD() vPortYieldFromISR() + +#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() +/*-----------------------------------------------------------*/ + + +/* Critical section management. */ + +/* + * Set basepri to portMAX_SYSCALL_INTERRUPT_PRIORITY without effecting other + * registers. r0 is clobbered. + */ +#define portSET_INTERRUPT_MASK() \ + __asm volatile \ + ( \ + " mov r0, %0 \n" \ + " msr basepri, r0 \n" \ + ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY):"r0" \ + ) + +/* + * Set basepri back to 0 without effective other registers. + * r0 is clobbered. + */ +#define portCLEAR_INTERRUPT_MASK() \ + __asm volatile \ + ( \ + " mov r0, #0 \n" \ + " msr basepri, r0 \n" \ + :::"r0" \ + ) + +#define portSET_INTERRUPT_MASK_FROM_ISR() 0;portSET_INTERRUPT_MASK() +#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) portCLEAR_INTERRUPT_MASK();(void)x + + +extern void vPortEnterCritical( void ); +extern void vPortExitCritical( void ); + +#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() +#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() +#define portENTER_CRITICAL() vPortEnterCritical() +#define portEXIT_CRITICAL() vPortExitCritical() +/*-----------------------------------------------------------*/ + +/* Task function macros as described on the FreeRTOS.org WEB site. */ +#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) +#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) + +#define portNOP() + +#ifdef __cplusplus +} +#endif + +#endif /* PORTMACRO_H */ + diff --git a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/MemMang/heap_1.c b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/MemMang/heap_1.c new file mode 100644 index 000000000..166c897a7 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/MemMang/heap_1.c @@ -0,0 +1,160 @@ +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +/* + * The simplest possible implementation of pvPortMalloc(). Note that this + * implementation does NOT allow allocated memory to be freed again. + * + * See heap_2.c and heap_3.c for alternative implementations, and the memory + * management pages of http://www.FreeRTOS.org for more information. + */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* Allocate the memory for the heap. The struct is used to force byte +alignment without using any non-portable code. */ +static union xRTOS_HEAP +{ + #if portBYTE_ALIGNMENT == 8 + volatile portDOUBLE dDummy; + #else + volatile unsigned long ulDummy; + #endif + unsigned char ucHeap[ configTOTAL_HEAP_SIZE ]; +} xHeap __attribute__ ((section (".heap"))); + +static size_t xNextFreeByte = ( size_t ) 0; +static size_t currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE; + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +void *pvReturn = NULL; + + /* Ensure that blocks are always aligned to the required number of bytes. */ + #if portBYTE_ALIGNMENT != 1 + if( xWantedSize & portBYTE_ALIGNMENT_MASK ) + { + /* Byte alignment required. */ + xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); + } + #endif + + vTaskSuspendAll(); + { + /* Check there is enough room left for the allocation. */ + if( ( ( xNextFreeByte + xWantedSize ) < currentTOTAL_HEAP_SIZE ) && + ( ( xNextFreeByte + xWantedSize ) > xNextFreeByte ) )/* Check for overflow. */ + { + /* Return the next free byte then increment the index past this + block. */ + pvReturn = &( xHeap.ucHeap[ xNextFreeByte ] ); + xNextFreeByte += xWantedSize; + } + } + xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ + /* Memory cannot be freed using this scheme. See heap_2.c and heap_3.c + for alternative implementations, and the memory management pages of + http://www.FreeRTOS.org for more information. */ + ( void ) pv; +} +/*-----------------------------------------------------------*/ + +void vPortInitialiseBlocks( void ) +{ + /* Only required when static memory is not cleared. */ + xNextFreeByte = ( size_t ) 0; +} +/*-----------------------------------------------------------*/ + +size_t xPortGetFreeHeapSize( void ) +{ + return ( currentTOTAL_HEAP_SIZE - xNextFreeByte ); +} +/*-----------------------------------------------------------*/ + +void xPortIncreaseHeapSize( size_t bytes ) +{ + vTaskSuspendAll(); + currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE + bytes; + xTaskResumeAll(); +} +/*-----------------------------------------------------------*/ diff --git a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/MemMang/heap_2.c b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/MemMang/heap_2.c new file mode 100644 index 000000000..1fbd1831b --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/MemMang/heap_2.c @@ -0,0 +1,318 @@ +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/* + * A sample implementation of pvPortMalloc() and vPortFree() that permits + * allocated blocks to be freed, but does not combine adjacent free blocks + * into a single larger block. + * + * See heap_1.c and heap_3.c for alternative implementations, and the memory + * management pages of http://www.FreeRTOS.org for more information. + */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* Allocate the memory for the heap. The struct is used to force byte +alignment without using any non-portable code. */ +static union xRTOS_HEAP +{ + #if portBYTE_ALIGNMENT == 8 + volatile portDOUBLE dDummy; + #else + volatile unsigned long ulDummy; + #endif + unsigned char ucHeap[ configTOTAL_HEAP_SIZE ]; +} xHeap __attribute__ ((section (".heap"))); + +/* Define the linked list structure. This is used to link free blocks in order +of their size. */ +typedef struct A_BLOCK_LINK +{ + struct A_BLOCK_LINK *pxNextFreeBlock; /*<< The next free block in the list. */ + size_t xBlockSize; /*<< The size of the free block. */ +} xBlockLink; + + +static const unsigned short heapSTRUCT_SIZE = ( sizeof( xBlockLink ) + portBYTE_ALIGNMENT - ( sizeof( xBlockLink ) % portBYTE_ALIGNMENT ) ); +#define heapMINIMUM_BLOCK_SIZE ( ( size_t ) ( heapSTRUCT_SIZE * 2 ) ) + +/* Create a couple of list links to mark the start and end of the list. */ +static xBlockLink xStart, xEnd; + +/* Markers in the heap segment */ +extern char _sheap, _eheap; +extern char _init_stack_top, _init_stack_end; + +static size_t currentTOTAL_HEAP_SIZE; + +/* Keeps track of the number of free bytes remaining, but says nothing about +fragmentation. */ +static size_t xFreeBytesRemaining; + +/* STATIC FUNCTIONS ARE DEFINED AS MACROS TO MINIMIZE THE FUNCTION CALL DEPTH. */ + +/* + * Insert a block into the list of free blocks - which is ordered by size of + * the block. Small blocks at the start of the list and large blocks at the end + * of the list. + */ +#define prvInsertBlockIntoFreeList( pxBlockToInsert ) \ +{ \ +xBlockLink *pxIterator; \ +size_t xBlockSize; \ + \ + xBlockSize = pxBlockToInsert->xBlockSize; \ + \ + /* Iterate through the list until a block is found that has a larger size */ \ + /* than the block we are inserting. */ \ + for( pxIterator = &xStart; pxIterator->pxNextFreeBlock->xBlockSize < xBlockSize; pxIterator = pxIterator->pxNextFreeBlock ) \ + { \ + /* There is nothing to do here - just iterate to the correct position. */ \ + } \ + \ + /* Update the list to include the block being inserted in the correct */ \ + /* position. */ \ + pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock; \ + pxIterator->pxNextFreeBlock = pxBlockToInsert; \ +} +/*-----------------------------------------------------------*/ + +#define prvHeapInit() \ +{ \ +xBlockLink *pxFirstFreeBlock; \ + \ + currentTOTAL_HEAP_SIZE = &_eheap - &_sheap; \ + xFreeBytesRemaining = currentTOTAL_HEAP_SIZE; \ + \ + /* xStart is used to hold a pointer to the first item in the list of free */ \ + /* blocks. The void cast is used to prevent compiler warnings. */ \ + xStart.pxNextFreeBlock = ( void * ) xHeap.ucHeap; \ + xStart.xBlockSize = ( size_t ) 0; \ + \ + /* xEnd is used to mark the end of the list of free blocks. */ \ + xEnd.xBlockSize = currentTOTAL_HEAP_SIZE; \ + xEnd.pxNextFreeBlock = NULL; \ + \ + /* To start with there is a single free block that is sized to take up the \ + entire heap space. */ \ + pxFirstFreeBlock = ( void * ) xHeap.ucHeap; \ + pxFirstFreeBlock->xBlockSize = currentTOTAL_HEAP_SIZE; \ + pxFirstFreeBlock->pxNextFreeBlock = &xEnd; \ +} +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +xBlockLink *pxBlock, *pxPreviousBlock, *pxNewBlockLink; +static portBASE_TYPE xHeapHasBeenInitialised = pdFALSE; +void *pvReturn = NULL; + + vTaskSuspendAll(); + { + /* If this is the first call to malloc then the heap will require + initialisation to setup the list of free blocks. */ + if( xHeapHasBeenInitialised == pdFALSE ) + { + prvHeapInit(); + xHeapHasBeenInitialised = pdTRUE; + } + + /* The wanted size is increased so it can contain a xBlockLink + structure in addition to the requested amount of bytes. */ + if( xWantedSize > 0 ) + { + xWantedSize += heapSTRUCT_SIZE; + + /* Ensure that blocks are always aligned to the required number of bytes. */ + if( xWantedSize & portBYTE_ALIGNMENT_MASK ) + { + /* Byte alignment required. */ + xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); + } + } + + if( ( xWantedSize > 0 ) && ( xWantedSize < currentTOTAL_HEAP_SIZE ) ) + { + /* Blocks are stored in byte order - traverse the list from the start + (smallest) block until one of adequate size is found. */ + pxPreviousBlock = &xStart; + pxBlock = xStart.pxNextFreeBlock; + while( ( pxBlock->xBlockSize < xWantedSize ) && ( pxBlock->pxNextFreeBlock ) ) + { + pxPreviousBlock = pxBlock; + pxBlock = pxBlock->pxNextFreeBlock; + } + + /* If we found the end marker then a block of adequate size was not found. */ + if( pxBlock != &xEnd ) + { + /* Return the memory space - jumping over the xBlockLink structure + at its start. */ + pvReturn = ( void * ) ( ( ( unsigned char * ) pxPreviousBlock->pxNextFreeBlock ) + heapSTRUCT_SIZE ); + + /* This block is being returned for use so must be taken our of the + list of free blocks. */ + pxPreviousBlock->pxNextFreeBlock = pxBlock->pxNextFreeBlock; + + /* If the block is larger than required it can be split into two. */ + if( ( pxBlock->xBlockSize - xWantedSize ) > heapMINIMUM_BLOCK_SIZE ) + { + /* This block is to be split into two. Create a new block + following the number of bytes requested. The void cast is + used to prevent byte alignment warnings from the compiler. */ + pxNewBlockLink = ( void * ) ( ( ( unsigned char * ) pxBlock ) + xWantedSize ); + + /* Calculate the sizes of two blocks split from the single + block. */ + pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - xWantedSize; + pxBlock->xBlockSize = xWantedSize; + + /* Insert the new block into the list of free blocks. */ + prvInsertBlockIntoFreeList( ( pxNewBlockLink ) ); + } + + xFreeBytesRemaining -= pxBlock->xBlockSize; + } + } + } + xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ +void xPortIncreaseHeapSize( size_t bytes ); + + +void vPortFree( void *pv ) +{ +unsigned char *puc = ( unsigned char * ) pv; +xBlockLink *pxLink; + + /* if this is the init stack being cleaned up on termination of the init task, sacrifice it to the heap */ + if( ( pv == (void *)&_init_stack_end ) && ( pv == &xHeap.ucHeap[currentTOTAL_HEAP_SIZE]) ) + { + xPortIncreaseHeapSize(&_init_stack_top - &_init_stack_end); + return; + } + + if( pv ) + { + /* The memory being freed will have an xBlockLink structure immediately + before it. */ + puc -= heapSTRUCT_SIZE; + + /* This casting is to keep the compiler from issuing warnings. */ + pxLink = ( void * ) puc; + + vTaskSuspendAll(); + { + /* Add this block to the list of free blocks. */ + prvInsertBlockIntoFreeList( ( ( xBlockLink * ) pxLink ) ); + xFreeBytesRemaining += pxLink->xBlockSize; + } + xTaskResumeAll(); + } +} +/*-----------------------------------------------------------*/ + +size_t xPortGetFreeHeapSize( void ) +{ + return xFreeBytesRemaining; +} +/*-----------------------------------------------------------*/ + +void vPortInitialiseBlocks( void ) +{ + /* This just exists to keep the linker quiet. */ +} + +void xPortIncreaseHeapSize( size_t bytes ) +{ + xBlockLink *pxNewBlockLink; + + vTaskSuspendAll(); + + /* increase the size of the end block so that this block will always be before it */ + xEnd.xBlockSize += bytes; + + /* Insert the new block into the list of free blocks. */ + pxNewBlockLink = ( void * ) &xHeap.ucHeap[ currentTOTAL_HEAP_SIZE ]; + pxNewBlockLink->xBlockSize = bytes; + prvInsertBlockIntoFreeList( ( pxNewBlockLink ) ); + + /* update heap statistics */ + currentTOTAL_HEAP_SIZE += bytes; + xFreeBytesRemaining += bytes; + + xTaskResumeAll(); +} +/*-----------------------------------------------------------*/ diff --git a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c new file mode 100644 index 000000000..09badd223 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c @@ -0,0 +1,117 @@ +/* + FreeRTOS V7.0.0 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS 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 and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +/* + * Implementation of pvPortMalloc() and vPortFree() that relies on the + * compilers own malloc() and free() implementations. + * + * This file can only be used if the linker is configured to to generate + * a heap memory area. + * + * See heap_2.c and heap_1.c for alternative implementations, and the memory + * management pages of http://www.FreeRTOS.org for more information. + */ + +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +void *pvReturn; + + vTaskSuspendAll(); + { + pvReturn = malloc( xWantedSize ); + } + xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ + if( pv ) + { + vTaskSuspendAll(); + { + free( pv ); + } + xTaskResumeAll(); + } +} + + + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/misc.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/misc.h new file mode 100644 index 000000000..df0a93ab1 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/misc.h @@ -0,0 +1,172 @@ +/** + ****************************************************************************** + * @file misc.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the miscellaneous + * firmware library functions (add-on to CMSIS functions). + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MISC_H +#define __MISC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup MISC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief NVIC Init Structure definition + */ + +typedef struct +{ + uint8_t NVIC_IRQChannel; /*!< Specifies the IRQ channel to be enabled or disabled. + This parameter can be an enumerator of @ref IRQn_Type + enumeration (For the complete STM32 Devices IRQ Channels + list, please refer to stm32f4xx.h file) */ + + uint8_t NVIC_IRQChannelPreemptionPriority; /*!< Specifies the pre-emption priority for the IRQ channel + specified in NVIC_IRQChannel. This parameter can be a value + between 0 and 15 as described in the table @ref MISC_NVIC_Priority_Table + A lower priority value indicates a higher priority */ + + uint8_t NVIC_IRQChannelSubPriority; /*!< Specifies the subpriority level for the IRQ channel specified + in NVIC_IRQChannel. This parameter can be a value + between 0 and 15 as described in the table @ref MISC_NVIC_Priority_Table + A lower priority value indicates a higher priority */ + + FunctionalState NVIC_IRQChannelCmd; /*!< Specifies whether the IRQ channel defined in NVIC_IRQChannel + will be enabled or disabled. + This parameter can be set either to ENABLE or DISABLE */ +} NVIC_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup MISC_Exported_Constants + * @{ + */ + +/** @defgroup MISC_Vector_Table_Base + * @{ + */ + +#define NVIC_VectTab_RAM ((uint32_t)0x20000000) +#define NVIC_VectTab_FLASH ((uint32_t)0x08000000) +#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \ + ((VECTTAB) == NVIC_VectTab_FLASH)) +/** + * @} + */ + +/** @defgroup MISC_System_Low_Power + * @{ + */ + +#define NVIC_LP_SEVONPEND ((uint8_t)0x10) +#define NVIC_LP_SLEEPDEEP ((uint8_t)0x04) +#define NVIC_LP_SLEEPONEXIT ((uint8_t)0x02) +#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \ + ((LP) == NVIC_LP_SLEEPDEEP) || \ + ((LP) == NVIC_LP_SLEEPONEXIT)) +/** + * @} + */ + +/** @defgroup MISC_Preemption_Priority_Group + * @{ + */ + +#define NVIC_PriorityGroup_0 ((uint32_t)0x700) /*!< 0 bits for pre-emption priority + 4 bits for subpriority */ +#define NVIC_PriorityGroup_1 ((uint32_t)0x600) /*!< 1 bits for pre-emption priority + 3 bits for subpriority */ +#define NVIC_PriorityGroup_2 ((uint32_t)0x500) /*!< 2 bits for pre-emption priority + 2 bits for subpriority */ +#define NVIC_PriorityGroup_3 ((uint32_t)0x400) /*!< 3 bits for pre-emption priority + 1 bits for subpriority */ +#define NVIC_PriorityGroup_4 ((uint32_t)0x300) /*!< 4 bits for pre-emption priority + 0 bits for subpriority */ + +#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \ + ((GROUP) == NVIC_PriorityGroup_1) || \ + ((GROUP) == NVIC_PriorityGroup_2) || \ + ((GROUP) == NVIC_PriorityGroup_3) || \ + ((GROUP) == NVIC_PriorityGroup_4)) + +#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) + +#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) + +#define IS_NVIC_OFFSET(OFFSET) ((OFFSET) < 0x000FFFFF) + +/** + * @} + */ + +/** @defgroup MISC_SysTick_clock_source + * @{ + */ + +#define SysTick_CLKSource_HCLK_Div8 ((uint32_t)0xFFFFFFFB) +#define SysTick_CLKSource_HCLK ((uint32_t)0x00000004) +#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \ + ((SOURCE) == SysTick_CLKSource_HCLK_Div8)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup); +void NVIC_Init(const NVIC_InitTypeDef* NVIC_InitStruct); +void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset); +void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState); +void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource); + +#ifdef __cplusplus +} +#endif + +#endif /* __MISC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_adc.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_adc.h new file mode 100644 index 000000000..b9d9d0904 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_adc.h @@ -0,0 +1,643 @@ +/** + ****************************************************************************** + * @file stm32f4xx_adc.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the ADC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_ADC_H +#define __STM32F4xx_ADC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup ADC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief ADC Init structure definition + */ +typedef struct +{ + uint32_t ADC_Resolution; /*!< Configures the ADC resolution dual mode. + This parameter can be a value of @ref ADC_resolution */ + FunctionalState ADC_ScanConvMode; /*!< Specifies whether the conversion + is performed in Scan (multichannels) + or Single (one channel) mode. + This parameter can be set to ENABLE or DISABLE */ + FunctionalState ADC_ContinuousConvMode; /*!< Specifies whether the conversion + is performed in Continuous or Single mode. + This parameter can be set to ENABLE or DISABLE. */ + uint32_t ADC_ExternalTrigConvEdge; /*!< Select the external trigger edge and + enable the trigger of a regular group. + This parameter can be a value of + @ref ADC_external_trigger_edge_for_regular_channels_conversion */ + uint32_t ADC_ExternalTrigConv; /*!< Select the external event used to trigger + the start of conversion of a regular group. + This parameter can be a value of + @ref ADC_extrenal_trigger_sources_for_regular_channels_conversion */ + uint32_t ADC_DataAlign; /*!< Specifies whether the ADC data alignment + is left or right. This parameter can be + a value of @ref ADC_data_align */ + uint8_t ADC_NbrOfConversion; /*!< Specifies the number of ADC conversions + that will be done using the sequencer for + regular channel group. + This parameter must range from 1 to 16. */ +}ADC_InitTypeDef; + +/** + * @brief ADC Common Init structure definition + */ +typedef struct +{ + uint32_t ADC_Mode; /*!< Configures the ADC to operate in + independent or multi mode. + This parameter can be a value of @ref ADC_Common_mode */ + uint32_t ADC_Prescaler; /*!< Select the frequency of the clock + to the ADC. The clock is common for all the ADCs. + This parameter can be a value of @ref ADC_Prescaler */ + uint32_t ADC_DMAAccessMode; /*!< Configures the Direct memory access + mode for multi ADC mode. + This parameter can be a value of + @ref ADC_Direct_memory_access_mode_for_multi_mode */ + uint32_t ADC_TwoSamplingDelay; /*!< Configures the Delay between 2 sampling phases. + This parameter can be a value of + @ref ADC_delay_between_2_sampling_phases */ + +}ADC_CommonInitTypeDef; + + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup ADC_Exported_Constants + * @{ + */ +#define IS_ADC_ALL_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ + ((PERIPH) == ADC2) || \ + ((PERIPH) == ADC3)) + +/** @defgroup ADC_Common_mode + * @{ + */ +#define ADC_Mode_Independent ((uint32_t)0x00000000) +#define ADC_DualMode_RegSimult_InjecSimult ((uint32_t)0x00000001) +#define ADC_DualMode_RegSimult_AlterTrig ((uint32_t)0x00000002) +#define ADC_DualMode_InjecSimult ((uint32_t)0x00000005) +#define ADC_DualMode_RegSimult ((uint32_t)0x00000006) +#define ADC_DualMode_Interl ((uint32_t)0x00000007) +#define ADC_DualMode_AlterTrig ((uint32_t)0x00000009) +#define ADC_TripleMode_RegSimult_InjecSimult ((uint32_t)0x00000011) +#define ADC_TripleMode_RegSimult_AlterTrig ((uint32_t)0x00000012) +#define ADC_TripleMode_InjecSimult ((uint32_t)0x00000015) +#define ADC_TripleMode_RegSimult ((uint32_t)0x00000016) +#define ADC_TripleMode_Interl ((uint32_t)0x00000017) +#define ADC_TripleMode_AlterTrig ((uint32_t)0x00000019) +#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \ + ((MODE) == ADC_DualMode_RegSimult_InjecSimult) || \ + ((MODE) == ADC_DualMode_RegSimult_AlterTrig) || \ + ((MODE) == ADC_DualMode_InjecSimult) || \ + ((MODE) == ADC_DualMode_RegSimult) || \ + ((MODE) == ADC_DualMode_Interl) || \ + ((MODE) == ADC_DualMode_AlterTrig) || \ + ((MODE) == ADC_TripleMode_RegSimult_InjecSimult) || \ + ((MODE) == ADC_TripleMode_RegSimult_AlterTrig) || \ + ((MODE) == ADC_TripleMode_InjecSimult) || \ + ((MODE) == ADC_TripleMode_RegSimult) || \ + ((MODE) == ADC_TripleMode_Interl) || \ + ((MODE) == ADC_TripleMode_AlterTrig)) +/** + * @} + */ + + +/** @defgroup ADC_Prescaler + * @{ + */ +#define ADC_Prescaler_Div2 ((uint32_t)0x00000000) +#define ADC_Prescaler_Div4 ((uint32_t)0x00010000) +#define ADC_Prescaler_Div6 ((uint32_t)0x00020000) +#define ADC_Prescaler_Div8 ((uint32_t)0x00030000) +#define IS_ADC_PRESCALER(PRESCALER) (((PRESCALER) == ADC_Prescaler_Div2) || \ + ((PRESCALER) == ADC_Prescaler_Div4) || \ + ((PRESCALER) == ADC_Prescaler_Div6) || \ + ((PRESCALER) == ADC_Prescaler_Div8)) +/** + * @} + */ + + +/** @defgroup ADC_Direct_memory_access_mode_for_multi_mode + * @{ + */ +#define ADC_DMAAccessMode_Disabled ((uint32_t)0x00000000) /* DMA mode disabled */ +#define ADC_DMAAccessMode_1 ((uint32_t)0x00004000) /* DMA mode 1 enabled (2 / 3 half-words one by one - 1 then 2 then 3)*/ +#define ADC_DMAAccessMode_2 ((uint32_t)0x00008000) /* DMA mode 2 enabled (2 / 3 half-words by pairs - 2&1 then 1&3 then 3&2)*/ +#define ADC_DMAAccessMode_3 ((uint32_t)0x0000C000) /* DMA mode 3 enabled (2 / 3 bytes by pairs - 2&1 then 1&3 then 3&2) */ +#define IS_ADC_DMA_ACCESS_MODE(MODE) (((MODE) == ADC_DMAAccessMode_Disabled) || \ + ((MODE) == ADC_DMAAccessMode_1) || \ + ((MODE) == ADC_DMAAccessMode_2) || \ + ((MODE) == ADC_DMAAccessMode_3)) + +/** + * @} + */ + + +/** @defgroup ADC_delay_between_2_sampling_phases + * @{ + */ +#define ADC_TwoSamplingDelay_5Cycles ((uint32_t)0x00000000) +#define ADC_TwoSamplingDelay_6Cycles ((uint32_t)0x00000100) +#define ADC_TwoSamplingDelay_7Cycles ((uint32_t)0x00000200) +#define ADC_TwoSamplingDelay_8Cycles ((uint32_t)0x00000300) +#define ADC_TwoSamplingDelay_9Cycles ((uint32_t)0x00000400) +#define ADC_TwoSamplingDelay_10Cycles ((uint32_t)0x00000500) +#define ADC_TwoSamplingDelay_11Cycles ((uint32_t)0x00000600) +#define ADC_TwoSamplingDelay_12Cycles ((uint32_t)0x00000700) +#define ADC_TwoSamplingDelay_13Cycles ((uint32_t)0x00000800) +#define ADC_TwoSamplingDelay_14Cycles ((uint32_t)0x00000900) +#define ADC_TwoSamplingDelay_15Cycles ((uint32_t)0x00000A00) +#define ADC_TwoSamplingDelay_16Cycles ((uint32_t)0x00000B00) +#define ADC_TwoSamplingDelay_17Cycles ((uint32_t)0x00000C00) +#define ADC_TwoSamplingDelay_18Cycles ((uint32_t)0x00000D00) +#define ADC_TwoSamplingDelay_19Cycles ((uint32_t)0x00000E00) +#define ADC_TwoSamplingDelay_20Cycles ((uint32_t)0x00000F00) +#define IS_ADC_SAMPLING_DELAY(DELAY) (((DELAY) == ADC_TwoSamplingDelay_5Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_6Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_7Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_8Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_9Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_10Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_11Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_12Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_13Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_14Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_15Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_16Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_17Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_18Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_19Cycles) || \ + ((DELAY) == ADC_TwoSamplingDelay_20Cycles)) + +/** + * @} + */ + + +/** @defgroup ADC_resolution + * @{ + */ +#define ADC_Resolution_12b ((uint32_t)0x00000000) +#define ADC_Resolution_10b ((uint32_t)0x01000000) +#define ADC_Resolution_8b ((uint32_t)0x02000000) +#define ADC_Resolution_6b ((uint32_t)0x03000000) +#define IS_ADC_RESOLUTION(RESOLUTION) (((RESOLUTION) == ADC_Resolution_12b) || \ + ((RESOLUTION) == ADC_Resolution_10b) || \ + ((RESOLUTION) == ADC_Resolution_8b) || \ + ((RESOLUTION) == ADC_Resolution_6b)) + +/** + * @} + */ + + +/** @defgroup ADC_external_trigger_edge_for_regular_channels_conversion + * @{ + */ +#define ADC_ExternalTrigConvEdge_None ((uint32_t)0x00000000) +#define ADC_ExternalTrigConvEdge_Rising ((uint32_t)0x10000000) +#define ADC_ExternalTrigConvEdge_Falling ((uint32_t)0x20000000) +#define ADC_ExternalTrigConvEdge_RisingFalling ((uint32_t)0x30000000) +#define IS_ADC_EXT_TRIG_EDGE(EDGE) (((EDGE) == ADC_ExternalTrigConvEdge_None) || \ + ((EDGE) == ADC_ExternalTrigConvEdge_Rising) || \ + ((EDGE) == ADC_ExternalTrigConvEdge_Falling) || \ + ((EDGE) == ADC_ExternalTrigConvEdge_RisingFalling)) +/** + * @} + */ + + +/** @defgroup ADC_extrenal_trigger_sources_for_regular_channels_conversion + * @{ + */ +#define ADC_ExternalTrigConv_T1_CC1 ((uint32_t)0x00000000) +#define ADC_ExternalTrigConv_T1_CC2 ((uint32_t)0x01000000) +#define ADC_ExternalTrigConv_T1_CC3 ((uint32_t)0x02000000) +#define ADC_ExternalTrigConv_T2_CC2 ((uint32_t)0x03000000) +#define ADC_ExternalTrigConv_T2_CC3 ((uint32_t)0x04000000) +#define ADC_ExternalTrigConv_T2_CC4 ((uint32_t)0x05000000) +#define ADC_ExternalTrigConv_T2_TRGO ((uint32_t)0x06000000) +#define ADC_ExternalTrigConv_T3_CC1 ((uint32_t)0x07000000) +#define ADC_ExternalTrigConv_T3_TRGO ((uint32_t)0x08000000) +#define ADC_ExternalTrigConv_T4_CC4 ((uint32_t)0x09000000) +#define ADC_ExternalTrigConv_T5_CC1 ((uint32_t)0x0A000000) +#define ADC_ExternalTrigConv_T5_CC2 ((uint32_t)0x0B000000) +#define ADC_ExternalTrigConv_T5_CC3 ((uint32_t)0x0C000000) +#define ADC_ExternalTrigConv_T8_CC1 ((uint32_t)0x0D000000) +#define ADC_ExternalTrigConv_T8_TRGO ((uint32_t)0x0E000000) +#define ADC_ExternalTrigConv_Ext_IT11 ((uint32_t)0x0F000000) +#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T2_CC4) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T2_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T5_CC2) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T5_CC3) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_Ext_IT11)) +/** + * @} + */ + + +/** @defgroup ADC_data_align + * @{ + */ +#define ADC_DataAlign_Right ((uint32_t)0x00000000) +#define ADC_DataAlign_Left ((uint32_t)0x00000800) +#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \ + ((ALIGN) == ADC_DataAlign_Left)) +/** + * @} + */ + + +/** @defgroup ADC_channels + * @{ + */ +#define ADC_Channel_0 ((uint8_t)0x00) +#define ADC_Channel_1 ((uint8_t)0x01) +#define ADC_Channel_2 ((uint8_t)0x02) +#define ADC_Channel_3 ((uint8_t)0x03) +#define ADC_Channel_4 ((uint8_t)0x04) +#define ADC_Channel_5 ((uint8_t)0x05) +#define ADC_Channel_6 ((uint8_t)0x06) +#define ADC_Channel_7 ((uint8_t)0x07) +#define ADC_Channel_8 ((uint8_t)0x08) +#define ADC_Channel_9 ((uint8_t)0x09) +#define ADC_Channel_10 ((uint8_t)0x0A) +#define ADC_Channel_11 ((uint8_t)0x0B) +#define ADC_Channel_12 ((uint8_t)0x0C) +#define ADC_Channel_13 ((uint8_t)0x0D) +#define ADC_Channel_14 ((uint8_t)0x0E) +#define ADC_Channel_15 ((uint8_t)0x0F) +#define ADC_Channel_16 ((uint8_t)0x10) +#define ADC_Channel_17 ((uint8_t)0x11) +#define ADC_Channel_18 ((uint8_t)0x12) + +#define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_16) +#define ADC_Channel_Vrefint ((uint8_t)ADC_Channel_17) +#define ADC_Channel_Vbat ((uint8_t)ADC_Channel_18) + +#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || \ + ((CHANNEL) == ADC_Channel_1) || \ + ((CHANNEL) == ADC_Channel_2) || \ + ((CHANNEL) == ADC_Channel_3) || \ + ((CHANNEL) == ADC_Channel_4) || \ + ((CHANNEL) == ADC_Channel_5) || \ + ((CHANNEL) == ADC_Channel_6) || \ + ((CHANNEL) == ADC_Channel_7) || \ + ((CHANNEL) == ADC_Channel_8) || \ + ((CHANNEL) == ADC_Channel_9) || \ + ((CHANNEL) == ADC_Channel_10) || \ + ((CHANNEL) == ADC_Channel_11) || \ + ((CHANNEL) == ADC_Channel_12) || \ + ((CHANNEL) == ADC_Channel_13) || \ + ((CHANNEL) == ADC_Channel_14) || \ + ((CHANNEL) == ADC_Channel_15) || \ + ((CHANNEL) == ADC_Channel_16) || \ + ((CHANNEL) == ADC_Channel_17) || \ + ((CHANNEL) == ADC_Channel_18)) +/** + * @} + */ + + +/** @defgroup ADC_sampling_times + * @{ + */ +#define ADC_SampleTime_3Cycles ((uint8_t)0x00) +#define ADC_SampleTime_15Cycles ((uint8_t)0x01) +#define ADC_SampleTime_28Cycles ((uint8_t)0x02) +#define ADC_SampleTime_56Cycles ((uint8_t)0x03) +#define ADC_SampleTime_84Cycles ((uint8_t)0x04) +#define ADC_SampleTime_112Cycles ((uint8_t)0x05) +#define ADC_SampleTime_144Cycles ((uint8_t)0x06) +#define ADC_SampleTime_480Cycles ((uint8_t)0x07) +#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_3Cycles) || \ + ((TIME) == ADC_SampleTime_15Cycles) || \ + ((TIME) == ADC_SampleTime_28Cycles) || \ + ((TIME) == ADC_SampleTime_56Cycles) || \ + ((TIME) == ADC_SampleTime_84Cycles) || \ + ((TIME) == ADC_SampleTime_112Cycles) || \ + ((TIME) == ADC_SampleTime_144Cycles) || \ + ((TIME) == ADC_SampleTime_480Cycles)) +/** + * @} + */ + + +/** @defgroup ADC_external_trigger_edge_for_injected_channels_conversion + * @{ + */ +#define ADC_ExternalTrigInjecConvEdge_None ((uint32_t)0x00000000) +#define ADC_ExternalTrigInjecConvEdge_Rising ((uint32_t)0x00100000) +#define ADC_ExternalTrigInjecConvEdge_Falling ((uint32_t)0x00200000) +#define ADC_ExternalTrigInjecConvEdge_RisingFalling ((uint32_t)0x00300000) +#define IS_ADC_EXT_INJEC_TRIG_EDGE(EDGE) (((EDGE) == ADC_ExternalTrigInjecConvEdge_None) || \ + ((EDGE) == ADC_ExternalTrigInjecConvEdge_Rising) || \ + ((EDGE) == ADC_ExternalTrigInjecConvEdge_Falling) || \ + ((EDGE) == ADC_ExternalTrigInjecConvEdge_RisingFalling)) + +/** + * @} + */ + + +/** @defgroup ADC_extrenal_trigger_sources_for_injected_channels_conversion + * @{ + */ +#define ADC_ExternalTrigInjecConv_T1_CC4 ((uint32_t)0x00000000) +#define ADC_ExternalTrigInjecConv_T1_TRGO ((uint32_t)0x00010000) +#define ADC_ExternalTrigInjecConv_T2_CC1 ((uint32_t)0x00020000) +#define ADC_ExternalTrigInjecConv_T2_TRGO ((uint32_t)0x00030000) +#define ADC_ExternalTrigInjecConv_T3_CC2 ((uint32_t)0x00040000) +#define ADC_ExternalTrigInjecConv_T3_CC4 ((uint32_t)0x00050000) +#define ADC_ExternalTrigInjecConv_T4_CC1 ((uint32_t)0x00060000) +#define ADC_ExternalTrigInjecConv_T4_CC2 ((uint32_t)0x00070000) +#define ADC_ExternalTrigInjecConv_T4_CC3 ((uint32_t)0x00080000) +#define ADC_ExternalTrigInjecConv_T4_TRGO ((uint32_t)0x00090000) +#define ADC_ExternalTrigInjecConv_T5_CC4 ((uint32_t)0x000A0000) +#define ADC_ExternalTrigInjecConv_T5_TRGO ((uint32_t)0x000B0000) +#define ADC_ExternalTrigInjecConv_T8_CC2 ((uint32_t)0x000C0000) +#define ADC_ExternalTrigInjecConv_T8_CC3 ((uint32_t)0x000D0000) +#define ADC_ExternalTrigInjecConv_T8_CC4 ((uint32_t)0x000E0000) +#define ADC_ExternalTrigInjecConv_Ext_IT15 ((uint32_t)0x000F0000) +#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC2) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC1) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC2) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC3) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15)) +/** + * @} + */ + + +/** @defgroup ADC_injected_channel_selection + * @{ + */ +#define ADC_InjectedChannel_1 ((uint8_t)0x14) +#define ADC_InjectedChannel_2 ((uint8_t)0x18) +#define ADC_InjectedChannel_3 ((uint8_t)0x1C) +#define ADC_InjectedChannel_4 ((uint8_t)0x20) +#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \ + ((CHANNEL) == ADC_InjectedChannel_2) || \ + ((CHANNEL) == ADC_InjectedChannel_3) || \ + ((CHANNEL) == ADC_InjectedChannel_4)) +/** + * @} + */ + + +/** @defgroup ADC_analog_watchdog_selection + * @{ + */ +#define ADC_AnalogWatchdog_SingleRegEnable ((uint32_t)0x00800200) +#define ADC_AnalogWatchdog_SingleInjecEnable ((uint32_t)0x00400200) +#define ADC_AnalogWatchdog_SingleRegOrInjecEnable ((uint32_t)0x00C00200) +#define ADC_AnalogWatchdog_AllRegEnable ((uint32_t)0x00800000) +#define ADC_AnalogWatchdog_AllInjecEnable ((uint32_t)0x00400000) +#define ADC_AnalogWatchdog_AllRegAllInjecEnable ((uint32_t)0x00C00000) +#define ADC_AnalogWatchdog_None ((uint32_t)0x00000000) +#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_None)) +/** + * @} + */ + + +/** @defgroup ADC_interrupts_definition + * @{ + */ +#define ADC_IT_EOC ((uint16_t)0x0205) +#define ADC_IT_AWD ((uint16_t)0x0106) +#define ADC_IT_JEOC ((uint16_t)0x0407) +#define ADC_IT_OVR ((uint16_t)0x201A) +#define IS_ADC_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \ + ((IT) == ADC_IT_JEOC)|| ((IT) == ADC_IT_OVR)) +/** + * @} + */ + + +/** @defgroup ADC_flags_definition + * @{ + */ +#define ADC_FLAG_AWD ((uint8_t)0x01) +#define ADC_FLAG_EOC ((uint8_t)0x02) +#define ADC_FLAG_JEOC ((uint8_t)0x04) +#define ADC_FLAG_JSTRT ((uint8_t)0x08) +#define ADC_FLAG_STRT ((uint8_t)0x10) +#define ADC_FLAG_OVR ((uint8_t)0x20) + +#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint8_t)0xC0) == 0x00) && ((FLAG) != 0x00)) +#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || \ + ((FLAG) == ADC_FLAG_EOC) || \ + ((FLAG) == ADC_FLAG_JEOC) || \ + ((FLAG)== ADC_FLAG_JSTRT) || \ + ((FLAG) == ADC_FLAG_STRT) || \ + ((FLAG)== ADC_FLAG_OVR)) +/** + * @} + */ + + +/** @defgroup ADC_thresholds + * @{ + */ +#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF) +/** + * @} + */ + + +/** @defgroup ADC_injected_offset + * @{ + */ +#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF) +/** + * @} + */ + + +/** @defgroup ADC_injected_length + * @{ + */ +#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4)) +/** + * @} + */ + + +/** @defgroup ADC_injected_rank + * @{ + */ +#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4)) +/** + * @} + */ + + +/** @defgroup ADC_regular_length + * @{ + */ +#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10)) +/** + * @} + */ + + +/** @defgroup ADC_regular_rank + * @{ + */ +#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10)) +/** + * @} + */ + + +/** @defgroup ADC_regular_discontinuous_mode_number + * @{ + */ +#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8)) +/** + * @} + */ + + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the ADC configuration to the default reset state *****/ +void ADC_DeInit(void); + +/* Initialization and Configuration functions *********************************/ +void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct); +void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct); +void ADC_CommonInit(ADC_CommonInitTypeDef* ADC_CommonInitStruct); +void ADC_CommonStructInit(ADC_CommonInitTypeDef* ADC_CommonInitStruct); +void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState); + +/* Analog Watchdog configuration functions ************************************/ +void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog); +void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold,uint16_t LowThreshold); +void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel); + +/* Temperature Sensor, Vrefint and VBAT management functions ******************/ +void ADC_TempSensorVrefintCmd(FunctionalState NewState); +void ADC_VBATCmd(FunctionalState NewState); + +/* Regular Channels Configuration functions ***********************************/ +void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); +void ADC_SoftwareStartConv(ADC_TypeDef* ADCx); +FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx); +void ADC_EOCOnEachRegularChannelCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_ContinuousModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number); +void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx); +uint32_t ADC_GetMultiModeConversionValue(void); + +/* Regular Channels DMA Configuration functions *******************************/ +void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_DMARequestAfterLastTransferCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_MultiModeDMARequestAfterLastTransferCmd(FunctionalState NewState); + +/* Injected channels Configuration functions **********************************/ +void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); +void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length); +void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset); +void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv); +void ADC_ExternalTrigInjectedConvEdgeConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConvEdge); +void ADC_SoftwareStartInjectedConv(ADC_TypeDef* ADCx); +FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx); +void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel); + +/* Interrupts and flags management functions **********************************/ +void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState); +FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG); +void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG); +ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT); +void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_ADC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_can.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_can.h new file mode 100644 index 000000000..900d50f03 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_can.h @@ -0,0 +1,638 @@ +/** + ****************************************************************************** + * @file stm32f4xx_can.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the CAN firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_CAN_H +#define __STM32F4xx_CAN_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CAN + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +#define IS_CAN_ALL_PERIPH(PERIPH) (((PERIPH) == CAN1) || \ + ((PERIPH) == CAN2)) + +/** + * @brief CAN init structure definition + */ +typedef struct +{ + uint16_t CAN_Prescaler; /*!< Specifies the length of a time quantum. + It ranges from 1 to 1024. */ + + uint8_t CAN_Mode; /*!< Specifies the CAN operating mode. + This parameter can be a value of @ref CAN_operating_mode */ + + uint8_t CAN_SJW; /*!< Specifies the maximum number of time quanta + the CAN hardware is allowed to lengthen or + shorten a bit to perform resynchronization. + This parameter can be a value of @ref CAN_synchronisation_jump_width */ + + uint8_t CAN_BS1; /*!< Specifies the number of time quanta in Bit + Segment 1. This parameter can be a value of + @ref CAN_time_quantum_in_bit_segment_1 */ + + uint8_t CAN_BS2; /*!< Specifies the number of time quanta in Bit Segment 2. + This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */ + + FunctionalState CAN_TTCM; /*!< Enable or disable the time triggered communication mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_ABOM; /*!< Enable or disable the automatic bus-off management. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_AWUM; /*!< Enable or disable the automatic wake-up mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_NART; /*!< Enable or disable the non-automatic retransmission mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_RFLM; /*!< Enable or disable the Receive FIFO Locked mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_TXFP; /*!< Enable or disable the transmit FIFO priority. + This parameter can be set either to ENABLE or DISABLE. */ +} CAN_InitTypeDef; + +/** + * @brief CAN filter init structure definition + */ +typedef struct +{ + uint16_t CAN_FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit + configuration, first one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit + configuration, second one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, + according to the mode (MSBs for a 32-bit configuration, + first one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, + according to the mode (LSBs for a 32-bit configuration, + second one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter. + This parameter can be a value of @ref CAN_filter_FIFO */ + + uint8_t CAN_FilterNumber; /*!< Specifies the filter which will be initialized. It ranges from 0 to 13. */ + + uint8_t CAN_FilterMode; /*!< Specifies the filter mode to be initialized. + This parameter can be a value of @ref CAN_filter_mode */ + + uint8_t CAN_FilterScale; /*!< Specifies the filter scale. + This parameter can be a value of @ref CAN_filter_scale */ + + FunctionalState CAN_FilterActivation; /*!< Enable or disable the filter. + This parameter can be set either to ENABLE or DISABLE. */ +} CAN_FilterInitTypeDef; + +/** + * @brief CAN Tx message structure definition + */ +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter can be a value between 0 to 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter can be a value between 0 to 0x1FFFFFFF. */ + + uint8_t IDE; /*!< Specifies the type of identifier for the message that + will be transmitted. This parameter can be a value + of @ref CAN_identifier_type */ + + uint8_t RTR; /*!< Specifies the type of frame for the message that will + be transmitted. This parameter can be a value of + @ref CAN_remote_transmission_request */ + + uint8_t DLC; /*!< Specifies the length of the frame that will be + transmitted. This parameter can be a value between + 0 to 8 */ + + uint8_t Data[8]; /*!< Contains the data to be transmitted. It ranges from 0 + to 0xFF. */ +} CanTxMsg; + +/** + * @brief CAN Rx message structure definition + */ +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter can be a value between 0 to 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter can be a value between 0 to 0x1FFFFFFF. */ + + uint8_t IDE; /*!< Specifies the type of identifier for the message that + will be received. This parameter can be a value of + @ref CAN_identifier_type */ + + uint8_t RTR; /*!< Specifies the type of frame for the received message. + This parameter can be a value of + @ref CAN_remote_transmission_request */ + + uint8_t DLC; /*!< Specifies the length of the frame that will be received. + This parameter can be a value between 0 to 8 */ + + uint8_t Data[8]; /*!< Contains the data to be received. It ranges from 0 to + 0xFF. */ + + uint8_t FMI; /*!< Specifies the index of the filter the message stored in + the mailbox passes through. This parameter can be a + value between 0 to 0xFF */ +} CanRxMsg; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup CAN_Exported_Constants + * @{ + */ + +/** @defgroup CAN_InitStatus + * @{ + */ + +#define CAN_InitStatus_Failed ((uint8_t)0x00) /*!< CAN initialization failed */ +#define CAN_InitStatus_Success ((uint8_t)0x01) /*!< CAN initialization OK */ + + +/* Legacy defines */ +#define CANINITFAILED CAN_InitStatus_Failed +#define CANINITOK CAN_InitStatus_Success +/** + * @} + */ + +/** @defgroup CAN_operating_mode + * @{ + */ + +#define CAN_Mode_Normal ((uint8_t)0x00) /*!< normal mode */ +#define CAN_Mode_LoopBack ((uint8_t)0x01) /*!< loopback mode */ +#define CAN_Mode_Silent ((uint8_t)0x02) /*!< silent mode */ +#define CAN_Mode_Silent_LoopBack ((uint8_t)0x03) /*!< loopback combined with silent mode */ + +#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || \ + ((MODE) == CAN_Mode_LoopBack)|| \ + ((MODE) == CAN_Mode_Silent) || \ + ((MODE) == CAN_Mode_Silent_LoopBack)) +/** + * @} + */ + + + /** + * @defgroup CAN_operating_mode + * @{ + */ +#define CAN_OperatingMode_Initialization ((uint8_t)0x00) /*!< Initialization mode */ +#define CAN_OperatingMode_Normal ((uint8_t)0x01) /*!< Normal mode */ +#define CAN_OperatingMode_Sleep ((uint8_t)0x02) /*!< sleep mode */ + + +#define IS_CAN_OPERATING_MODE(MODE) (((MODE) == CAN_OperatingMode_Initialization) ||\ + ((MODE) == CAN_OperatingMode_Normal)|| \ + ((MODE) == CAN_OperatingMode_Sleep)) +/** + * @} + */ + +/** + * @defgroup CAN_operating_mode_status + * @{ + */ + +#define CAN_ModeStatus_Failed ((uint8_t)0x00) /*!< CAN entering the specific mode failed */ +#define CAN_ModeStatus_Success ((uint8_t)!CAN_ModeStatus_Failed) /*!< CAN entering the specific mode Succeed */ +/** + * @} + */ + +/** @defgroup CAN_synchronisation_jump_width + * @{ + */ +#define CAN_SJW_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_SJW_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_SJW_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_SJW_4tq ((uint8_t)0x03) /*!< 4 time quantum */ + +#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \ + ((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq)) +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_1 + * @{ + */ +#define CAN_BS1_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_BS1_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_BS1_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_BS1_4tq ((uint8_t)0x03) /*!< 4 time quantum */ +#define CAN_BS1_5tq ((uint8_t)0x04) /*!< 5 time quantum */ +#define CAN_BS1_6tq ((uint8_t)0x05) /*!< 6 time quantum */ +#define CAN_BS1_7tq ((uint8_t)0x06) /*!< 7 time quantum */ +#define CAN_BS1_8tq ((uint8_t)0x07) /*!< 8 time quantum */ +#define CAN_BS1_9tq ((uint8_t)0x08) /*!< 9 time quantum */ +#define CAN_BS1_10tq ((uint8_t)0x09) /*!< 10 time quantum */ +#define CAN_BS1_11tq ((uint8_t)0x0A) /*!< 11 time quantum */ +#define CAN_BS1_12tq ((uint8_t)0x0B) /*!< 12 time quantum */ +#define CAN_BS1_13tq ((uint8_t)0x0C) /*!< 13 time quantum */ +#define CAN_BS1_14tq ((uint8_t)0x0D) /*!< 14 time quantum */ +#define CAN_BS1_15tq ((uint8_t)0x0E) /*!< 15 time quantum */ +#define CAN_BS1_16tq ((uint8_t)0x0F) /*!< 16 time quantum */ + +#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq) +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_2 + * @{ + */ +#define CAN_BS2_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_BS2_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_BS2_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_BS2_4tq ((uint8_t)0x03) /*!< 4 time quantum */ +#define CAN_BS2_5tq ((uint8_t)0x04) /*!< 5 time quantum */ +#define CAN_BS2_6tq ((uint8_t)0x05) /*!< 6 time quantum */ +#define CAN_BS2_7tq ((uint8_t)0x06) /*!< 7 time quantum */ +#define CAN_BS2_8tq ((uint8_t)0x07) /*!< 8 time quantum */ + +#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq) +/** + * @} + */ + +/** @defgroup CAN_clock_prescaler + * @{ + */ +#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024)) +/** + * @} + */ + +/** @defgroup CAN_filter_number + * @{ + */ +#define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27) +/** + * @} + */ + +/** @defgroup CAN_filter_mode + * @{ + */ +#define CAN_FilterMode_IdMask ((uint8_t)0x00) /*!< identifier/mask mode */ +#define CAN_FilterMode_IdList ((uint8_t)0x01) /*!< identifier list mode */ + +#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \ + ((MODE) == CAN_FilterMode_IdList)) +/** + * @} + */ + +/** @defgroup CAN_filter_scale + * @{ + */ +#define CAN_FilterScale_16bit ((uint8_t)0x00) /*!< Two 16-bit filters */ +#define CAN_FilterScale_32bit ((uint8_t)0x01) /*!< One 32-bit filter */ + +#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \ + ((SCALE) == CAN_FilterScale_32bit)) +/** + * @} + */ + +/** @defgroup CAN_filter_FIFO + * @{ + */ +#define CAN_Filter_FIFO0 ((uint8_t)0x00) /*!< Filter FIFO 0 assignment for filter x */ +#define CAN_Filter_FIFO1 ((uint8_t)0x01) /*!< Filter FIFO 1 assignment for filter x */ +#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \ + ((FIFO) == CAN_FilterFIFO1)) + +/* Legacy defines */ +#define CAN_FilterFIFO0 CAN_Filter_FIFO0 +#define CAN_FilterFIFO1 CAN_Filter_FIFO1 +/** + * @} + */ + +/** @defgroup CAN_Start_bank_filter_for_slave_CAN + * @{ + */ +#define IS_CAN_BANKNUMBER(BANKNUMBER) (((BANKNUMBER) >= 1) && ((BANKNUMBER) <= 27)) +/** + * @} + */ + +/** @defgroup CAN_Tx + * @{ + */ +#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02)) +#define IS_CAN_STDID(STDID) ((STDID) <= ((uint32_t)0x7FF)) +#define IS_CAN_EXTID(EXTID) ((EXTID) <= ((uint32_t)0x1FFFFFFF)) +#define IS_CAN_DLC(DLC) ((DLC) <= ((uint8_t)0x08)) +/** + * @} + */ + +/** @defgroup CAN_identifier_type + * @{ + */ +#define CAN_Id_Standard ((uint32_t)0x00000000) /*!< Standard Id */ +#define CAN_Id_Extended ((uint32_t)0x00000004) /*!< Extended Id */ +#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_Id_Standard) || \ + ((IDTYPE) == CAN_Id_Extended)) + +/* Legacy defines */ +#define CAN_ID_STD CAN_Id_Standard +#define CAN_ID_EXT CAN_Id_Extended +/** + * @} + */ + +/** @defgroup CAN_remote_transmission_request + * @{ + */ +#define CAN_RTR_Data ((uint32_t)0x00000000) /*!< Data frame */ +#define CAN_RTR_Remote ((uint32_t)0x00000002) /*!< Remote frame */ +#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_Data) || ((RTR) == CAN_RTR_Remote)) + +/* Legacy defines */ +#define CAN_RTR_DATA CAN_RTR_Data +#define CAN_RTR_REMOTE CAN_RTR_Remote +/** + * @} + */ + +/** @defgroup CAN_transmit_constants + * @{ + */ +#define CAN_TxStatus_Failed ((uint8_t)0x00)/*!< CAN transmission failed */ +#define CAN_TxStatus_Ok ((uint8_t)0x01) /*!< CAN transmission succeeded */ +#define CAN_TxStatus_Pending ((uint8_t)0x02) /*!< CAN transmission pending */ +#define CAN_TxStatus_NoMailBox ((uint8_t)0x04) /*!< CAN cell did not provide + an empty mailbox */ +/* Legacy defines */ +#define CANTXFAILED CAN_TxStatus_Failed +#define CANTXOK CAN_TxStatus_Ok +#define CANTXPENDING CAN_TxStatus_Pending +#define CAN_NO_MB CAN_TxStatus_NoMailBox +/** + * @} + */ + +/** @defgroup CAN_receive_FIFO_number_constants + * @{ + */ +#define CAN_FIFO0 ((uint8_t)0x00) /*!< CAN FIFO 0 used to receive */ +#define CAN_FIFO1 ((uint8_t)0x01) /*!< CAN FIFO 1 used to receive */ + +#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1)) +/** + * @} + */ + +/** @defgroup CAN_sleep_constants + * @{ + */ +#define CAN_Sleep_Failed ((uint8_t)0x00) /*!< CAN did not enter the sleep mode */ +#define CAN_Sleep_Ok ((uint8_t)0x01) /*!< CAN entered the sleep mode */ + +/* Legacy defines */ +#define CANSLEEPFAILED CAN_Sleep_Failed +#define CANSLEEPOK CAN_Sleep_Ok +/** + * @} + */ + +/** @defgroup CAN_wake_up_constants + * @{ + */ +#define CAN_WakeUp_Failed ((uint8_t)0x00) /*!< CAN did not leave the sleep mode */ +#define CAN_WakeUp_Ok ((uint8_t)0x01) /*!< CAN leaved the sleep mode */ + +/* Legacy defines */ +#define CANWAKEUPFAILED CAN_WakeUp_Failed +#define CANWAKEUPOK CAN_WakeUp_Ok +/** + * @} + */ + +/** + * @defgroup CAN_Error_Code_constants + * @{ + */ +#define CAN_ErrorCode_NoErr ((uint8_t)0x00) /*!< No Error */ +#define CAN_ErrorCode_StuffErr ((uint8_t)0x10) /*!< Stuff Error */ +#define CAN_ErrorCode_FormErr ((uint8_t)0x20) /*!< Form Error */ +#define CAN_ErrorCode_ACKErr ((uint8_t)0x30) /*!< Acknowledgment Error */ +#define CAN_ErrorCode_BitRecessiveErr ((uint8_t)0x40) /*!< Bit Recessive Error */ +#define CAN_ErrorCode_BitDominantErr ((uint8_t)0x50) /*!< Bit Dominant Error */ +#define CAN_ErrorCode_CRCErr ((uint8_t)0x60) /*!< CRC Error */ +#define CAN_ErrorCode_SoftwareSetErr ((uint8_t)0x70) /*!< Software Set Error */ +/** + * @} + */ + +/** @defgroup CAN_flags + * @{ + */ +/* If the flag is 0x3XXXXXXX, it means that it can be used with CAN_GetFlagStatus() + and CAN_ClearFlag() functions. */ +/* If the flag is 0x1XXXXXXX, it means that it can only be used with + CAN_GetFlagStatus() function. */ + +/* Transmit Flags */ +#define CAN_FLAG_RQCP0 ((uint32_t)0x38000001) /*!< Request MailBox0 Flag */ +#define CAN_FLAG_RQCP1 ((uint32_t)0x38000100) /*!< Request MailBox1 Flag */ +#define CAN_FLAG_RQCP2 ((uint32_t)0x38010000) /*!< Request MailBox2 Flag */ + +/* Receive Flags */ +#define CAN_FLAG_FMP0 ((uint32_t)0x12000003) /*!< FIFO 0 Message Pending Flag */ +#define CAN_FLAG_FF0 ((uint32_t)0x32000008) /*!< FIFO 0 Full Flag */ +#define CAN_FLAG_FOV0 ((uint32_t)0x32000010) /*!< FIFO 0 Overrun Flag */ +#define CAN_FLAG_FMP1 ((uint32_t)0x14000003) /*!< FIFO 1 Message Pending Flag */ +#define CAN_FLAG_FF1 ((uint32_t)0x34000008) /*!< FIFO 1 Full Flag */ +#define CAN_FLAG_FOV1 ((uint32_t)0x34000010) /*!< FIFO 1 Overrun Flag */ + +/* Operating Mode Flags */ +#define CAN_FLAG_WKU ((uint32_t)0x31000008) /*!< Wake up Flag */ +#define CAN_FLAG_SLAK ((uint32_t)0x31000012) /*!< Sleep acknowledge Flag */ +/* @note When SLAK interrupt is disabled (SLKIE=0), no polling on SLAKI is possible. + In this case the SLAK bit can be polled.*/ + +/* Error Flags */ +#define CAN_FLAG_EWG ((uint32_t)0x10F00001) /*!< Error Warning Flag */ +#define CAN_FLAG_EPV ((uint32_t)0x10F00002) /*!< Error Passive Flag */ +#define CAN_FLAG_BOF ((uint32_t)0x10F00004) /*!< Bus-Off Flag */ +#define CAN_FLAG_LEC ((uint32_t)0x30F00070) /*!< Last error code Flag */ + +#define IS_CAN_GET_FLAG(FLAG) (((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_BOF) || \ + ((FLAG) == CAN_FLAG_EPV) || ((FLAG) == CAN_FLAG_EWG) || \ + ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_FOV0) || \ + ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FMP0) || \ + ((FLAG) == CAN_FLAG_FOV1) || ((FLAG) == CAN_FLAG_FF1) || \ + ((FLAG) == CAN_FLAG_FMP1) || ((FLAG) == CAN_FLAG_RQCP2) || \ + ((FLAG) == CAN_FLAG_RQCP1)|| ((FLAG) == CAN_FLAG_RQCP0) || \ + ((FLAG) == CAN_FLAG_SLAK )) + +#define IS_CAN_CLEAR_FLAG(FLAG)(((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_RQCP2) || \ + ((FLAG) == CAN_FLAG_RQCP1) || ((FLAG) == CAN_FLAG_RQCP0) || \ + ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FOV0) ||\ + ((FLAG) == CAN_FLAG_FF1) || ((FLAG) == CAN_FLAG_FOV1) || \ + ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_SLAK)) +/** + * @} + */ + + +/** @defgroup CAN_interrupts + * @{ + */ +#define CAN_IT_TME ((uint32_t)0x00000001) /*!< Transmit mailbox empty Interrupt*/ + +/* Receive Interrupts */ +#define CAN_IT_FMP0 ((uint32_t)0x00000002) /*!< FIFO 0 message pending Interrupt*/ +#define CAN_IT_FF0 ((uint32_t)0x00000004) /*!< FIFO 0 full Interrupt*/ +#define CAN_IT_FOV0 ((uint32_t)0x00000008) /*!< FIFO 0 overrun Interrupt*/ +#define CAN_IT_FMP1 ((uint32_t)0x00000010) /*!< FIFO 1 message pending Interrupt*/ +#define CAN_IT_FF1 ((uint32_t)0x00000020) /*!< FIFO 1 full Interrupt*/ +#define CAN_IT_FOV1 ((uint32_t)0x00000040) /*!< FIFO 1 overrun Interrupt*/ + +/* Operating Mode Interrupts */ +#define CAN_IT_WKU ((uint32_t)0x00010000) /*!< Wake-up Interrupt*/ +#define CAN_IT_SLK ((uint32_t)0x00020000) /*!< Sleep acknowledge Interrupt*/ + +/* Error Interrupts */ +#define CAN_IT_EWG ((uint32_t)0x00000100) /*!< Error warning Interrupt*/ +#define CAN_IT_EPV ((uint32_t)0x00000200) /*!< Error passive Interrupt*/ +#define CAN_IT_BOF ((uint32_t)0x00000400) /*!< Bus-off Interrupt*/ +#define CAN_IT_LEC ((uint32_t)0x00000800) /*!< Last error code Interrupt*/ +#define CAN_IT_ERR ((uint32_t)0x00008000) /*!< Error Interrupt*/ + +/* Flags named as Interrupts : kept only for FW compatibility */ +#define CAN_IT_RQCP0 CAN_IT_TME +#define CAN_IT_RQCP1 CAN_IT_TME +#define CAN_IT_RQCP2 CAN_IT_TME + + +#define IS_CAN_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FMP0) ||\ + ((IT) == CAN_IT_FF0) || ((IT) == CAN_IT_FOV0) ||\ + ((IT) == CAN_IT_FMP1) || ((IT) == CAN_IT_FF1) ||\ + ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\ + ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ + ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ + ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) + +#define IS_CAN_CLEAR_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FF0) ||\ + ((IT) == CAN_IT_FOV0)|| ((IT) == CAN_IT_FF1) ||\ + ((IT) == CAN_IT_FOV1)|| ((IT) == CAN_IT_EWG) ||\ + ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ + ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ + ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the CAN configuration to the default reset state *****/ +void CAN_DeInit(CAN_TypeDef* CANx); + +/* Initialization and Configuration functions *********************************/ +uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct); +void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct); +void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct); +void CAN_SlaveStartBank(uint8_t CAN_BankNumber); +void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState); +void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState); + +/* CAN Frames Transmission functions ******************************************/ +uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage); +uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox); +void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox); + +/* CAN Frames Reception functions *********************************************/ +void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage); +void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber); +uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber); + +/* Operation modes functions **************************************************/ +uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode); +uint8_t CAN_Sleep(CAN_TypeDef* CANx); +uint8_t CAN_WakeUp(CAN_TypeDef* CANx); + +/* CAN Bus Error management functions *****************************************/ +uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx); +uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx); +uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx); + +/* Interrupts and flags management functions **********************************/ +void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState); +FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG); +void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG); +ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT); +void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_CAN_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_crc.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_crc.h new file mode 100644 index 000000000..9a8c79af0 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_crc.h @@ -0,0 +1,77 @@ +/** + ****************************************************************************** + * @file stm32f4xx_crc.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the CRC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_CRC_H +#define __STM32F4xx_CRC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CRC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup CRC_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +void CRC_ResetDR(void); +uint32_t CRC_CalcCRC(uint32_t Data); +uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength); +uint32_t CRC_GetCRC(void); +void CRC_SetIDRegister(uint8_t IDValue); +uint8_t CRC_GetIDRegister(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_CRC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cryp.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cryp.h new file mode 100644 index 000000000..0b2572a91 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cryp.h @@ -0,0 +1,338 @@ +/** + ****************************************************************************** + * @file stm32f4xx_cryp.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the Cryptographic + * processor(CRYP) firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_CRYP_H +#define __STM32F4xx_CRYP_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CRYP + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief CRYP Init structure definition + */ +typedef struct +{ + uint16_t CRYP_AlgoDir; /*!< Encrypt or Decrypt. This parameter can be a + value of @ref CRYP_Algorithm_Direction */ + uint16_t CRYP_AlgoMode; /*!< TDES-ECB, TDES-CBC, DES-ECB, DES-CBC, AES-ECB, + AES-CBC, AES-CTR, AES-Key. This parameter can be + a value of @ref CRYP_Algorithm_Mode */ + uint16_t CRYP_DataType; /*!< 32-bit data, 16-bit data, bit data or bit-string. + This parameter can be a value of @ref CRYP_Data_Type */ + uint16_t CRYP_KeySize; /*!< Used only in AES mode only : 128, 192 or 256 bit + key length. This parameter can be a value of + @ref CRYP_Key_Size_for_AES_only */ +}CRYP_InitTypeDef; + +/** + * @brief CRYP Key(s) structure definition + */ +typedef struct +{ + uint32_t CRYP_Key0Left; /*!< Key 0 Left */ + uint32_t CRYP_Key0Right; /*!< Key 0 Right */ + uint32_t CRYP_Key1Left; /*!< Key 1 left */ + uint32_t CRYP_Key1Right; /*!< Key 1 Right */ + uint32_t CRYP_Key2Left; /*!< Key 2 left */ + uint32_t CRYP_Key2Right; /*!< Key 2 Right */ + uint32_t CRYP_Key3Left; /*!< Key 3 left */ + uint32_t CRYP_Key3Right; /*!< Key 3 Right */ +}CRYP_KeyInitTypeDef; +/** + * @brief CRYP Initialization Vectors (IV) structure definition + */ +typedef struct +{ + uint32_t CRYP_IV0Left; /*!< Init Vector 0 Left */ + uint32_t CRYP_IV0Right; /*!< Init Vector 0 Right */ + uint32_t CRYP_IV1Left; /*!< Init Vector 1 left */ + uint32_t CRYP_IV1Right; /*!< Init Vector 1 Right */ +}CRYP_IVInitTypeDef; + +/** + * @brief CRYP context swapping structure definition + */ +typedef struct +{ + /*!< Configuration */ + uint32_t CR_bits9to2; + /*!< KEY */ + uint32_t CRYP_IV0LR; + uint32_t CRYP_IV0RR; + uint32_t CRYP_IV1LR; + uint32_t CRYP_IV1RR; + /*!< IV */ + uint32_t CRYP_K0LR; + uint32_t CRYP_K0RR; + uint32_t CRYP_K1LR; + uint32_t CRYP_K1RR; + uint32_t CRYP_K2LR; + uint32_t CRYP_K2RR; + uint32_t CRYP_K3LR; + uint32_t CRYP_K3RR; +}CRYP_Context; + + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup CRYP_Exported_Constants + * @{ + */ + +/** @defgroup CRYP_Algorithm_Direction + * @{ + */ +#define CRYP_AlgoDir_Encrypt ((uint16_t)0x0000) +#define CRYP_AlgoDir_Decrypt ((uint16_t)0x0004) +#define IS_CRYP_ALGODIR(ALGODIR) (((ALGODIR) == CRYP_AlgoDir_Encrypt) || \ + ((ALGODIR) == CRYP_AlgoDir_Decrypt)) + +/** + * @} + */ + +/** @defgroup CRYP_Algorithm_Mode + * @{ + */ + +/*!< TDES Modes */ +#define CRYP_AlgoMode_TDES_ECB ((uint16_t)0x0000) +#define CRYP_AlgoMode_TDES_CBC ((uint16_t)0x0008) + +/*!< DES Modes */ +#define CRYP_AlgoMode_DES_ECB ((uint16_t)0x0010) +#define CRYP_AlgoMode_DES_CBC ((uint16_t)0x0018) + +/*!< AES Modes */ +#define CRYP_AlgoMode_AES_ECB ((uint16_t)0x0020) +#define CRYP_AlgoMode_AES_CBC ((uint16_t)0x0028) +#define CRYP_AlgoMode_AES_CTR ((uint16_t)0x0030) +#define CRYP_AlgoMode_AES_Key ((uint16_t)0x0038) + +#define IS_CRYP_ALGOMODE(ALGOMODE) (((ALGOMODE) == CRYP_AlgoMode_TDES_ECB) || \ + ((ALGOMODE) == CRYP_AlgoMode_TDES_CBC)|| \ + ((ALGOMODE) == CRYP_AlgoMode_DES_ECB)|| \ + ((ALGOMODE) == CRYP_AlgoMode_DES_CBC) || \ + ((ALGOMODE) == CRYP_AlgoMode_AES_ECB) || \ + ((ALGOMODE) == CRYP_AlgoMode_AES_CBC) || \ + ((ALGOMODE) == CRYP_AlgoMode_AES_CTR) || \ + ((ALGOMODE) == CRYP_AlgoMode_AES_Key)) +/** + * @} + */ + +/** @defgroup CRYP_Data_Type + * @{ + */ +#define CRYP_DataType_32b ((uint16_t)0x0000) +#define CRYP_DataType_16b ((uint16_t)0x0040) +#define CRYP_DataType_8b ((uint16_t)0x0080) +#define CRYP_DataType_1b ((uint16_t)0x00C0) +#define IS_CRYP_DATATYPE(DATATYPE) (((DATATYPE) == CRYP_DataType_32b) || \ + ((DATATYPE) == CRYP_DataType_16b)|| \ + ((DATATYPE) == CRYP_DataType_8b)|| \ + ((DATATYPE) == CRYP_DataType_1b)) +/** + * @} + */ + +/** @defgroup CRYP_Key_Size_for_AES_only + * @{ + */ +#define CRYP_KeySize_128b ((uint16_t)0x0000) +#define CRYP_KeySize_192b ((uint16_t)0x0100) +#define CRYP_KeySize_256b ((uint16_t)0x0200) +#define IS_CRYP_KEYSIZE(KEYSIZE) (((KEYSIZE) == CRYP_KeySize_128b)|| \ + ((KEYSIZE) == CRYP_KeySize_192b)|| \ + ((KEYSIZE) == CRYP_KeySize_256b)) +/** + * @} + */ + +/** @defgroup CRYP_flags_definition + * @{ + */ +#define CRYP_FLAG_BUSY ((uint8_t)0x10) /*!< The CRYP core is currently + processing a block of data + or a key preparation (for + AES decryption). */ +#define CRYP_FLAG_IFEM ((uint8_t)0x01) /*!< Input Fifo Empty */ +#define CRYP_FLAG_IFNF ((uint8_t)0x02) /*!< Input Fifo is Not Full */ +#define CRYP_FLAG_INRIS ((uint8_t)0x22) /*!< Raw interrupt pending */ +#define CRYP_FLAG_OFNE ((uint8_t)0x04) /*!< Input Fifo service raw + interrupt status */ +#define CRYP_FLAG_OFFU ((uint8_t)0x08) /*!< Output Fifo is Full */ +#define CRYP_FLAG_OUTRIS ((uint8_t)0x21) /*!< Output Fifo service raw + interrupt status */ + +#define IS_CRYP_GET_FLAG(FLAG) (((FLAG) == CRYP_FLAG_IFEM) || \ + ((FLAG) == CRYP_FLAG_IFNF) || \ + ((FLAG) == CRYP_FLAG_OFNE) || \ + ((FLAG) == CRYP_FLAG_OFFU) || \ + ((FLAG) == CRYP_FLAG_BUSY) || \ + ((FLAG) == CRYP_FLAG_OUTRIS)|| \ + ((FLAG) == CRYP_FLAG_INRIS)) +/** + * @} + */ + +/** @defgroup CRYP_interrupts_definition + * @{ + */ +#define CRYP_IT_INI ((uint8_t)0x01) /*!< IN Fifo Interrupt */ +#define CRYP_IT_OUTI ((uint8_t)0x02) /*!< OUT Fifo Interrupt */ +#define IS_CRYP_CONFIG_IT(IT) ((((IT) & (uint8_t)0xFC) == 0x00) && ((IT) != 0x00)) +#define IS_CRYP_GET_IT(IT) (((IT) == CRYP_IT_INI) || ((IT) == CRYP_IT_OUTI)) + +/** + * @} + */ + +/** @defgroup CRYP_Encryption_Decryption_modes_definition + * @{ + */ +#define MODE_ENCRYPT ((uint8_t)0x01) +#define MODE_DECRYPT ((uint8_t)0x00) + +/** + * @} + */ + +/** @defgroup CRYP_DMA_transfer_requests + * @{ + */ +#define CRYP_DMAReq_DataIN ((uint8_t)0x01) +#define CRYP_DMAReq_DataOUT ((uint8_t)0x02) +#define IS_CRYP_DMAREQ(DMAREQ) ((((DMAREQ) & (uint8_t)0xFC) == 0x00) && ((DMAREQ) != 0x00)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the CRYP configuration to the default reset state ****/ +void CRYP_DeInit(void); + +/* CRYP Initialization and Configuration functions ****************************/ +void CRYP_Init(CRYP_InitTypeDef* CRYP_InitStruct); +void CRYP_StructInit(CRYP_InitTypeDef* CRYP_InitStruct); +void CRYP_KeyInit(CRYP_KeyInitTypeDef* CRYP_KeyInitStruct); +void CRYP_KeyStructInit(CRYP_KeyInitTypeDef* CRYP_KeyInitStruct); +void CRYP_IVInit(CRYP_IVInitTypeDef* CRYP_IVInitStruct); +void CRYP_IVStructInit(CRYP_IVInitTypeDef* CRYP_IVInitStruct); +void CRYP_Cmd(FunctionalState NewState); + +/* CRYP Data processing functions *********************************************/ +void CRYP_DataIn(uint32_t Data); +uint32_t CRYP_DataOut(void); +void CRYP_FIFOFlush(void); + +/* CRYP Context swapping functions ********************************************/ +ErrorStatus CRYP_SaveContext(CRYP_Context* CRYP_ContextSave, + CRYP_KeyInitTypeDef* CRYP_KeyInitStruct); +void CRYP_RestoreContext(CRYP_Context* CRYP_ContextRestore); + +/* CRYP's DMA interface function **********************************************/ +void CRYP_DMACmd(uint8_t CRYP_DMAReq, FunctionalState NewState); + +/* Interrupts and flags management functions **********************************/ +void CRYP_ITConfig(uint8_t CRYP_IT, FunctionalState NewState); +ITStatus CRYP_GetITStatus(uint8_t CRYP_IT); +FlagStatus CRYP_GetFlagStatus(uint8_t CRYP_FLAG); + +/* High Level AES functions **************************************************/ +ErrorStatus CRYP_AES_ECB(uint8_t Mode, + uint8_t *Key, uint16_t Keysize, + uint8_t *Input, uint32_t Ilength, + uint8_t *Output); + +ErrorStatus CRYP_AES_CBC(uint8_t Mode, + uint8_t InitVectors[16], + uint8_t *Key, uint16_t Keysize, + uint8_t *Input, uint32_t Ilength, + uint8_t *Output); + +ErrorStatus CRYP_AES_CTR(uint8_t Mode, + uint8_t InitVectors[16], + uint8_t *Key, uint16_t Keysize, + uint8_t *Input, uint32_t Ilength, + uint8_t *Output); + +/* High Level TDES functions **************************************************/ +ErrorStatus CRYP_TDES_ECB(uint8_t Mode, + uint8_t Key[24], + uint8_t *Input, uint32_t Ilength, + uint8_t *Output); + +ErrorStatus CRYP_TDES_CBC(uint8_t Mode, + uint8_t Key[24], + uint8_t InitVectors[8], + uint8_t *Input, uint32_t Ilength, + uint8_t *Output); + +/* High Level DES functions **************************************************/ +ErrorStatus CRYP_DES_ECB(uint8_t Mode, + uint8_t Key[8], + uint8_t *Input, uint32_t Ilength, + uint8_t *Output); + +ErrorStatus CRYP_DES_CBC(uint8_t Mode, + uint8_t Key[8], + uint8_t InitVectors[8], + uint8_t *Input,uint32_t Ilength, + uint8_t *Output); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_CRYP_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dac.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dac.h new file mode 100644 index 000000000..8d928184a --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dac.h @@ -0,0 +1,298 @@ +/** + ****************************************************************************** + * @file stm32f4xx_dac.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the DAC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_DAC_H +#define __STM32F4xx_DAC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DAC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief DAC Init structure definition + */ + +typedef struct +{ + uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel. + This parameter can be a value of @ref DAC_trigger_selection */ + + uint32_t DAC_WaveGeneration; /*!< Specifies whether DAC channel noise waves or triangle waves + are generated, or whether no wave is generated. + This parameter can be a value of @ref DAC_wave_generation */ + + uint32_t DAC_LFSRUnmask_TriangleAmplitude; /*!< Specifies the LFSR mask for noise wave generation or + the maximum amplitude triangle generation for the DAC channel. + This parameter can be a value of @ref DAC_lfsrunmask_triangleamplitude */ + + uint32_t DAC_OutputBuffer; /*!< Specifies whether the DAC channel output buffer is enabled or disabled. + This parameter can be a value of @ref DAC_output_buffer */ +}DAC_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup DAC_Exported_Constants + * @{ + */ + +/** @defgroup DAC_trigger_selection + * @{ + */ + +#define DAC_Trigger_None ((uint32_t)0x00000000) /*!< Conversion is automatic once the DAC1_DHRxxxx register + has been loaded, and not by external trigger */ +#define DAC_Trigger_T2_TRGO ((uint32_t)0x00000024) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T4_TRGO ((uint32_t)0x0000002C) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T5_TRGO ((uint32_t)0x0000001C) /*!< TIM5 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T6_TRGO ((uint32_t)0x00000004) /*!< TIM6 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T7_TRGO ((uint32_t)0x00000014) /*!< TIM7 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T8_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel */ + +#define DAC_Trigger_Ext_IT9 ((uint32_t)0x00000034) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_Software ((uint32_t)0x0000003C) /*!< Conversion started by software trigger for DAC channel */ + +#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \ + ((TRIGGER) == DAC_Trigger_T6_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T8_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T7_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T5_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T2_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T4_TRGO) || \ + ((TRIGGER) == DAC_Trigger_Ext_IT9) || \ + ((TRIGGER) == DAC_Trigger_Software)) + +/** + * @} + */ + +/** @defgroup DAC_wave_generation + * @{ + */ + +#define DAC_WaveGeneration_None ((uint32_t)0x00000000) +#define DAC_WaveGeneration_Noise ((uint32_t)0x00000040) +#define DAC_WaveGeneration_Triangle ((uint32_t)0x00000080) +#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \ + ((WAVE) == DAC_WaveGeneration_Noise) || \ + ((WAVE) == DAC_WaveGeneration_Triangle)) +/** + * @} + */ + +/** @defgroup DAC_lfsrunmask_triangleamplitude + * @{ + */ + +#define DAC_LFSRUnmask_Bit0 ((uint32_t)0x00000000) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */ +#define DAC_LFSRUnmask_Bits1_0 ((uint32_t)0x00000100) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits2_0 ((uint32_t)0x00000200) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits3_0 ((uint32_t)0x00000300) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits4_0 ((uint32_t)0x00000400) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits5_0 ((uint32_t)0x00000500) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits6_0 ((uint32_t)0x00000600) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits7_0 ((uint32_t)0x00000700) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits8_0 ((uint32_t)0x00000800) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits9_0 ((uint32_t)0x00000900) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits10_0 ((uint32_t)0x00000A00) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits11_0 ((uint32_t)0x00000B00) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */ +#define DAC_TriangleAmplitude_1 ((uint32_t)0x00000000) /*!< Select max triangle amplitude of 1 */ +#define DAC_TriangleAmplitude_3 ((uint32_t)0x00000100) /*!< Select max triangle amplitude of 3 */ +#define DAC_TriangleAmplitude_7 ((uint32_t)0x00000200) /*!< Select max triangle amplitude of 7 */ +#define DAC_TriangleAmplitude_15 ((uint32_t)0x00000300) /*!< Select max triangle amplitude of 15 */ +#define DAC_TriangleAmplitude_31 ((uint32_t)0x00000400) /*!< Select max triangle amplitude of 31 */ +#define DAC_TriangleAmplitude_63 ((uint32_t)0x00000500) /*!< Select max triangle amplitude of 63 */ +#define DAC_TriangleAmplitude_127 ((uint32_t)0x00000600) /*!< Select max triangle amplitude of 127 */ +#define DAC_TriangleAmplitude_255 ((uint32_t)0x00000700) /*!< Select max triangle amplitude of 255 */ +#define DAC_TriangleAmplitude_511 ((uint32_t)0x00000800) /*!< Select max triangle amplitude of 511 */ +#define DAC_TriangleAmplitude_1023 ((uint32_t)0x00000900) /*!< Select max triangle amplitude of 1023 */ +#define DAC_TriangleAmplitude_2047 ((uint32_t)0x00000A00) /*!< Select max triangle amplitude of 2047 */ +#define DAC_TriangleAmplitude_4095 ((uint32_t)0x00000B00) /*!< Select max triangle amplitude of 4095 */ + +#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits1_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits2_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits3_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits4_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits5_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits6_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits7_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits8_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits9_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits10_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits11_0) || \ + ((VALUE) == DAC_TriangleAmplitude_1) || \ + ((VALUE) == DAC_TriangleAmplitude_3) || \ + ((VALUE) == DAC_TriangleAmplitude_7) || \ + ((VALUE) == DAC_TriangleAmplitude_15) || \ + ((VALUE) == DAC_TriangleAmplitude_31) || \ + ((VALUE) == DAC_TriangleAmplitude_63) || \ + ((VALUE) == DAC_TriangleAmplitude_127) || \ + ((VALUE) == DAC_TriangleAmplitude_255) || \ + ((VALUE) == DAC_TriangleAmplitude_511) || \ + ((VALUE) == DAC_TriangleAmplitude_1023) || \ + ((VALUE) == DAC_TriangleAmplitude_2047) || \ + ((VALUE) == DAC_TriangleAmplitude_4095)) +/** + * @} + */ + +/** @defgroup DAC_output_buffer + * @{ + */ + +#define DAC_OutputBuffer_Enable ((uint32_t)0x00000000) +#define DAC_OutputBuffer_Disable ((uint32_t)0x00000002) +#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OutputBuffer_Enable) || \ + ((STATE) == DAC_OutputBuffer_Disable)) +/** + * @} + */ + +/** @defgroup DAC_Channel_selection + * @{ + */ + +#define DAC_Channel_1 ((uint32_t)0x00000000) +#define DAC_Channel_2 ((uint32_t)0x00000010) +#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \ + ((CHANNEL) == DAC_Channel_2)) +/** + * @} + */ + +/** @defgroup DAC_data_alignement + * @{ + */ + +#define DAC_Align_12b_R ((uint32_t)0x00000000) +#define DAC_Align_12b_L ((uint32_t)0x00000004) +#define DAC_Align_8b_R ((uint32_t)0x00000008) +#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \ + ((ALIGN) == DAC_Align_12b_L) || \ + ((ALIGN) == DAC_Align_8b_R)) +/** + * @} + */ + +/** @defgroup DAC_wave_generation + * @{ + */ + +#define DAC_Wave_Noise ((uint32_t)0x00000040) +#define DAC_Wave_Triangle ((uint32_t)0x00000080) +#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \ + ((WAVE) == DAC_Wave_Triangle)) +/** + * @} + */ + +/** @defgroup DAC_data + * @{ + */ + +#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0) +/** + * @} + */ + +/** @defgroup DAC_interrupts_definition + * @{ + */ +#define DAC_IT_DMAUDR ((uint32_t)0x00002000) +#define IS_DAC_IT(IT) (((IT) == DAC_IT_DMAUDR)) + +/** + * @} + */ + +/** @defgroup DAC_flags_definition + * @{ + */ + +#define DAC_FLAG_DMAUDR ((uint32_t)0x00002000) +#define IS_DAC_FLAG(FLAG) (((FLAG) == DAC_FLAG_DMAUDR)) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the DAC configuration to the default reset state *****/ +void DAC_DeInit(void); + +/* DAC channels configuration: trigger, output buffer, data format functions */ +void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct); +void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct); +void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState); +void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState); +void DAC_DualSoftwareTriggerCmd(FunctionalState NewState); +void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState); +void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data); +void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data); +void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1); +uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel); + +/* DMA management functions ***************************************************/ +void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState); + +/* Interrupts and flags management functions **********************************/ +void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState); +FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG); +void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG); +ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT); +void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_DAC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dbgmcu.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dbgmcu.h new file mode 100644 index 000000000..da913375e --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dbgmcu.h @@ -0,0 +1,103 @@ +/** + ****************************************************************************** + * @file stm32f4xx_dbgmcu.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the DBGMCU firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_DBGMCU_H +#define __STM32F4xx_DBGMCU_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DBGMCU + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup DBGMCU_Exported_Constants + * @{ + */ +#define DBGMCU_SLEEP ((uint32_t)0x00000001) +#define DBGMCU_STOP ((uint32_t)0x00000002) +#define DBGMCU_STANDBY ((uint32_t)0x00000004) +#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFF8) == 0x00) && ((PERIPH) != 0x00)) + +#define DBGMCU_TIM2_STOP ((uint32_t)0x00000001) +#define DBGMCU_TIM3_STOP ((uint32_t)0x00000002) +#define DBGMCU_TIM4_STOP ((uint32_t)0x00000004) +#define DBGMCU_TIM5_STOP ((uint32_t)0x00000008) +#define DBGMCU_TIM6_STOP ((uint32_t)0x00000010) +#define DBGMCU_TIM7_STOP ((uint32_t)0x00000020) +#define DBGMCU_TIM12_STOP ((uint32_t)0x00000040) +#define DBGMCU_TIM13_STOP ((uint32_t)0x00000080) +#define DBGMCU_TIM14_STOP ((uint32_t)0x00000100) +#define DBGMCU_RTC_STOP ((uint32_t)0x00000400) +#define DBGMCU_WWDG_STOP ((uint32_t)0x00000800) +#define DBGMCU_IWDG_STOP ((uint32_t)0x00001000) +#define DBGMCU_I2C1_SMBUS_TIMEOUT ((uint32_t)0x00200000) +#define DBGMCU_I2C2_SMBUS_TIMEOUT ((uint32_t)0x00400000) +#define DBGMCU_I2C3_SMBUS_TIMEOUT ((uint32_t)0x00800000) +#define DBGMCU_CAN1_STOP ((uint32_t)0x02000000) +#define DBGMCU_CAN2_STOP ((uint32_t)0x04000000) +#define IS_DBGMCU_APB1PERIPH(PERIPH) ((((PERIPH) & 0xF91FE200) == 0x00) && ((PERIPH) != 0x00)) + +#define DBGMCU_TIM1_STOP ((uint32_t)0x00000001) +#define DBGMCU_TIM8_STOP ((uint32_t)0x00000002) +#define DBGMCU_TIM9_STOP ((uint32_t)0x00010000) +#define DBGMCU_TIM10_STOP ((uint32_t)0x00020000) +#define DBGMCU_TIM11_STOP ((uint32_t)0x00040000) +#define IS_DBGMCU_APB2PERIPH(PERIPH) ((((PERIPH) & 0xFFF8FFFC) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +uint32_t DBGMCU_GetREVID(void); +uint32_t DBGMCU_GetDEVID(void); +void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState); +void DBGMCU_APB1PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState); +void DBGMCU_APB2PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_DBGMCU_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dcmi.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dcmi.h new file mode 100644 index 000000000..c2631d618 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dcmi.h @@ -0,0 +1,306 @@ +/** + ****************************************************************************** + * @file stm32f4xx_dcmi.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the DCMI firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_DCMI_H +#define __STM32F4xx_DCMI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DCMI + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** + * @brief DCMI Init structure definition + */ +typedef struct +{ + uint16_t DCMI_CaptureMode; /*!< Specifies the Capture Mode: Continuous or Snapshot. + This parameter can be a value of @ref DCMI_Capture_Mode */ + + uint16_t DCMI_SynchroMode; /*!< Specifies the Synchronization Mode: Hardware or Embedded. + This parameter can be a value of @ref DCMI_Synchronization_Mode */ + + uint16_t DCMI_PCKPolarity; /*!< Specifies the Pixel clock polarity: Falling or Rising. + This parameter can be a value of @ref DCMI_PIXCK_Polarity */ + + uint16_t DCMI_VSPolarity; /*!< Specifies the Vertical synchronization polarity: High or Low. + This parameter can be a value of @ref DCMI_VSYNC_Polarity */ + + uint16_t DCMI_HSPolarity; /*!< Specifies the Horizontal synchronization polarity: High or Low. + This parameter can be a value of @ref DCMI_HSYNC_Polarity */ + + uint16_t DCMI_CaptureRate; /*!< Specifies the frequency of frame capture: All, 1/2 or 1/4. + This parameter can be a value of @ref DCMI_Capture_Rate */ + + uint16_t DCMI_ExtendedDataMode; /*!< Specifies the data width: 8-bit, 10-bit, 12-bit or 14-bit. + This parameter can be a value of @ref DCMI_Extended_Data_Mode */ +} DCMI_InitTypeDef; + +/** + * @brief DCMI CROP Init structure definition + */ +typedef struct +{ + uint16_t DCMI_VerticalStartLine; /*!< Specifies the Vertical start line count from which the image capture + will start. This parameter can be a value between 0x00 and 0x1FFF */ + + uint16_t DCMI_HorizontalOffsetCount; /*!< Specifies the number of pixel clocks to count before starting a capture. + This parameter can be a value between 0x00 and 0x3FFF */ + + uint16_t DCMI_VerticalLineCount; /*!< Specifies the number of lines to be captured from the starting point. + This parameter can be a value between 0x00 and 0x3FFF */ + + uint16_t DCMI_CaptureCount; /*!< Specifies the number of pixel clocks to be captured from the starting + point on the same line. + This parameter can be a value between 0x00 and 0x3FFF */ +} DCMI_CROPInitTypeDef; + +/** + * @brief DCMI Embedded Synchronisation CODE Init structure definition + */ +typedef struct +{ + uint8_t DCMI_FrameStartCode; /*!< Specifies the code of the frame start delimiter. */ + uint8_t DCMI_LineStartCode; /*!< Specifies the code of the line start delimiter. */ + uint8_t DCMI_LineEndCode; /*!< Specifies the code of the line end delimiter. */ + uint8_t DCMI_FrameEndCode; /*!< Specifies the code of the frame end delimiter. */ +} DCMI_CodesInitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup DCMI_Exported_Constants + * @{ + */ + +/** @defgroup DCMI_Capture_Mode + * @{ + */ +#define DCMI_CaptureMode_Continuous ((uint16_t)0x0000) /*!< The received data are transferred continuously + into the destination memory through the DMA */ +#define DCMI_CaptureMode_SnapShot ((uint16_t)0x0002) /*!< Once activated, the interface waits for the start of + frame and then transfers a single frame through the DMA */ +#define IS_DCMI_CAPTURE_MODE(MODE)(((MODE) == DCMI_CaptureMode_Continuous) || \ + ((MODE) == DCMI_CaptureMode_SnapShot)) +/** + * @} + */ + + +/** @defgroup DCMI_Synchronization_Mode + * @{ + */ +#define DCMI_SynchroMode_Hardware ((uint16_t)0x0000) /*!< Hardware synchronization data capture (frame/line start/stop) + is synchronized with the HSYNC/VSYNC signals */ +#define DCMI_SynchroMode_Embedded ((uint16_t)0x0010) /*!< Embedded synchronization data capture is synchronized with + synchronization codes embedded in the data flow */ +#define IS_DCMI_SYNCHRO(MODE)(((MODE) == DCMI_SynchroMode_Hardware) || \ + ((MODE) == DCMI_SynchroMode_Embedded)) +/** + * @} + */ + + +/** @defgroup DCMI_PIXCK_Polarity + * @{ + */ +#define DCMI_PCKPolarity_Falling ((uint16_t)0x0000) /*!< Pixel clock active on Falling edge */ +#define DCMI_PCKPolarity_Rising ((uint16_t)0x0020) /*!< Pixel clock active on Rising edge */ +#define IS_DCMI_PCKPOLARITY(POLARITY)(((POLARITY) == DCMI_PCKPolarity_Falling) || \ + ((POLARITY) == DCMI_PCKPolarity_Rising)) +/** + * @} + */ + + +/** @defgroup DCMI_VSYNC_Polarity + * @{ + */ +#define DCMI_VSPolarity_Low ((uint16_t)0x0000) /*!< Vertical synchronization active Low */ +#define DCMI_VSPolarity_High ((uint16_t)0x0080) /*!< Vertical synchronization active High */ +#define IS_DCMI_VSPOLARITY(POLARITY)(((POLARITY) == DCMI_VSPolarity_Low) || \ + ((POLARITY) == DCMI_VSPolarity_High)) +/** + * @} + */ + + +/** @defgroup DCMI_HSYNC_Polarity + * @{ + */ +#define DCMI_HSPolarity_Low ((uint16_t)0x0000) /*!< Horizontal synchronization active Low */ +#define DCMI_HSPolarity_High ((uint16_t)0x0040) /*!< Horizontal synchronization active High */ +#define IS_DCMI_HSPOLARITY(POLARITY)(((POLARITY) == DCMI_HSPolarity_Low) || \ + ((POLARITY) == DCMI_HSPolarity_High)) +/** + * @} + */ + + +/** @defgroup DCMI_Capture_Rate + * @{ + */ +#define DCMI_CaptureRate_All_Frame ((uint16_t)0x0000) /*!< All frames are captured */ +#define DCMI_CaptureRate_1of2_Frame ((uint16_t)0x0100) /*!< Every alternate frame captured */ +#define DCMI_CaptureRate_1of4_Frame ((uint16_t)0x0200) /*!< One frame in 4 frames captured */ +#define IS_DCMI_CAPTURE_RATE(RATE) (((RATE) == DCMI_CaptureRate_All_Frame) || \ + ((RATE) == DCMI_CaptureRate_1of2_Frame) ||\ + ((RATE) == DCMI_CaptureRate_1of4_Frame)) +/** + * @} + */ + + +/** @defgroup DCMI_Extended_Data_Mode + * @{ + */ +#define DCMI_ExtendedDataMode_8b ((uint16_t)0x0000) /*!< Interface captures 8-bit data on every pixel clock */ +#define DCMI_ExtendedDataMode_10b ((uint16_t)0x0400) /*!< Interface captures 10-bit data on every pixel clock */ +#define DCMI_ExtendedDataMode_12b ((uint16_t)0x0800) /*!< Interface captures 12-bit data on every pixel clock */ +#define DCMI_ExtendedDataMode_14b ((uint16_t)0x0C00) /*!< Interface captures 14-bit data on every pixel clock */ +#define IS_DCMI_EXTENDED_DATA(DATA)(((DATA) == DCMI_ExtendedDataMode_8b) || \ + ((DATA) == DCMI_ExtendedDataMode_10b) ||\ + ((DATA) == DCMI_ExtendedDataMode_12b) ||\ + ((DATA) == DCMI_ExtendedDataMode_14b)) +/** + * @} + */ + + +/** @defgroup DCMI_interrupt_sources + * @{ + */ +#define DCMI_IT_FRAME ((uint16_t)0x0001) +#define DCMI_IT_OVF ((uint16_t)0x0002) +#define DCMI_IT_ERR ((uint16_t)0x0004) +#define DCMI_IT_VSYNC ((uint16_t)0x0008) +#define DCMI_IT_LINE ((uint16_t)0x0010) +#define IS_DCMI_CONFIG_IT(IT) ((((IT) & (uint16_t)0xFFE0) == 0x0000) && ((IT) != 0x0000)) +#define IS_DCMI_GET_IT(IT) (((IT) == DCMI_IT_FRAME) || \ + ((IT) == DCMI_IT_OVF) || \ + ((IT) == DCMI_IT_ERR) || \ + ((IT) == DCMI_IT_VSYNC) || \ + ((IT) == DCMI_IT_LINE)) +/** + * @} + */ + + +/** @defgroup DCMI_Flags + * @{ + */ +/** + * @brief DCMI SR register + */ +#define DCMI_FLAG_HSYNC ((uint16_t)0x2001) +#define DCMI_FLAG_VSYNC ((uint16_t)0x2002) +#define DCMI_FLAG_FNE ((uint16_t)0x2004) +/** + * @brief DCMI RISR register + */ +#define DCMI_FLAG_FRAMERI ((uint16_t)0x0001) +#define DCMI_FLAG_OVFRI ((uint16_t)0x0002) +#define DCMI_FLAG_ERRRI ((uint16_t)0x0004) +#define DCMI_FLAG_VSYNCRI ((uint16_t)0x0008) +#define DCMI_FLAG_LINERI ((uint16_t)0x0010) +/** + * @brief DCMI MISR register + */ +#define DCMI_FLAG_FRAMEMI ((uint16_t)0x1001) +#define DCMI_FLAG_OVFMI ((uint16_t)0x1002) +#define DCMI_FLAG_ERRMI ((uint16_t)0x1004) +#define DCMI_FLAG_VSYNCMI ((uint16_t)0x1008) +#define DCMI_FLAG_LINEMI ((uint16_t)0x1010) +#define IS_DCMI_GET_FLAG(FLAG) (((FLAG) == DCMI_FLAG_HSYNC) || \ + ((FLAG) == DCMI_FLAG_VSYNC) || \ + ((FLAG) == DCMI_FLAG_FNE) || \ + ((FLAG) == DCMI_FLAG_FRAMERI) || \ + ((FLAG) == DCMI_FLAG_OVFRI) || \ + ((FLAG) == DCMI_FLAG_ERRRI) || \ + ((FLAG) == DCMI_FLAG_VSYNCRI) || \ + ((FLAG) == DCMI_FLAG_LINERI) || \ + ((FLAG) == DCMI_FLAG_FRAMEMI) || \ + ((FLAG) == DCMI_FLAG_OVFMI) || \ + ((FLAG) == DCMI_FLAG_ERRMI) || \ + ((FLAG) == DCMI_FLAG_VSYNCMI) || \ + ((FLAG) == DCMI_FLAG_LINEMI)) + +#define IS_DCMI_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFFE0) == 0x0000) && ((FLAG) != 0x0000)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the DCMI configuration to the default reset state ****/ +void DCMI_DeInit(void); + +/* Initialization and Configuration functions *********************************/ +void DCMI_Init(DCMI_InitTypeDef* DCMI_InitStruct); +void DCMI_StructInit(DCMI_InitTypeDef* DCMI_InitStruct); +void DCMI_CROPConfig(DCMI_CROPInitTypeDef* DCMI_CROPInitStruct); +void DCMI_CROPCmd(FunctionalState NewState); +void DCMI_SetEmbeddedSynchroCodes(DCMI_CodesInitTypeDef* DCMI_CodesInitStruct); +void DCMI_JPEGCmd(FunctionalState NewState); + +/* Image capture functions ****************************************************/ +void DCMI_Cmd(FunctionalState NewState); +void DCMI_CaptureCmd(FunctionalState NewState); +uint32_t DCMI_ReadData(void); + +/* Interrupts and flags management functions **********************************/ +void DCMI_ITConfig(uint16_t DCMI_IT, FunctionalState NewState); +FlagStatus DCMI_GetFlagStatus(uint16_t DCMI_FLAG); +void DCMI_ClearFlag(uint16_t DCMI_FLAG); +ITStatus DCMI_GetITStatus(uint16_t DCMI_IT); +void DCMI_ClearITPendingBit(uint16_t DCMI_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_DCMI_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma.h new file mode 100644 index 000000000..a081e3dff --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma.h @@ -0,0 +1,603 @@ +/** + ****************************************************************************** + * @file stm32f4xx_dma.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the DMA firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_DMA_H +#define __STM32F4xx_DMA_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DMA + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief DMA Init structure definition + */ + +typedef struct +{ + uint32_t DMA_Channel; /*!< Specifies the channel used for the specified stream. + This parameter can be a value of @ref DMA_channel */ + + uint32_t DMA_PeripheralBaseAddr; /*!< Specifies the peripheral base address for DMAy Streamx. */ + + uint32_t DMA_Memory0BaseAddr; /*!< Specifies the memory 0 base address for DMAy Streamx. + This memory is the default memory used when double buffer mode is + not enabled. */ + + uint32_t DMA_DIR; /*!< Specifies if the data will be transferred from memory to peripheral, + from memory to memory or from peripheral to memory. + This parameter can be a value of @ref DMA_data_transfer_direction */ + + uint32_t DMA_BufferSize; /*!< Specifies the buffer size, in data unit, of the specified Stream. + The data unit is equal to the configuration set in DMA_PeripheralDataSize + or DMA_MemoryDataSize members depending in the transfer direction. */ + + uint32_t DMA_PeripheralInc; /*!< Specifies whether the Peripheral address register should be incremented or not. + This parameter can be a value of @ref DMA_peripheral_incremented_mode */ + + uint32_t DMA_MemoryInc; /*!< Specifies whether the memory address register should be incremented or not. + This parameter can be a value of @ref DMA_memory_incremented_mode */ + + uint32_t DMA_PeripheralDataSize; /*!< Specifies the Peripheral data width. + This parameter can be a value of @ref DMA_peripheral_data_size */ + + uint32_t DMA_MemoryDataSize; /*!< Specifies the Memory data width. + This parameter can be a value of @ref DMA_memory_data_size */ + + uint32_t DMA_Mode; /*!< Specifies the operation mode of the DMAy Streamx. + This parameter can be a value of @ref DMA_circular_normal_mode + @note The circular buffer mode cannot be used if the memory-to-memory + data transfer is configured on the selected Stream */ + + uint32_t DMA_Priority; /*!< Specifies the software priority for the DMAy Streamx. + This parameter can be a value of @ref DMA_priority_level */ + + uint32_t DMA_FIFOMode; /*!< Specifies if the FIFO mode or Direct mode will be used for the specified Stream. + This parameter can be a value of @ref DMA_fifo_direct_mode + @note The Direct mode (FIFO mode disabled) cannot be used if the + memory-to-memory data transfer is configured on the selected Stream */ + + uint32_t DMA_FIFOThreshold; /*!< Specifies the FIFO threshold level. + This parameter can be a value of @ref DMA_fifo_threshold_level */ + + uint32_t DMA_MemoryBurst; /*!< Specifies the Burst transfer configuration for the memory transfers. + It specifies the amount of data to be transferred in a single non interruptable + transaction. This parameter can be a value of @ref DMA_memory_burst + @note The burst mode is possible only if the address Increment mode is enabled. */ + + uint32_t DMA_PeripheralBurst; /*!< Specifies the Burst transfer configuration for the peripheral transfers. + It specifies the amount of data to be transferred in a single non interruptable + transaction. This parameter can be a value of @ref DMA_peripheral_burst + @note The burst mode is possible only if the address Increment mode is enabled. */ +}DMA_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup DMA_Exported_Constants + * @{ + */ + +#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Stream0) || \ + ((PERIPH) == DMA1_Stream1) || \ + ((PERIPH) == DMA1_Stream2) || \ + ((PERIPH) == DMA1_Stream3) || \ + ((PERIPH) == DMA1_Stream4) || \ + ((PERIPH) == DMA1_Stream5) || \ + ((PERIPH) == DMA1_Stream6) || \ + ((PERIPH) == DMA1_Stream7) || \ + ((PERIPH) == DMA2_Stream0) || \ + ((PERIPH) == DMA2_Stream1) || \ + ((PERIPH) == DMA2_Stream2) || \ + ((PERIPH) == DMA2_Stream3) || \ + ((PERIPH) == DMA2_Stream4) || \ + ((PERIPH) == DMA2_Stream5) || \ + ((PERIPH) == DMA2_Stream6) || \ + ((PERIPH) == DMA2_Stream7)) + +#define IS_DMA_ALL_CONTROLLER(CONTROLLER) (((CONTROLLER) == DMA1) || \ + ((CONTROLLER) == DMA2)) + +/** @defgroup DMA_channel + * @{ + */ +#define DMA_Channel_0 ((uint32_t)0x00000000) +#define DMA_Channel_1 ((uint32_t)0x02000000) +#define DMA_Channel_2 ((uint32_t)0x04000000) +#define DMA_Channel_3 ((uint32_t)0x06000000) +#define DMA_Channel_4 ((uint32_t)0x08000000) +#define DMA_Channel_5 ((uint32_t)0x0A000000) +#define DMA_Channel_6 ((uint32_t)0x0C000000) +#define DMA_Channel_7 ((uint32_t)0x0E000000) + +#define IS_DMA_CHANNEL(CHANNEL) (((CHANNEL) == DMA_Channel_0) || \ + ((CHANNEL) == DMA_Channel_1) || \ + ((CHANNEL) == DMA_Channel_2) || \ + ((CHANNEL) == DMA_Channel_3) || \ + ((CHANNEL) == DMA_Channel_4) || \ + ((CHANNEL) == DMA_Channel_5) || \ + ((CHANNEL) == DMA_Channel_6) || \ + ((CHANNEL) == DMA_Channel_7)) +/** + * @} + */ + + +/** @defgroup DMA_data_transfer_direction + * @{ + */ +#define DMA_DIR_PeripheralToMemory ((uint32_t)0x00000000) +#define DMA_DIR_MemoryToPeripheral ((uint32_t)0x00000040) +#define DMA_DIR_MemoryToMemory ((uint32_t)0x00000080) + +#define IS_DMA_DIRECTION(DIRECTION) (((DIRECTION) == DMA_DIR_PeripheralToMemory ) || \ + ((DIRECTION) == DMA_DIR_MemoryToPeripheral) || \ + ((DIRECTION) == DMA_DIR_MemoryToMemory)) +/** + * @} + */ + + +/** @defgroup DMA_data_buffer_size + * @{ + */ +#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000)) +/** + * @} + */ + + +/** @defgroup DMA_peripheral_incremented_mode + * @{ + */ +#define DMA_PeripheralInc_Enable ((uint32_t)0x00000200) +#define DMA_PeripheralInc_Disable ((uint32_t)0x00000000) + +#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \ + ((STATE) == DMA_PeripheralInc_Disable)) +/** + * @} + */ + + +/** @defgroup DMA_memory_incremented_mode + * @{ + */ +#define DMA_MemoryInc_Enable ((uint32_t)0x00000400) +#define DMA_MemoryInc_Disable ((uint32_t)0x00000000) + +#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \ + ((STATE) == DMA_MemoryInc_Disable)) +/** + * @} + */ + + +/** @defgroup DMA_peripheral_data_size + * @{ + */ +#define DMA_PeripheralDataSize_Byte ((uint32_t)0x00000000) +#define DMA_PeripheralDataSize_HalfWord ((uint32_t)0x00000800) +#define DMA_PeripheralDataSize_Word ((uint32_t)0x00001000) + +#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \ + ((SIZE) == DMA_PeripheralDataSize_HalfWord) || \ + ((SIZE) == DMA_PeripheralDataSize_Word)) +/** + * @} + */ + + +/** @defgroup DMA_memory_data_size + * @{ + */ +#define DMA_MemoryDataSize_Byte ((uint32_t)0x00000000) +#define DMA_MemoryDataSize_HalfWord ((uint32_t)0x00002000) +#define DMA_MemoryDataSize_Word ((uint32_t)0x00004000) + +#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \ + ((SIZE) == DMA_MemoryDataSize_HalfWord) || \ + ((SIZE) == DMA_MemoryDataSize_Word )) +/** + * @} + */ + + +/** @defgroup DMA_circular_normal_mode + * @{ + */ +#define DMA_Mode_Normal ((uint32_t)0x00000000) +#define DMA_Mode_Circular ((uint32_t)0x00000100) + +#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Normal ) || \ + ((MODE) == DMA_Mode_Circular)) +/** + * @} + */ + + +/** @defgroup DMA_priority_level + * @{ + */ +#define DMA_Priority_Low ((uint32_t)0x00000000) +#define DMA_Priority_Medium ((uint32_t)0x00010000) +#define DMA_Priority_High ((uint32_t)0x00020000) +#define DMA_Priority_VeryHigh ((uint32_t)0x00030000) + +#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_Low ) || \ + ((PRIORITY) == DMA_Priority_Medium) || \ + ((PRIORITY) == DMA_Priority_High) || \ + ((PRIORITY) == DMA_Priority_VeryHigh)) +/** + * @} + */ + + +/** @defgroup DMA_fifo_direct_mode + * @{ + */ +#define DMA_FIFOMode_Disable ((uint32_t)0x00000000) +#define DMA_FIFOMode_Enable ((uint32_t)0x00000004) + +#define IS_DMA_FIFO_MODE_STATE(STATE) (((STATE) == DMA_FIFOMode_Disable ) || \ + ((STATE) == DMA_FIFOMode_Enable)) +/** + * @} + */ + + +/** @defgroup DMA_fifo_threshold_level + * @{ + */ +#define DMA_FIFOThreshold_1QuarterFull ((uint32_t)0x00000000) +#define DMA_FIFOThreshold_HalfFull ((uint32_t)0x00000001) +#define DMA_FIFOThreshold_3QuartersFull ((uint32_t)0x00000002) +#define DMA_FIFOThreshold_Full ((uint32_t)0x00000003) + +#define IS_DMA_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == DMA_FIFOThreshold_1QuarterFull ) || \ + ((THRESHOLD) == DMA_FIFOThreshold_HalfFull) || \ + ((THRESHOLD) == DMA_FIFOThreshold_3QuartersFull) || \ + ((THRESHOLD) == DMA_FIFOThreshold_Full)) +/** + * @} + */ + + +/** @defgroup DMA_memory_burst + * @{ + */ +#define DMA_MemoryBurst_Single ((uint32_t)0x00000000) +#define DMA_MemoryBurst_INC4 ((uint32_t)0x00800000) +#define DMA_MemoryBurst_INC8 ((uint32_t)0x01000000) +#define DMA_MemoryBurst_INC16 ((uint32_t)0x01800000) + +#define IS_DMA_MEMORY_BURST(BURST) (((BURST) == DMA_MemoryBurst_Single) || \ + ((BURST) == DMA_MemoryBurst_INC4) || \ + ((BURST) == DMA_MemoryBurst_INC8) || \ + ((BURST) == DMA_MemoryBurst_INC16)) +/** + * @} + */ + + +/** @defgroup DMA_peripheral_burst + * @{ + */ +#define DMA_PeripheralBurst_Single ((uint32_t)0x00000000) +#define DMA_PeripheralBurst_INC4 ((uint32_t)0x00200000) +#define DMA_PeripheralBurst_INC8 ((uint32_t)0x00400000) +#define DMA_PeripheralBurst_INC16 ((uint32_t)0x00600000) + +#define IS_DMA_PERIPHERAL_BURST(BURST) (((BURST) == DMA_PeripheralBurst_Single) || \ + ((BURST) == DMA_PeripheralBurst_INC4) || \ + ((BURST) == DMA_PeripheralBurst_INC8) || \ + ((BURST) == DMA_PeripheralBurst_INC16)) +/** + * @} + */ + + +/** @defgroup DMA_fifo_status_level + * @{ + */ +#define DMA_FIFOStatus_Less1QuarterFull ((uint32_t)0x00000000 << 3) +#define DMA_FIFOStatus_1QuarterFull ((uint32_t)0x00000001 << 3) +#define DMA_FIFOStatus_HalfFull ((uint32_t)0x00000002 << 3) +#define DMA_FIFOStatus_3QuartersFull ((uint32_t)0x00000003 << 3) +#define DMA_FIFOStatus_Empty ((uint32_t)0x00000004 << 3) +#define DMA_FIFOStatus_Full ((uint32_t)0x00000005 << 3) + +#define IS_DMA_FIFO_STATUS(STATUS) (((STATUS) == DMA_FIFOStatus_Less1QuarterFull ) || \ + ((STATUS) == DMA_FIFOStatus_HalfFull) || \ + ((STATUS) == DMA_FIFOStatus_1QuarterFull) || \ + ((STATUS) == DMA_FIFOStatus_3QuartersFull) || \ + ((STATUS) == DMA_FIFOStatus_Full) || \ + ((STATUS) == DMA_FIFOStatus_Empty)) +/** + * @} + */ + +/** @defgroup DMA_flags_definition + * @{ + */ +#define DMA_FLAG_FEIF0 ((uint32_t)0x10800001) +#define DMA_FLAG_DMEIF0 ((uint32_t)0x10800004) +#define DMA_FLAG_TEIF0 ((uint32_t)0x10000008) +#define DMA_FLAG_HTIF0 ((uint32_t)0x10000010) +#define DMA_FLAG_TCIF0 ((uint32_t)0x10000020) +#define DMA_FLAG_FEIF1 ((uint32_t)0x10000040) +#define DMA_FLAG_DMEIF1 ((uint32_t)0x10000100) +#define DMA_FLAG_TEIF1 ((uint32_t)0x10000200) +#define DMA_FLAG_HTIF1 ((uint32_t)0x10000400) +#define DMA_FLAG_TCIF1 ((uint32_t)0x10000800) +#define DMA_FLAG_FEIF2 ((uint32_t)0x10010000) +#define DMA_FLAG_DMEIF2 ((uint32_t)0x10040000) +#define DMA_FLAG_TEIF2 ((uint32_t)0x10080000) +#define DMA_FLAG_HTIF2 ((uint32_t)0x10100000) +#define DMA_FLAG_TCIF2 ((uint32_t)0x10200000) +#define DMA_FLAG_FEIF3 ((uint32_t)0x10400000) +#define DMA_FLAG_DMEIF3 ((uint32_t)0x11000000) +#define DMA_FLAG_TEIF3 ((uint32_t)0x12000000) +#define DMA_FLAG_HTIF3 ((uint32_t)0x14000000) +#define DMA_FLAG_TCIF3 ((uint32_t)0x18000000) +#define DMA_FLAG_FEIF4 ((uint32_t)0x20000001) +#define DMA_FLAG_DMEIF4 ((uint32_t)0x20000004) +#define DMA_FLAG_TEIF4 ((uint32_t)0x20000008) +#define DMA_FLAG_HTIF4 ((uint32_t)0x20000010) +#define DMA_FLAG_TCIF4 ((uint32_t)0x20000020) +#define DMA_FLAG_FEIF5 ((uint32_t)0x20000040) +#define DMA_FLAG_DMEIF5 ((uint32_t)0x20000100) +#define DMA_FLAG_TEIF5 ((uint32_t)0x20000200) +#define DMA_FLAG_HTIF5 ((uint32_t)0x20000400) +#define DMA_FLAG_TCIF5 ((uint32_t)0x20000800) +#define DMA_FLAG_FEIF6 ((uint32_t)0x20010000) +#define DMA_FLAG_DMEIF6 ((uint32_t)0x20040000) +#define DMA_FLAG_TEIF6 ((uint32_t)0x20080000) +#define DMA_FLAG_HTIF6 ((uint32_t)0x20100000) +#define DMA_FLAG_TCIF6 ((uint32_t)0x20200000) +#define DMA_FLAG_FEIF7 ((uint32_t)0x20400000) +#define DMA_FLAG_DMEIF7 ((uint32_t)0x21000000) +#define DMA_FLAG_TEIF7 ((uint32_t)0x22000000) +#define DMA_FLAG_HTIF7 ((uint32_t)0x24000000) +#define DMA_FLAG_TCIF7 ((uint32_t)0x28000000) + +#define IS_DMA_CLEAR_FLAG(FLAG) ((((FLAG) & 0x30000000) != 0x30000000) && (((FLAG) & 0x30000000) != 0) && \ + (((FLAG) & 0xC082F082) == 0x00) && ((FLAG) != 0x00)) + +#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA_FLAG_TCIF0) || ((FLAG) == DMA_FLAG_HTIF0) || \ + ((FLAG) == DMA_FLAG_TEIF0) || ((FLAG) == DMA_FLAG_DMEIF0) || \ + ((FLAG) == DMA_FLAG_FEIF0) || ((FLAG) == DMA_FLAG_TCIF1) || \ + ((FLAG) == DMA_FLAG_HTIF1) || ((FLAG) == DMA_FLAG_TEIF1) || \ + ((FLAG) == DMA_FLAG_DMEIF1) || ((FLAG) == DMA_FLAG_FEIF1) || \ + ((FLAG) == DMA_FLAG_TCIF2) || ((FLAG) == DMA_FLAG_HTIF2) || \ + ((FLAG) == DMA_FLAG_TEIF2) || ((FLAG) == DMA_FLAG_DMEIF2) || \ + ((FLAG) == DMA_FLAG_FEIF2) || ((FLAG) == DMA_FLAG_TCIF3) || \ + ((FLAG) == DMA_FLAG_HTIF3) || ((FLAG) == DMA_FLAG_TEIF3) || \ + ((FLAG) == DMA_FLAG_DMEIF3) || ((FLAG) == DMA_FLAG_FEIF3) || \ + ((FLAG) == DMA_FLAG_TCIF4) || ((FLAG) == DMA_FLAG_HTIF4) || \ + ((FLAG) == DMA_FLAG_TEIF4) || ((FLAG) == DMA_FLAG_DMEIF4) || \ + ((FLAG) == DMA_FLAG_FEIF4) || ((FLAG) == DMA_FLAG_TCIF5) || \ + ((FLAG) == DMA_FLAG_HTIF5) || ((FLAG) == DMA_FLAG_TEIF5) || \ + ((FLAG) == DMA_FLAG_DMEIF5) || ((FLAG) == DMA_FLAG_FEIF5) || \ + ((FLAG) == DMA_FLAG_TCIF6) || ((FLAG) == DMA_FLAG_HTIF6) || \ + ((FLAG) == DMA_FLAG_TEIF6) || ((FLAG) == DMA_FLAG_DMEIF6) || \ + ((FLAG) == DMA_FLAG_FEIF6) || ((FLAG) == DMA_FLAG_TCIF7) || \ + ((FLAG) == DMA_FLAG_HTIF7) || ((FLAG) == DMA_FLAG_TEIF7) || \ + ((FLAG) == DMA_FLAG_DMEIF7) || ((FLAG) == DMA_FLAG_FEIF7)) +/** + * @} + */ + + +/** @defgroup DMA_interrupt_enable_definitions + * @{ + */ +#define DMA_IT_TC ((uint32_t)0x00000010) +#define DMA_IT_HT ((uint32_t)0x00000008) +#define DMA_IT_TE ((uint32_t)0x00000004) +#define DMA_IT_DME ((uint32_t)0x00000002) +#define DMA_IT_FE ((uint32_t)0x00000080) + +#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFF61) == 0x00) && ((IT) != 0x00)) +/** + * @} + */ + + +/** @defgroup DMA_interrupts_definitions + * @{ + */ +#define DMA_IT_FEIF0 ((uint32_t)0x90000001) +#define DMA_IT_DMEIF0 ((uint32_t)0x10001004) +#define DMA_IT_TEIF0 ((uint32_t)0x10002008) +#define DMA_IT_HTIF0 ((uint32_t)0x10004010) +#define DMA_IT_TCIF0 ((uint32_t)0x10008020) +#define DMA_IT_FEIF1 ((uint32_t)0x90000040) +#define DMA_IT_DMEIF1 ((uint32_t)0x10001100) +#define DMA_IT_TEIF1 ((uint32_t)0x10002200) +#define DMA_IT_HTIF1 ((uint32_t)0x10004400) +#define DMA_IT_TCIF1 ((uint32_t)0x10008800) +#define DMA_IT_FEIF2 ((uint32_t)0x90010000) +#define DMA_IT_DMEIF2 ((uint32_t)0x10041000) +#define DMA_IT_TEIF2 ((uint32_t)0x10082000) +#define DMA_IT_HTIF2 ((uint32_t)0x10104000) +#define DMA_IT_TCIF2 ((uint32_t)0x10208000) +#define DMA_IT_FEIF3 ((uint32_t)0x90400000) +#define DMA_IT_DMEIF3 ((uint32_t)0x11001000) +#define DMA_IT_TEIF3 ((uint32_t)0x12002000) +#define DMA_IT_HTIF3 ((uint32_t)0x14004000) +#define DMA_IT_TCIF3 ((uint32_t)0x18008000) +#define DMA_IT_FEIF4 ((uint32_t)0xA0000001) +#define DMA_IT_DMEIF4 ((uint32_t)0x20001004) +#define DMA_IT_TEIF4 ((uint32_t)0x20002008) +#define DMA_IT_HTIF4 ((uint32_t)0x20004010) +#define DMA_IT_TCIF4 ((uint32_t)0x20008020) +#define DMA_IT_FEIF5 ((uint32_t)0xA0000040) +#define DMA_IT_DMEIF5 ((uint32_t)0x20001100) +#define DMA_IT_TEIF5 ((uint32_t)0x20002200) +#define DMA_IT_HTIF5 ((uint32_t)0x20004400) +#define DMA_IT_TCIF5 ((uint32_t)0x20008800) +#define DMA_IT_FEIF6 ((uint32_t)0xA0010000) +#define DMA_IT_DMEIF6 ((uint32_t)0x20041000) +#define DMA_IT_TEIF6 ((uint32_t)0x20082000) +#define DMA_IT_HTIF6 ((uint32_t)0x20104000) +#define DMA_IT_TCIF6 ((uint32_t)0x20208000) +#define DMA_IT_FEIF7 ((uint32_t)0xA0400000) +#define DMA_IT_DMEIF7 ((uint32_t)0x21001000) +#define DMA_IT_TEIF7 ((uint32_t)0x22002000) +#define DMA_IT_HTIF7 ((uint32_t)0x24004000) +#define DMA_IT_TCIF7 ((uint32_t)0x28008000) + +#define IS_DMA_CLEAR_IT(IT) ((((IT) & 0x30000000) != 0x30000000) && \ + (((IT) & 0x30000000) != 0) && ((IT) != 0x00) && \ + (((IT) & 0x40820082) == 0x00)) + +#define IS_DMA_GET_IT(IT) (((IT) == DMA_IT_TCIF0) || ((IT) == DMA_IT_HTIF0) || \ + ((IT) == DMA_IT_TEIF0) || ((IT) == DMA_IT_DMEIF0) || \ + ((IT) == DMA_IT_FEIF0) || ((IT) == DMA_IT_TCIF1) || \ + ((IT) == DMA_IT_HTIF1) || ((IT) == DMA_IT_TEIF1) || \ + ((IT) == DMA_IT_DMEIF1)|| ((IT) == DMA_IT_FEIF1) || \ + ((IT) == DMA_IT_TCIF2) || ((IT) == DMA_IT_HTIF2) || \ + ((IT) == DMA_IT_TEIF2) || ((IT) == DMA_IT_DMEIF2) || \ + ((IT) == DMA_IT_FEIF2) || ((IT) == DMA_IT_TCIF3) || \ + ((IT) == DMA_IT_HTIF3) || ((IT) == DMA_IT_TEIF3) || \ + ((IT) == DMA_IT_DMEIF3)|| ((IT) == DMA_IT_FEIF3) || \ + ((IT) == DMA_IT_TCIF4) || ((IT) == DMA_IT_HTIF4) || \ + ((IT) == DMA_IT_TEIF4) || ((IT) == DMA_IT_DMEIF4) || \ + ((IT) == DMA_IT_FEIF4) || ((IT) == DMA_IT_TCIF5) || \ + ((IT) == DMA_IT_HTIF5) || ((IT) == DMA_IT_TEIF5) || \ + ((IT) == DMA_IT_DMEIF5)|| ((IT) == DMA_IT_FEIF5) || \ + ((IT) == DMA_IT_TCIF6) || ((IT) == DMA_IT_HTIF6) || \ + ((IT) == DMA_IT_TEIF6) || ((IT) == DMA_IT_DMEIF6) || \ + ((IT) == DMA_IT_FEIF6) || ((IT) == DMA_IT_TCIF7) || \ + ((IT) == DMA_IT_HTIF7) || ((IT) == DMA_IT_TEIF7) || \ + ((IT) == DMA_IT_DMEIF7)|| ((IT) == DMA_IT_FEIF7)) +/** + * @} + */ + + +/** @defgroup DMA_peripheral_increment_offset + * @{ + */ +#define DMA_PINCOS_Psize ((uint32_t)0x00000000) +#define DMA_PINCOS_WordAligned ((uint32_t)0x00008000) + +#define IS_DMA_PINCOS_SIZE(SIZE) (((SIZE) == DMA_PINCOS_Psize) || \ + ((SIZE) == DMA_PINCOS_WordAligned)) +/** + * @} + */ + + +/** @defgroup DMA_flow_controller_definitions + * @{ + */ +#define DMA_FlowCtrl_Memory ((uint32_t)0x00000000) +#define DMA_FlowCtrl_Peripheral ((uint32_t)0x00000020) + +#define IS_DMA_FLOW_CTRL(CTRL) (((CTRL) == DMA_FlowCtrl_Memory) || \ + ((CTRL) == DMA_FlowCtrl_Peripheral)) +/** + * @} + */ + + +/** @defgroup DMA_memory_targets_definitions + * @{ + */ +#define DMA_Memory_0 ((uint32_t)0x00000000) +#define DMA_Memory_1 ((uint32_t)0x00080000) + +#define IS_DMA_CURRENT_MEM(MEM) (((MEM) == DMA_Memory_0) || ((MEM) == DMA_Memory_1)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the DMA configuration to the default reset state *****/ +void DMA_DeInit(DMA_Stream_TypeDef* DMAy_Streamx); + +/* Initialization and Configuration functions *********************************/ +void DMA_Init(DMA_Stream_TypeDef* DMAy_Streamx, DMA_InitTypeDef* DMA_InitStruct); +void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct); +void DMA_Cmd(DMA_Stream_TypeDef* DMAy_Streamx, FunctionalState NewState); + +/* Optional Configuration functions *******************************************/ +void DMA_PeriphIncOffsetSizeConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_Pincos); +void DMA_FlowControllerConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FlowCtrl); + +/* Data Counter functions *****************************************************/ +void DMA_SetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx, uint16_t Counter); +uint16_t DMA_GetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx); + +/* Double Buffer mode functions ***********************************************/ +void DMA_DoubleBufferModeConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t Memory1BaseAddr, + uint32_t DMA_CurrentMemory); +void DMA_DoubleBufferModeCmd(DMA_Stream_TypeDef* DMAy_Streamx, FunctionalState NewState); +void DMA_MemoryTargetConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t MemoryBaseAddr, + uint32_t DMA_MemoryTarget); +uint32_t DMA_GetCurrentMemoryTarget(DMA_Stream_TypeDef* DMAy_Streamx); + +/* Interrupts and flags management functions **********************************/ +FunctionalState DMA_GetCmdStatus(DMA_Stream_TypeDef* DMAy_Streamx); +uint32_t DMA_GetFIFOStatus(DMA_Stream_TypeDef* DMAy_Streamx); +FlagStatus DMA_GetFlagStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG); +void DMA_ClearFlag(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG); +void DMA_ITConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT, FunctionalState NewState); +ITStatus DMA_GetITStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT); +void DMA_ClearITPendingBit(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_DMA_H */ + +/** + * @} + */ + +/** + * @} + */ + + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_exti.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_exti.h new file mode 100644 index 000000000..d103540f8 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_exti.h @@ -0,0 +1,177 @@ +/** + ****************************************************************************** + * @file stm32f4xx_exti.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the EXTI firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_EXTI_H +#define __STM32F4xx_EXTI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup EXTI + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief EXTI mode enumeration + */ + +typedef enum +{ + EXTI_Mode_Interrupt = 0x00, + EXTI_Mode_Event = 0x04 +}EXTIMode_TypeDef; + +#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event)) + +/** + * @brief EXTI Trigger enumeration + */ + +typedef enum +{ + EXTI_Trigger_Rising = 0x08, + EXTI_Trigger_Falling = 0x0C, + EXTI_Trigger_Rising_Falling = 0x10 +}EXTITrigger_TypeDef; + +#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \ + ((TRIGGER) == EXTI_Trigger_Falling) || \ + ((TRIGGER) == EXTI_Trigger_Rising_Falling)) +/** + * @brief EXTI Init Structure definition + */ + +typedef struct +{ + uint32_t EXTI_Line; /*!< Specifies the EXTI lines to be enabled or disabled. + This parameter can be any combination value of @ref EXTI_Lines */ + + EXTIMode_TypeDef EXTI_Mode; /*!< Specifies the mode for the EXTI lines. + This parameter can be a value of @ref EXTIMode_TypeDef */ + + EXTITrigger_TypeDef EXTI_Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines. + This parameter can be a value of @ref EXTITrigger_TypeDef */ + + FunctionalState EXTI_LineCmd; /*!< Specifies the new state of the selected EXTI lines. + This parameter can be set either to ENABLE or DISABLE */ +}EXTI_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup EXTI_Exported_Constants + * @{ + */ + +/** @defgroup EXTI_Lines + * @{ + */ + +#define EXTI_Line0 ((uint32_t)0x00001) /*!< External interrupt line 0 */ +#define EXTI_Line1 ((uint32_t)0x00002) /*!< External interrupt line 1 */ +#define EXTI_Line2 ((uint32_t)0x00004) /*!< External interrupt line 2 */ +#define EXTI_Line3 ((uint32_t)0x00008) /*!< External interrupt line 3 */ +#define EXTI_Line4 ((uint32_t)0x00010) /*!< External interrupt line 4 */ +#define EXTI_Line5 ((uint32_t)0x00020) /*!< External interrupt line 5 */ +#define EXTI_Line6 ((uint32_t)0x00040) /*!< External interrupt line 6 */ +#define EXTI_Line7 ((uint32_t)0x00080) /*!< External interrupt line 7 */ +#define EXTI_Line8 ((uint32_t)0x00100) /*!< External interrupt line 8 */ +#define EXTI_Line9 ((uint32_t)0x00200) /*!< External interrupt line 9 */ +#define EXTI_Line10 ((uint32_t)0x00400) /*!< External interrupt line 10 */ +#define EXTI_Line11 ((uint32_t)0x00800) /*!< External interrupt line 11 */ +#define EXTI_Line12 ((uint32_t)0x01000) /*!< External interrupt line 12 */ +#define EXTI_Line13 ((uint32_t)0x02000) /*!< External interrupt line 13 */ +#define EXTI_Line14 ((uint32_t)0x04000) /*!< External interrupt line 14 */ +#define EXTI_Line15 ((uint32_t)0x08000) /*!< External interrupt line 15 */ +#define EXTI_Line16 ((uint32_t)0x10000) /*!< External interrupt line 16 Connected to the PVD Output */ +#define EXTI_Line17 ((uint32_t)0x20000) /*!< External interrupt line 17 Connected to the RTC Alarm event */ +#define EXTI_Line18 ((uint32_t)0x40000) /*!< External interrupt line 18 Connected to the USB OTG FS Wakeup from suspend event */ +#define EXTI_Line19 ((uint32_t)0x80000) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */ +#define EXTI_Line20 ((uint32_t)0x00100000) /*!< External interrupt line 20 Connected to the USB OTG HS (configured in FS) Wakeup event */ +#define EXTI_Line21 ((uint32_t)0x00200000) /*!< External interrupt line 21 Connected to the RTC Tamper and Time Stamp events */ +#define EXTI_Line22 ((uint32_t)0x00400000) /*!< External interrupt line 22 Connected to the RTC Wakeup event */ + +#define IS_EXTI_LINE(LINE) ((((LINE) & (uint32_t)0xFF800000) == 0x00) && ((LINE) != (uint16_t)0x00)) + +#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \ + ((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \ + ((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \ + ((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \ + ((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \ + ((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \ + ((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \ + ((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \ + ((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \ + ((LINE) == EXTI_Line18) || ((LINE) == EXTI_Line19) || \ + ((LINE) == EXTI_Line20) || ((LINE) == EXTI_Line21) ||\ + ((LINE) == EXTI_Line22)) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the EXTI configuration to the default reset state *****/ +void EXTI_DeInit(void); + +/* Initialization and Configuration functions *********************************/ +void EXTI_Init(const EXTI_InitTypeDef* EXTI_InitStruct); +void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct); +void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line); + +/* Interrupts and flags management functions **********************************/ +FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line); +void EXTI_ClearFlag(uint32_t EXTI_Line); +ITStatus EXTI_GetITStatus(uint32_t EXTI_Line); +void EXTI_ClearITPendingBit(uint32_t EXTI_Line); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_EXTI_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash.h new file mode 100644 index 000000000..458f1d8b8 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash.h @@ -0,0 +1,334 @@ +/** + ****************************************************************************** + * @file stm32f4xx_flash.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the FLASH + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_FLASH_H +#define __STM32F4xx_FLASH_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup FLASH + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** + * @brief FLASH Status + */ +typedef enum +{ + FLASH_BUSY = 1, + FLASH_ERROR_PGS, + FLASH_ERROR_PGP, + FLASH_ERROR_PGA, + FLASH_ERROR_WRP, + FLASH_ERROR_PROGRAM, + FLASH_ERROR_OPERATION, + FLASH_COMPLETE +}FLASH_Status; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup FLASH_Exported_Constants + * @{ + */ + +/** @defgroup Flash_Latency + * @{ + */ +#define FLASH_Latency_0 ((uint8_t)0x0000) /*!< FLASH Zero Latency cycle */ +#define FLASH_Latency_1 ((uint8_t)0x0001) /*!< FLASH One Latency cycle */ +#define FLASH_Latency_2 ((uint8_t)0x0002) /*!< FLASH Two Latency cycles */ +#define FLASH_Latency_3 ((uint8_t)0x0003) /*!< FLASH Three Latency cycles */ +#define FLASH_Latency_4 ((uint8_t)0x0004) /*!< FLASH Four Latency cycles */ +#define FLASH_Latency_5 ((uint8_t)0x0005) /*!< FLASH Five Latency cycles */ +#define FLASH_Latency_6 ((uint8_t)0x0006) /*!< FLASH Six Latency cycles */ +#define FLASH_Latency_7 ((uint8_t)0x0007) /*!< FLASH Seven Latency cycles */ + +#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \ + ((LATENCY) == FLASH_Latency_1) || \ + ((LATENCY) == FLASH_Latency_2) || \ + ((LATENCY) == FLASH_Latency_3) || \ + ((LATENCY) == FLASH_Latency_4) || \ + ((LATENCY) == FLASH_Latency_5) || \ + ((LATENCY) == FLASH_Latency_6) || \ + ((LATENCY) == FLASH_Latency_7)) +/** + * @} + */ + +/** @defgroup FLASH_Voltage_Range + * @{ + */ +#define VoltageRange_1 ((uint8_t)0x00) /*!< Device operating range: 1.8V to 2.1V */ +#define VoltageRange_2 ((uint8_t)0x01) /*!= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) ||\ + (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) < 0x1FFF7A0F))) +/** + * @} + */ + +/** @defgroup Option_Bytes_Write_Protection + * @{ + */ +#define OB_WRP_Sector_0 ((uint32_t)0x00000001) /*!< Write protection of Sector0 */ +#define OB_WRP_Sector_1 ((uint32_t)0x00000002) /*!< Write protection of Sector1 */ +#define OB_WRP_Sector_2 ((uint32_t)0x00000004) /*!< Write protection of Sector2 */ +#define OB_WRP_Sector_3 ((uint32_t)0x00000008) /*!< Write protection of Sector3 */ +#define OB_WRP_Sector_4 ((uint32_t)0x00000010) /*!< Write protection of Sector4 */ +#define OB_WRP_Sector_5 ((uint32_t)0x00000020) /*!< Write protection of Sector5 */ +#define OB_WRP_Sector_6 ((uint32_t)0x00000040) /*!< Write protection of Sector6 */ +#define OB_WRP_Sector_7 ((uint32_t)0x00000080) /*!< Write protection of Sector7 */ +#define OB_WRP_Sector_8 ((uint32_t)0x00000100) /*!< Write protection of Sector8 */ +#define OB_WRP_Sector_9 ((uint32_t)0x00000200) /*!< Write protection of Sector9 */ +#define OB_WRP_Sector_10 ((uint32_t)0x00000400) /*!< Write protection of Sector10 */ +#define OB_WRP_Sector_11 ((uint32_t)0x00000800) /*!< Write protection of Sector11 */ +#define OB_WRP_Sector_All ((uint32_t)0x00000FFF) /*!< Write protection of all Sectors */ + +#define IS_OB_WRP(SECTOR)((((SECTOR) & (uint32_t)0xFFFFF000) == 0x00000000) && ((SECTOR) != 0x00000000)) +/** + * @} + */ + +/** @defgroup FLASH_Option_Bytes_Read_Protection + * @{ + */ +#define OB_RDP_Level_0 ((uint8_t)0xAA) +#define OB_RDP_Level_1 ((uint8_t)0x55) +/*#define OB_RDP_Level_2 ((uint8_t)0xCC)*/ /*!< Warning: When enabling read protection level 2 + it's no more possible to go back to level 1 or 0 */ +#define IS_OB_RDP(LEVEL) (((LEVEL) == OB_RDP_Level_0)||\ + ((LEVEL) == OB_RDP_Level_1))/*||\ + ((LEVEL) == OB_RDP_Level_2))*/ +/** + * @} + */ + +/** @defgroup FLASH_Option_Bytes_IWatchdog + * @{ + */ +#define OB_IWDG_SW ((uint8_t)0x20) /*!< Software IWDG selected */ +#define OB_IWDG_HW ((uint8_t)0x00) /*!< Hardware IWDG selected */ +#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW)) +/** + * @} + */ + +/** @defgroup FLASH_Option_Bytes_nRST_STOP + * @{ + */ +#define OB_STOP_NoRST ((uint8_t)0x40) /*!< No reset generated when entering in STOP */ +#define OB_STOP_RST ((uint8_t)0x00) /*!< Reset generated when entering in STOP */ +#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST)) +/** + * @} + */ + + +/** @defgroup FLASH_Option_Bytes_nRST_STDBY + * @{ + */ +#define OB_STDBY_NoRST ((uint8_t)0x80) /*!< No reset generated when entering in STANDBY */ +#define OB_STDBY_RST ((uint8_t)0x00) /*!< Reset generated when entering in STANDBY */ +#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST)) +/** + * @} + */ + +/** @defgroup FLASH_BOR_Reset_Level + * @{ + */ +#define OB_BOR_LEVEL3 ((uint8_t)0x00) /*!< Supply voltage ranges from 2.70 to 3.60 V */ +#define OB_BOR_LEVEL2 ((uint8_t)0x04) /*!< Supply voltage ranges from 2.40 to 2.70 V */ +#define OB_BOR_LEVEL1 ((uint8_t)0x08) /*!< Supply voltage ranges from 2.10 to 2.40 V */ +#define OB_BOR_OFF ((uint8_t)0x0C) /*!< Supply voltage ranges from 1.62 to 2.10 V */ +#define IS_OB_BOR(LEVEL) (((LEVEL) == OB_BOR_LEVEL1) || ((LEVEL) == OB_BOR_LEVEL2) ||\ + ((LEVEL) == OB_BOR_LEVEL3) || ((LEVEL) == OB_BOR_OFF)) +/** + * @} + */ + +/** @defgroup FLASH_Interrupts + * @{ + */ +#define FLASH_IT_EOP ((uint32_t)0x01000000) /*!< End of FLASH Operation Interrupt source */ +#define FLASH_IT_ERR ((uint32_t)0x02000000) /*!< Error Interrupt source */ +#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFCFFFFFF) == 0x00000000) && ((IT) != 0x00000000)) +/** + * @} + */ + +/** @defgroup FLASH_Flags + * @{ + */ +#define FLASH_FLAG_EOP ((uint32_t)0x00000001) /*!< FLASH End of Operation flag */ +#define FLASH_FLAG_OPERR ((uint32_t)0x00000002) /*!< FLASH operation Error flag */ +#define FLASH_FLAG_WRPERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */ +#define FLASH_FLAG_PGAERR ((uint32_t)0x00000020) /*!< FLASH Programming Alignment error flag */ +#define FLASH_FLAG_PGPERR ((uint32_t)0x00000040) /*!< FLASH Programming Parallelism error flag */ +#define FLASH_FLAG_PGSERR ((uint32_t)0x00000080) /*!< FLASH Programming Sequence error flag */ +#define FLASH_FLAG_BSY ((uint32_t)0x00010000) /*!< FLASH Busy flag */ +#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFF0C) == 0x00000000) && ((FLAG) != 0x00000000)) +#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_EOP) || ((FLAG) == FLASH_FLAG_OPERR) || \ + ((FLAG) == FLASH_FLAG_WRPERR) || ((FLAG) == FLASH_FLAG_PGAERR) || \ + ((FLAG) == FLASH_FLAG_PGPERR) || ((FLAG) == FLASH_FLAG_PGSERR) || \ + ((FLAG) == FLASH_FLAG_BSY)) +/** + * @} + */ + +/** @defgroup FLASH_Program_Parallelism + * @{ + */ +#define FLASH_PSIZE_BYTE ((uint32_t)0x00000000) +#define FLASH_PSIZE_HALF_WORD ((uint32_t)0x00000100) +#define FLASH_PSIZE_WORD ((uint32_t)0x00000200) +#define FLASH_PSIZE_DOUBLE_WORD ((uint32_t)0x00000300) +#define CR_PSIZE_MASK ((uint32_t)0xFFFFFCFF) +/** + * @} + */ + +/** @defgroup FLASH_Keys + * @{ + */ +#define RDP_KEY ((uint16_t)0x00A5) +#define FLASH_KEY1 ((uint32_t)0x45670123) +#define FLASH_KEY2 ((uint32_t)0xCDEF89AB) +#define FLASH_OPT_KEY1 ((uint32_t)0x08192A3B) +#define FLASH_OPT_KEY2 ((uint32_t)0x4C5D6E7F) +/** + * @} + */ + +/** + * @brief ACR register byte 0 (Bits[8:0]) base address + */ +#define ACR_BYTE0_ADDRESS ((uint32_t)0x40023C00) +/** + * @brief OPTCR register byte 3 (Bits[24:16]) base address + */ +#define OPTCR_BYTE0_ADDRESS ((uint32_t)0x40023C14) +#define OPTCR_BYTE1_ADDRESS ((uint32_t)0x40023C15) +#define OPTCR_BYTE2_ADDRESS ((uint32_t)0x40023C16) + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* FLASH Interface configuration functions ************************************/ +void FLASH_SetLatency(uint32_t FLASH_Latency); +void FLASH_PrefetchBufferCmd(FunctionalState NewState); +void FLASH_InstructionCacheCmd(FunctionalState NewState); +void FLASH_DataCacheCmd(FunctionalState NewState); +void FLASH_InstructionCacheReset(void); +void FLASH_DataCacheReset(void); + +/* FLASH Memory Programming functions *****************************************/ +void FLASH_Unlock(void); +void FLASH_Lock(void); +FLASH_Status FLASH_EraseSector(uint32_t FLASH_Sector, uint8_t VoltageRange); +FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange); +FLASH_Status FLASH_ProgramDoubleWord(uint32_t Address, uint64_t Data); +FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data); +FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data); +FLASH_Status FLASH_ProgramByte(uint32_t Address, uint8_t Data); + +/* Option Bytes Programming functions *****************************************/ +void FLASH_OB_Unlock(void); +void FLASH_OB_Lock(void); +void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState); +void FLASH_OB_RDPConfig(uint8_t OB_RDP); +void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY); +void FLASH_OB_BORConfig(uint8_t OB_BOR); +FLASH_Status FLASH_OB_Launch(void); +uint8_t FLASH_OB_GetUser(void); +uint16_t FLASH_OB_GetWRP(void); +FlagStatus FLASH_OB_GetRDP(void); +uint8_t FLASH_OB_GetBOR(void); + +/* Interrupts and flags management functions **********************************/ +void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState); +FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG); +void FLASH_ClearFlag(uint32_t FLASH_FLAG); +FLASH_Status FLASH_GetStatus(void); +FLASH_Status FLASH_WaitForLastOperation(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_FLASH_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fsmc.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fsmc.h new file mode 100644 index 000000000..29baf50bf --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fsmc.h @@ -0,0 +1,669 @@ +/** + ****************************************************************************** + * @file stm32f4xx_fsmc.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the FSMC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_FSMC_H +#define __STM32F4xx_FSMC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup FSMC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief Timing parameters For NOR/SRAM Banks + */ +typedef struct +{ + uint32_t FSMC_AddressSetupTime; /*!< Defines the number of HCLK cycles to configure + the duration of the address setup time. + This parameter can be a value between 0 and 0xF. + @note This parameter is not used with synchronous NOR Flash memories. */ + + uint32_t FSMC_AddressHoldTime; /*!< Defines the number of HCLK cycles to configure + the duration of the address hold time. + This parameter can be a value between 0 and 0xF. + @note This parameter is not used with synchronous NOR Flash memories.*/ + + uint32_t FSMC_DataSetupTime; /*!< Defines the number of HCLK cycles to configure + the duration of the data setup time. + This parameter can be a value between 0 and 0xFF. + @note This parameter is used for SRAMs, ROMs and asynchronous multiplexed NOR Flash memories. */ + + uint32_t FSMC_BusTurnAroundDuration; /*!< Defines the number of HCLK cycles to configure + the duration of the bus turnaround. + This parameter can be a value between 0 and 0xF. + @note This parameter is only used for multiplexed NOR Flash memories. */ + + uint32_t FSMC_CLKDivision; /*!< Defines the period of CLK clock output signal, expressed in number of HCLK cycles. + This parameter can be a value between 1 and 0xF. + @note This parameter is not used for asynchronous NOR Flash, SRAM or ROM accesses. */ + + uint32_t FSMC_DataLatency; /*!< Defines the number of memory clock cycles to issue + to the memory before getting the first data. + The parameter value depends on the memory type as shown below: + - It must be set to 0 in case of a CRAM + - It is don't care in asynchronous NOR, SRAM or ROM accesses + - It may assume a value between 0 and 0xF in NOR Flash memories + with synchronous burst mode enable */ + + uint32_t FSMC_AccessMode; /*!< Specifies the asynchronous access mode. + This parameter can be a value of @ref FSMC_Access_Mode */ +}FSMC_NORSRAMTimingInitTypeDef; + +/** + * @brief FSMC NOR/SRAM Init structure definition + */ +typedef struct +{ + uint32_t FSMC_Bank; /*!< Specifies the NOR/SRAM memory bank that will be used. + This parameter can be a value of @ref FSMC_NORSRAM_Bank */ + + uint32_t FSMC_DataAddressMux; /*!< Specifies whether the address and data values are + multiplexed on the databus or not. + This parameter can be a value of @ref FSMC_Data_Address_Bus_Multiplexing */ + + uint32_t FSMC_MemoryType; /*!< Specifies the type of external memory attached to + the corresponding memory bank. + This parameter can be a value of @ref FSMC_Memory_Type */ + + uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width. + This parameter can be a value of @ref FSMC_Data_Width */ + + uint32_t FSMC_BurstAccessMode; /*!< Enables or disables the burst access mode for Flash memory, + valid only with synchronous burst Flash memories. + This parameter can be a value of @ref FSMC_Burst_Access_Mode */ + + uint32_t FSMC_AsynchronousWait; /*!< Enables or disables wait signal during asynchronous transfers, + valid only with asynchronous Flash memories. + This parameter can be a value of @ref FSMC_AsynchronousWait */ + + uint32_t FSMC_WaitSignalPolarity; /*!< Specifies the wait signal polarity, valid only when accessing + the Flash memory in burst mode. + This parameter can be a value of @ref FSMC_Wait_Signal_Polarity */ + + uint32_t FSMC_WrapMode; /*!< Enables or disables the Wrapped burst access mode for Flash + memory, valid only when accessing Flash memories in burst mode. + This parameter can be a value of @ref FSMC_Wrap_Mode */ + + uint32_t FSMC_WaitSignalActive; /*!< Specifies if the wait signal is asserted by the memory one + clock cycle before the wait state or during the wait state, + valid only when accessing memories in burst mode. + This parameter can be a value of @ref FSMC_Wait_Timing */ + + uint32_t FSMC_WriteOperation; /*!< Enables or disables the write operation in the selected bank by the FSMC. + This parameter can be a value of @ref FSMC_Write_Operation */ + + uint32_t FSMC_WaitSignal; /*!< Enables or disables the wait-state insertion via wait + signal, valid for Flash memory access in burst mode. + This parameter can be a value of @ref FSMC_Wait_Signal */ + + uint32_t FSMC_ExtendedMode; /*!< Enables or disables the extended mode. + This parameter can be a value of @ref FSMC_Extended_Mode */ + + uint32_t FSMC_WriteBurst; /*!< Enables or disables the write burst operation. + This parameter can be a value of @ref FSMC_Write_Burst */ + + FSMC_NORSRAMTimingInitTypeDef* FSMC_ReadWriteTimingStruct; /*!< Timing Parameters for write and read access if the ExtendedMode is not used*/ + + FSMC_NORSRAMTimingInitTypeDef* FSMC_WriteTimingStruct; /*!< Timing Parameters for write access if the ExtendedMode is used*/ +}FSMC_NORSRAMInitTypeDef; + +/** + * @brief Timing parameters For FSMC NAND and PCCARD Banks + */ +typedef struct +{ + uint32_t FSMC_SetupTime; /*!< Defines the number of HCLK cycles to setup address before + the command assertion for NAND-Flash read or write access + to common/Attribute or I/O memory space (depending on + the memory space timing to be configured). + This parameter can be a value between 0 and 0xFF.*/ + + uint32_t FSMC_WaitSetupTime; /*!< Defines the minimum number of HCLK cycles to assert the + command for NAND-Flash read or write access to + common/Attribute or I/O memory space (depending on the + memory space timing to be configured). + This parameter can be a number between 0x00 and 0xFF */ + + uint32_t FSMC_HoldSetupTime; /*!< Defines the number of HCLK clock cycles to hold address + (and data for write access) after the command deassertion + for NAND-Flash read or write access to common/Attribute + or I/O memory space (depending on the memory space timing + to be configured). + This parameter can be a number between 0x00 and 0xFF */ + + uint32_t FSMC_HiZSetupTime; /*!< Defines the number of HCLK clock cycles during which the + databus is kept in HiZ after the start of a NAND-Flash + write access to common/Attribute or I/O memory space (depending + on the memory space timing to be configured). + This parameter can be a number between 0x00 and 0xFF */ +}FSMC_NAND_PCCARDTimingInitTypeDef; + +/** + * @brief FSMC NAND Init structure definition + */ +typedef struct +{ + uint32_t FSMC_Bank; /*!< Specifies the NAND memory bank that will be used. + This parameter can be a value of @ref FSMC_NAND_Bank */ + + uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the NAND Memory Bank. + This parameter can be any value of @ref FSMC_Wait_feature */ + + uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width. + This parameter can be any value of @ref FSMC_Data_Width */ + + uint32_t FSMC_ECC; /*!< Enables or disables the ECC computation. + This parameter can be any value of @ref FSMC_ECC */ + + uint32_t FSMC_ECCPageSize; /*!< Defines the page size for the extended ECC. + This parameter can be any value of @ref FSMC_ECC_Page_Size */ + + uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between CLE low and RE low. + This parameter can be a value between 0 and 0xFF. */ + + uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between ALE low and RE low. + This parameter can be a number between 0x0 and 0xFF */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */ +}FSMC_NANDInitTypeDef; + +/** + * @brief FSMC PCCARD Init structure definition + */ + +typedef struct +{ + uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the Memory Bank. + This parameter can be any value of @ref FSMC_Wait_feature */ + + uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between CLE low and RE low. + This parameter can be a value between 0 and 0xFF. */ + + uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between ALE low and RE low. + This parameter can be a number between 0x0 and 0xFF */ + + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_IOSpaceTimingStruct; /*!< FSMC IO Space Timing */ +}FSMC_PCCARDInitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup FSMC_Exported_Constants + * @{ + */ + +/** @defgroup FSMC_NORSRAM_Bank + * @{ + */ +#define FSMC_Bank1_NORSRAM1 ((uint32_t)0x00000000) +#define FSMC_Bank1_NORSRAM2 ((uint32_t)0x00000002) +#define FSMC_Bank1_NORSRAM3 ((uint32_t)0x00000004) +#define FSMC_Bank1_NORSRAM4 ((uint32_t)0x00000006) +/** + * @} + */ + +/** @defgroup FSMC_NAND_Bank + * @{ + */ +#define FSMC_Bank2_NAND ((uint32_t)0x00000010) +#define FSMC_Bank3_NAND ((uint32_t)0x00000100) +/** + * @} + */ + +/** @defgroup FSMC_PCCARD_Bank + * @{ + */ +#define FSMC_Bank4_PCCARD ((uint32_t)0x00001000) +/** + * @} + */ + +#define IS_FSMC_NORSRAM_BANK(BANK) (((BANK) == FSMC_Bank1_NORSRAM1) || \ + ((BANK) == FSMC_Bank1_NORSRAM2) || \ + ((BANK) == FSMC_Bank1_NORSRAM3) || \ + ((BANK) == FSMC_Bank1_NORSRAM4)) + +#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND)) + +#define IS_FSMC_GETFLAG_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND) || \ + ((BANK) == FSMC_Bank4_PCCARD)) + +#define IS_FSMC_IT_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND) || \ + ((BANK) == FSMC_Bank4_PCCARD)) + +/** @defgroup FSMC_NOR_SRAM_Controller + * @{ + */ + +/** @defgroup FSMC_Data_Address_Bus_Multiplexing + * @{ + */ + +#define FSMC_DataAddressMux_Disable ((uint32_t)0x00000000) +#define FSMC_DataAddressMux_Enable ((uint32_t)0x00000002) +#define IS_FSMC_MUX(MUX) (((MUX) == FSMC_DataAddressMux_Disable) || \ + ((MUX) == FSMC_DataAddressMux_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Memory_Type + * @{ + */ + +#define FSMC_MemoryType_SRAM ((uint32_t)0x00000000) +#define FSMC_MemoryType_PSRAM ((uint32_t)0x00000004) +#define FSMC_MemoryType_NOR ((uint32_t)0x00000008) +#define IS_FSMC_MEMORY(MEMORY) (((MEMORY) == FSMC_MemoryType_SRAM) || \ + ((MEMORY) == FSMC_MemoryType_PSRAM)|| \ + ((MEMORY) == FSMC_MemoryType_NOR)) +/** + * @} + */ + +/** @defgroup FSMC_Data_Width + * @{ + */ + +#define FSMC_MemoryDataWidth_8b ((uint32_t)0x00000000) +#define FSMC_MemoryDataWidth_16b ((uint32_t)0x00000010) +#define IS_FSMC_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \ + ((WIDTH) == FSMC_MemoryDataWidth_16b)) +/** + * @} + */ + +/** @defgroup FSMC_Burst_Access_Mode + * @{ + */ + +#define FSMC_BurstAccessMode_Disable ((uint32_t)0x00000000) +#define FSMC_BurstAccessMode_Enable ((uint32_t)0x00000100) +#define IS_FSMC_BURSTMODE(STATE) (((STATE) == FSMC_BurstAccessMode_Disable) || \ + ((STATE) == FSMC_BurstAccessMode_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_AsynchronousWait + * @{ + */ +#define FSMC_AsynchronousWait_Disable ((uint32_t)0x00000000) +#define FSMC_AsynchronousWait_Enable ((uint32_t)0x00008000) +#define IS_FSMC_ASYNWAIT(STATE) (((STATE) == FSMC_AsynchronousWait_Disable) || \ + ((STATE) == FSMC_AsynchronousWait_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Wait_Signal_Polarity + * @{ + */ +#define FSMC_WaitSignalPolarity_Low ((uint32_t)0x00000000) +#define FSMC_WaitSignalPolarity_High ((uint32_t)0x00000200) +#define IS_FSMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FSMC_WaitSignalPolarity_Low) || \ + ((POLARITY) == FSMC_WaitSignalPolarity_High)) +/** + * @} + */ + +/** @defgroup FSMC_Wrap_Mode + * @{ + */ +#define FSMC_WrapMode_Disable ((uint32_t)0x00000000) +#define FSMC_WrapMode_Enable ((uint32_t)0x00000400) +#define IS_FSMC_WRAP_MODE(MODE) (((MODE) == FSMC_WrapMode_Disable) || \ + ((MODE) == FSMC_WrapMode_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Wait_Timing + * @{ + */ +#define FSMC_WaitSignalActive_BeforeWaitState ((uint32_t)0x00000000) +#define FSMC_WaitSignalActive_DuringWaitState ((uint32_t)0x00000800) +#define IS_FSMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FSMC_WaitSignalActive_BeforeWaitState) || \ + ((ACTIVE) == FSMC_WaitSignalActive_DuringWaitState)) +/** + * @} + */ + +/** @defgroup FSMC_Write_Operation + * @{ + */ +#define FSMC_WriteOperation_Disable ((uint32_t)0x00000000) +#define FSMC_WriteOperation_Enable ((uint32_t)0x00001000) +#define IS_FSMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FSMC_WriteOperation_Disable) || \ + ((OPERATION) == FSMC_WriteOperation_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Wait_Signal + * @{ + */ +#define FSMC_WaitSignal_Disable ((uint32_t)0x00000000) +#define FSMC_WaitSignal_Enable ((uint32_t)0x00002000) +#define IS_FSMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FSMC_WaitSignal_Disable) || \ + ((SIGNAL) == FSMC_WaitSignal_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Extended_Mode + * @{ + */ +#define FSMC_ExtendedMode_Disable ((uint32_t)0x00000000) +#define FSMC_ExtendedMode_Enable ((uint32_t)0x00004000) + +#define IS_FSMC_EXTENDED_MODE(MODE) (((MODE) == FSMC_ExtendedMode_Disable) || \ + ((MODE) == FSMC_ExtendedMode_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Write_Burst + * @{ + */ + +#define FSMC_WriteBurst_Disable ((uint32_t)0x00000000) +#define FSMC_WriteBurst_Enable ((uint32_t)0x00080000) +#define IS_FSMC_WRITE_BURST(BURST) (((BURST) == FSMC_WriteBurst_Disable) || \ + ((BURST) == FSMC_WriteBurst_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Address_Setup_Time + * @{ + */ +#define IS_FSMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 0xF) +/** + * @} + */ + +/** @defgroup FSMC_Address_Hold_Time + * @{ + */ +#define IS_FSMC_ADDRESS_HOLD_TIME(TIME) ((TIME) <= 0xF) +/** + * @} + */ + +/** @defgroup FSMC_Data_Setup_Time + * @{ + */ +#define IS_FSMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 0xFF)) +/** + * @} + */ + +/** @defgroup FSMC_Bus_Turn_around_Duration + * @{ + */ +#define IS_FSMC_TURNAROUND_TIME(TIME) ((TIME) <= 0xF) +/** + * @} + */ + +/** @defgroup FSMC_CLK_Division + * @{ + */ +#define IS_FSMC_CLK_DIV(DIV) ((DIV) <= 0xF) +/** + * @} + */ + +/** @defgroup FSMC_Data_Latency + * @{ + */ +#define IS_FSMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 0xF) +/** + * @} + */ + +/** @defgroup FSMC_Access_Mode + * @{ + */ +#define FSMC_AccessMode_A ((uint32_t)0x00000000) +#define FSMC_AccessMode_B ((uint32_t)0x10000000) +#define FSMC_AccessMode_C ((uint32_t)0x20000000) +#define FSMC_AccessMode_D ((uint32_t)0x30000000) +#define IS_FSMC_ACCESS_MODE(MODE) (((MODE) == FSMC_AccessMode_A) || \ + ((MODE) == FSMC_AccessMode_B) || \ + ((MODE) == FSMC_AccessMode_C) || \ + ((MODE) == FSMC_AccessMode_D)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup FSMC_NAND_PCCARD_Controller + * @{ + */ + +/** @defgroup FSMC_Wait_feature + * @{ + */ +#define FSMC_Waitfeature_Disable ((uint32_t)0x00000000) +#define FSMC_Waitfeature_Enable ((uint32_t)0x00000002) +#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_Waitfeature_Disable) || \ + ((FEATURE) == FSMC_Waitfeature_Enable)) +/** + * @} + */ + + +/** @defgroup FSMC_ECC + * @{ + */ +#define FSMC_ECC_Disable ((uint32_t)0x00000000) +#define FSMC_ECC_Enable ((uint32_t)0x00000040) +#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_ECC_Disable) || \ + ((STATE) == FSMC_ECC_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_ECC_Page_Size + * @{ + */ +#define FSMC_ECCPageSize_256Bytes ((uint32_t)0x00000000) +#define FSMC_ECCPageSize_512Bytes ((uint32_t)0x00020000) +#define FSMC_ECCPageSize_1024Bytes ((uint32_t)0x00040000) +#define FSMC_ECCPageSize_2048Bytes ((uint32_t)0x00060000) +#define FSMC_ECCPageSize_4096Bytes ((uint32_t)0x00080000) +#define FSMC_ECCPageSize_8192Bytes ((uint32_t)0x000A0000) +#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_ECCPageSize_256Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_512Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_1024Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_2048Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_4096Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_8192Bytes)) +/** + * @} + */ + +/** @defgroup FSMC_TCLR_Setup_Time + * @{ + */ +#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 0xFF) +/** + * @} + */ + +/** @defgroup FSMC_TAR_Setup_Time + * @{ + */ +#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 0xFF) +/** + * @} + */ + +/** @defgroup FSMC_Setup_Time + * @{ + */ +#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 0xFF) +/** + * @} + */ + +/** @defgroup FSMC_Wait_Setup_Time + * @{ + */ +#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 0xFF) +/** + * @} + */ + +/** @defgroup FSMC_Hold_Setup_Time + * @{ + */ +#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 0xFF) +/** + * @} + */ + +/** @defgroup FSMC_HiZ_Setup_Time + * @{ + */ +#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 0xFF) +/** + * @} + */ + +/** @defgroup FSMC_Interrupt_sources + * @{ + */ +#define FSMC_IT_RisingEdge ((uint32_t)0x00000008) +#define FSMC_IT_Level ((uint32_t)0x00000010) +#define FSMC_IT_FallingEdge ((uint32_t)0x00000020) +#define IS_FSMC_IT(IT) ((((IT) & (uint32_t)0xFFFFFFC7) == 0x00000000) && ((IT) != 0x00000000)) +#define IS_FSMC_GET_IT(IT) (((IT) == FSMC_IT_RisingEdge) || \ + ((IT) == FSMC_IT_Level) || \ + ((IT) == FSMC_IT_FallingEdge)) +/** + * @} + */ + +/** @defgroup FSMC_Flags + * @{ + */ +#define FSMC_FLAG_RisingEdge ((uint32_t)0x00000001) +#define FSMC_FLAG_Level ((uint32_t)0x00000002) +#define FSMC_FLAG_FallingEdge ((uint32_t)0x00000004) +#define FSMC_FLAG_FEMPT ((uint32_t)0x00000040) +#define IS_FSMC_GET_FLAG(FLAG) (((FLAG) == FSMC_FLAG_RisingEdge) || \ + ((FLAG) == FSMC_FLAG_Level) || \ + ((FLAG) == FSMC_FLAG_FallingEdge) || \ + ((FLAG) == FSMC_FLAG_FEMPT)) + +#define IS_FSMC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000)) +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* NOR/SRAM Controller functions **********************************************/ +void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank); +void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct); +void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct); +void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState); + +/* NAND Controller functions **************************************************/ +void FSMC_NANDDeInit(uint32_t FSMC_Bank); +void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct); +void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct); +void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState); +void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState); +uint32_t FSMC_GetECC(uint32_t FSMC_Bank); + +/* PCCARD Controller functions ************************************************/ +void FSMC_PCCARDDeInit(void); +void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct); +void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct); +void FSMC_PCCARDCmd(FunctionalState NewState); + +/* Interrupts and flags management functions **********************************/ +void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState); +FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG); +void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG); +ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT); +void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_FSMC_H */ +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_gpio.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_gpio.h new file mode 100644 index 000000000..52d71e5c2 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_gpio.h @@ -0,0 +1,406 @@ +/** + ****************************************************************************** + * @file stm32f4xx_gpio.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the GPIO firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_GPIO_H +#define __STM32F4xx_GPIO_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup GPIO + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \ + ((PERIPH) == GPIOB) || \ + ((PERIPH) == GPIOC) || \ + ((PERIPH) == GPIOD) || \ + ((PERIPH) == GPIOE) || \ + ((PERIPH) == GPIOF) || \ + ((PERIPH) == GPIOG) || \ + ((PERIPH) == GPIOH) || \ + ((PERIPH) == GPIOI)) + +/** + * @brief GPIO Configuration Mode enumeration + */ +typedef enum +{ + GPIO_Mode_IN = 0x00, /*!< GPIO Input Mode */ + GPIO_Mode_OUT = 0x01, /*!< GPIO Output Mode */ + GPIO_Mode_AF = 0x02, /*!< GPIO Alternate function Mode */ + GPIO_Mode_AN = 0x03 /*!< GPIO Analog Mode */ +}GPIOMode_TypeDef; +#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_IN) || ((MODE) == GPIO_Mode_OUT) || \ + ((MODE) == GPIO_Mode_AF)|| ((MODE) == GPIO_Mode_AN)) + +/** + * @brief GPIO Output type enumeration + */ +typedef enum +{ + GPIO_OType_PP = 0x00, + GPIO_OType_OD = 0x01 +}GPIOOType_TypeDef; +#define IS_GPIO_OTYPE(OTYPE) (((OTYPE) == GPIO_OType_PP) || ((OTYPE) == GPIO_OType_OD)) + + +/** + * @brief GPIO Output Maximum frequency enumeration + */ +typedef enum +{ + GPIO_Speed_2MHz = 0x00, /*!< Low speed */ + GPIO_Speed_25MHz = 0x01, /*!< Medium speed */ + GPIO_Speed_50MHz = 0x02, /*!< Fast speed */ + GPIO_Speed_100MHz = 0x03 /*!< High speed on 30 pF (80 MHz Output max speed on 15 pF) */ +}GPIOSpeed_TypeDef; +#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_2MHz) || ((SPEED) == GPIO_Speed_25MHz) || \ + ((SPEED) == GPIO_Speed_50MHz)|| ((SPEED) == GPIO_Speed_100MHz)) + +/** + * @brief GPIO Configuration PullUp PullDown enumeration + */ +typedef enum +{ + GPIO_PuPd_NOPULL = 0x00, + GPIO_PuPd_UP = 0x01, + GPIO_PuPd_DOWN = 0x02 +}GPIOPuPd_TypeDef; +#define IS_GPIO_PUPD(PUPD) (((PUPD) == GPIO_PuPd_NOPULL) || ((PUPD) == GPIO_PuPd_UP) || \ + ((PUPD) == GPIO_PuPd_DOWN)) + +/** + * @brief GPIO Bit SET and Bit RESET enumeration + */ +typedef enum +{ + Bit_RESET = 0, + Bit_SET +}BitAction; +#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET)) + + +/** + * @brief GPIO Init structure definition + */ +typedef struct +{ + uint32_t GPIO_Pin; /*!< Specifies the GPIO pins to be configured. + This parameter can be any value of @ref GPIO_pins_define */ + + GPIOMode_TypeDef GPIO_Mode; /*!< Specifies the operating mode for the selected pins. + This parameter can be a value of @ref GPIOMode_TypeDef */ + + GPIOSpeed_TypeDef GPIO_Speed; /*!< Specifies the speed for the selected pins. + This parameter can be a value of @ref GPIOSpeed_TypeDef */ + + GPIOOType_TypeDef GPIO_OType; /*!< Specifies the operating output type for the selected pins. + This parameter can be a value of @ref GPIOOType_TypeDef */ + + GPIOPuPd_TypeDef GPIO_PuPd; /*!< Specifies the operating Pull-up/Pull down for the selected pins. + This parameter can be a value of @ref GPIOPuPd_TypeDef */ +}GPIO_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup GPIO_Exported_Constants + * @{ + */ + +/** @defgroup GPIO_pins_define + * @{ + */ +#define GPIO_Pin_0 ((uint16_t)0x0001) /* Pin 0 selected */ +#define GPIO_Pin_1 ((uint16_t)0x0002) /* Pin 1 selected */ +#define GPIO_Pin_2 ((uint16_t)0x0004) /* Pin 2 selected */ +#define GPIO_Pin_3 ((uint16_t)0x0008) /* Pin 3 selected */ +#define GPIO_Pin_4 ((uint16_t)0x0010) /* Pin 4 selected */ +#define GPIO_Pin_5 ((uint16_t)0x0020) /* Pin 5 selected */ +#define GPIO_Pin_6 ((uint16_t)0x0040) /* Pin 6 selected */ +#define GPIO_Pin_7 ((uint16_t)0x0080) /* Pin 7 selected */ +#define GPIO_Pin_8 ((uint16_t)0x0100) /* Pin 8 selected */ +#define GPIO_Pin_9 ((uint16_t)0x0200) /* Pin 9 selected */ +#define GPIO_Pin_10 ((uint16_t)0x0400) /* Pin 10 selected */ +#define GPIO_Pin_11 ((uint16_t)0x0800) /* Pin 11 selected */ +#define GPIO_Pin_12 ((uint16_t)0x1000) /* Pin 12 selected */ +#define GPIO_Pin_13 ((uint16_t)0x2000) /* Pin 13 selected */ +#define GPIO_Pin_14 ((uint16_t)0x4000) /* Pin 14 selected */ +#define GPIO_Pin_15 ((uint16_t)0x8000) /* Pin 15 selected */ +#define GPIO_Pin_All ((uint16_t)0xFFFF) /* All pins selected */ + +#define IS_GPIO_PIN(PIN) ((((PIN) & (uint16_t)0x00) == 0x00) && ((PIN) != (uint16_t)0x00)) +#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \ + ((PIN) == GPIO_Pin_1) || \ + ((PIN) == GPIO_Pin_2) || \ + ((PIN) == GPIO_Pin_3) || \ + ((PIN) == GPIO_Pin_4) || \ + ((PIN) == GPIO_Pin_5) || \ + ((PIN) == GPIO_Pin_6) || \ + ((PIN) == GPIO_Pin_7) || \ + ((PIN) == GPIO_Pin_8) || \ + ((PIN) == GPIO_Pin_9) || \ + ((PIN) == GPIO_Pin_10) || \ + ((PIN) == GPIO_Pin_11) || \ + ((PIN) == GPIO_Pin_12) || \ + ((PIN) == GPIO_Pin_13) || \ + ((PIN) == GPIO_Pin_14) || \ + ((PIN) == GPIO_Pin_15)) +/** + * @} + */ + + +/** @defgroup GPIO_Pin_sources + * @{ + */ +#define GPIO_PinSource0 ((uint8_t)0x00) +#define GPIO_PinSource1 ((uint8_t)0x01) +#define GPIO_PinSource2 ((uint8_t)0x02) +#define GPIO_PinSource3 ((uint8_t)0x03) +#define GPIO_PinSource4 ((uint8_t)0x04) +#define GPIO_PinSource5 ((uint8_t)0x05) +#define GPIO_PinSource6 ((uint8_t)0x06) +#define GPIO_PinSource7 ((uint8_t)0x07) +#define GPIO_PinSource8 ((uint8_t)0x08) +#define GPIO_PinSource9 ((uint8_t)0x09) +#define GPIO_PinSource10 ((uint8_t)0x0A) +#define GPIO_PinSource11 ((uint8_t)0x0B) +#define GPIO_PinSource12 ((uint8_t)0x0C) +#define GPIO_PinSource13 ((uint8_t)0x0D) +#define GPIO_PinSource14 ((uint8_t)0x0E) +#define GPIO_PinSource15 ((uint8_t)0x0F) + +#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \ + ((PINSOURCE) == GPIO_PinSource1) || \ + ((PINSOURCE) == GPIO_PinSource2) || \ + ((PINSOURCE) == GPIO_PinSource3) || \ + ((PINSOURCE) == GPIO_PinSource4) || \ + ((PINSOURCE) == GPIO_PinSource5) || \ + ((PINSOURCE) == GPIO_PinSource6) || \ + ((PINSOURCE) == GPIO_PinSource7) || \ + ((PINSOURCE) == GPIO_PinSource8) || \ + ((PINSOURCE) == GPIO_PinSource9) || \ + ((PINSOURCE) == GPIO_PinSource10) || \ + ((PINSOURCE) == GPIO_PinSource11) || \ + ((PINSOURCE) == GPIO_PinSource12) || \ + ((PINSOURCE) == GPIO_PinSource13) || \ + ((PINSOURCE) == GPIO_PinSource14) || \ + ((PINSOURCE) == GPIO_PinSource15)) +/** + * @} + */ + +/** @defgroup GPIO_Alternat_function_selection_define + * @{ + */ +/** + * @brief AF 0 selection + */ +#define GPIO_AF_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ +#define GPIO_AF_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ +#define GPIO_AF_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ +#define GPIO_AF_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ +#define GPIO_AF_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ +#define GPIO_AF_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ +#define GPIO_AF_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ +#define GPIO_AF_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ +#define GPIO_AF_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ +#define GPIO_AF_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ +#define GPIO_AF_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ +#define GPIO_AF_I2S3ext ((uint8_t)0x07) /* I2S3ext Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ +#define GPIO_AF_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ +#define GPIO_AF_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ +#define GPIO_AF_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ +#define GPIO_AF_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ +#define GPIO_AF_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ +#define GPIO_AF_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF_OTG_FS ((uint8_t)0xA) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF_OTG_HS ((uint8_t)0xA) /* OTG_HS Alternate Function mapping */ + +/** + * @brief AF 11 selection + */ +#define GPIO_AF_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF_FSMC ((uint8_t)0xC) /* FSMC Alternate Function mapping */ +#define GPIO_AF_OTG_HS_FS ((uint8_t)0xC) /* OTG HS configured in FS, Alternate Function mapping */ +#define GPIO_AF_SDIO ((uint8_t)0xC) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 13 selection + */ +#define GPIO_AF_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ + +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF_RTC_50Hz) || ((AF) == GPIO_AF_TIM14) || \ + ((AF) == GPIO_AF_MCO) || ((AF) == GPIO_AF_TAMPER) || \ + ((AF) == GPIO_AF_SWJ) || ((AF) == GPIO_AF_TRACE) || \ + ((AF) == GPIO_AF_TIM1) || ((AF) == GPIO_AF_TIM2) || \ + ((AF) == GPIO_AF_TIM3) || ((AF) == GPIO_AF_TIM4) || \ + ((AF) == GPIO_AF_TIM5) || ((AF) == GPIO_AF_TIM8) || \ + ((AF) == GPIO_AF_I2C1) || ((AF) == GPIO_AF_I2C2) || \ + ((AF) == GPIO_AF_I2C3) || ((AF) == GPIO_AF_SPI1) || \ + ((AF) == GPIO_AF_SPI2) || ((AF) == GPIO_AF_TIM13) || \ + ((AF) == GPIO_AF_SPI3) || ((AF) == GPIO_AF_TIM14) || \ + ((AF) == GPIO_AF_USART1) || ((AF) == GPIO_AF_USART2) || \ + ((AF) == GPIO_AF_USART3) || ((AF) == GPIO_AF_UART4) || \ + ((AF) == GPIO_AF_UART5) || ((AF) == GPIO_AF_USART6) || \ + ((AF) == GPIO_AF_CAN1) || ((AF) == GPIO_AF_CAN2) || \ + ((AF) == GPIO_AF_OTG_FS) || ((AF) == GPIO_AF_OTG_HS) || \ + ((AF) == GPIO_AF_ETH) || ((AF) == GPIO_AF_FSMC) || \ + ((AF) == GPIO_AF_OTG_HS_FS) || ((AF) == GPIO_AF_SDIO) || \ + ((AF) == GPIO_AF_DCMI) || ((AF) == GPIO_AF_EVENTOUT)) +/** + * @} + */ + +/** @defgroup GPIO_Legacy + * @{ + */ + +#define GPIO_Mode_AIN GPIO_Mode_AN + +#define GPIO_AF_OTG1_FS GPIO_AF_OTG_FS +#define GPIO_AF_OTG2_HS GPIO_AF_OTG_HS +#define GPIO_AF_OTG2_FS GPIO_AF_OTG_HS_FS + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the GPIO configuration to the default reset state ****/ +void GPIO_DeInit(GPIO_TypeDef* GPIOx); + +/* Initialization and Configuration functions *********************************/ +void GPIO_Init(GPIO_TypeDef* GPIOx, const GPIO_InitTypeDef* GPIO_InitStruct); +void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct); +void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); + +/* GPIO Read and Write functions **********************************************/ +uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx); +uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx); +void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal); +void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal); +void GPIO_ToggleBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); + +/* GPIO Alternate functions configuration function ****************************/ +void GPIO_PinAFConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_GPIO_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_hash.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_hash.h new file mode 100644 index 000000000..f303c880a --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_hash.h @@ -0,0 +1,244 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hash.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the HASH + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HASH_H +#define __STM32F4xx_HASH_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup HASH + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief HASH Init structure definition + */ +typedef struct +{ + uint32_t HASH_AlgoSelection; /*!< SHA-1 or MD5. This parameter can be a value + of @ref HASH_Algo_Selection */ + uint32_t HASH_AlgoMode; /*!< HASH or HMAC. This parameter can be a value + of @ref HASH_processor_Algorithm_Mode */ + uint32_t HASH_DataType; /*!< 32-bit data, 16-bit data, 8-bit data or + bit-string. This parameter can be a value of + @ref HASH_Data_Type */ + uint32_t HASH_HMACKeyType; /*!< HMAC Short key or HMAC Long Key. This parameter + can be a value of @ref HASH_HMAC_Long_key_only_for_HMAC_mode */ +}HASH_InitTypeDef; + +/** + * @brief HASH message digest result structure definition + */ +typedef struct +{ + uint32_t Data[5]; /*!< Message digest result : 5x 32bit words for SHA1 or + 4x 32bit words for MD5 */ +} HASH_MsgDigest; + +/** + * @brief HASH context swapping structure definition + */ +typedef struct +{ + uint32_t HASH_IMR; + uint32_t HASH_STR; + uint32_t HASH_CR; + uint32_t HASH_CSR[51]; +}HASH_Context; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup HASH_Exported_Constants + * @{ + */ + +/** @defgroup HASH_Algo_Selection + * @{ + */ +#define HASH_AlgoSelection_SHA1 ((uint16_t)0x0000) /*!< HASH function is SHA1 */ +#define HASH_AlgoSelection_MD5 ((uint16_t)0x0080) /*!< HASH function is MD5 */ + +#define IS_HASH_ALGOSELECTION(ALGOSELECTION) (((ALGOSELECTION) == HASH_AlgoSelection_SHA1) || \ + ((ALGOSELECTION) == HASH_AlgoSelection_MD5)) +/** + * @} + */ + +/** @defgroup HASH_processor_Algorithm_Mode + * @{ + */ +#define HASH_AlgoMode_HASH ((uint16_t)0x0000) /*!< Algorithm is HASH */ +#define HASH_AlgoMode_HMAC ((uint16_t)0x0040) /*!< Algorithm is HMAC */ + +#define IS_HASH_ALGOMODE(ALGOMODE) (((ALGOMODE) == HASH_AlgoMode_HASH) || \ + ((ALGOMODE) == HASH_AlgoMode_HMAC)) +/** + * @} + */ + +/** @defgroup HASH_Data_Type + * @{ + */ +#define HASH_DataType_32b ((uint16_t)0x0000) +#define HASH_DataType_16b ((uint16_t)0x0010) +#define HASH_DataType_8b ((uint16_t)0x0020) +#define HASH_DataType_1b ((uint16_t)0x0030) + +#define IS_HASH_DATATYPE(DATATYPE) (((DATATYPE) == HASH_DataType_32b)|| \ + ((DATATYPE) == HASH_DataType_16b)|| \ + ((DATATYPE) == HASH_DataType_8b)|| \ + ((DATATYPE) == HASH_DataType_1b)) +/** + * @} + */ + +/** @defgroup HASH_HMAC_Long_key_only_for_HMAC_mode + * @{ + */ +#define HASH_HMACKeyType_ShortKey ((uint32_t)0x00000000) /*!< HMAC Key is <= 64 bytes */ +#define HASH_HMACKeyType_LongKey ((uint32_t)0x00010000) /*!< HMAC Key is > 64 bytes */ + +#define IS_HASH_HMAC_KEYTYPE(KEYTYPE) (((KEYTYPE) == HASH_HMACKeyType_ShortKey) || \ + ((KEYTYPE) == HASH_HMACKeyType_LongKey)) +/** + * @} + */ + +/** @defgroup Number_of_valid_bits_in_last_word_of_the_message + * @{ + */ +#define IS_HASH_VALIDBITSNUMBER(VALIDBITS) ((VALIDBITS) <= 0x1F) + +/** + * @} + */ + +/** @defgroup HASH_interrupts_definition + * @{ + */ +#define HASH_IT_DINI ((uint8_t)0x01) /*!< A new block can be entered into the input buffer (DIN)*/ +#define HASH_IT_DCI ((uint8_t)0x02) /*!< Digest calculation complete */ + +#define IS_HASH_IT(IT) ((((IT) & (uint8_t)0xFC) == 0x00) && ((IT) != 0x00)) +#define IS_HASH_GET_IT(IT) (((IT) == HASH_IT_DINI) || ((IT) == HASH_IT_DCI)) + +/** + * @} + */ + +/** @defgroup HASH_flags_definition + * @{ + */ +#define HASH_FLAG_DINIS ((uint16_t)0x0001) /*!< 16 locations are free in the DIN : A new block can be entered into the input buffer.*/ +#define HASH_FLAG_DCIS ((uint16_t)0x0002) /*!< Digest calculation complete */ +#define HASH_FLAG_DMAS ((uint16_t)0x0004) /*!< DMA interface is enabled (DMAE=1) or a transfer is ongoing */ +#define HASH_FLAG_BUSY ((uint16_t)0x0008) /*!< The hash core is Busy : processing a block of data */ +#define HASH_FLAG_DINNE ((uint16_t)0x1000) /*!< DIN not empty : The input buffer contains at least one word of data */ + +#define IS_HASH_GET_FLAG(FLAG) (((FLAG) == HASH_FLAG_DINIS) || \ + ((FLAG) == HASH_FLAG_DCIS) || \ + ((FLAG) == HASH_FLAG_DMAS) || \ + ((FLAG) == HASH_FLAG_BUSY) || \ + ((FLAG) == HASH_FLAG_DINNE)) + +#define IS_HASH_CLEAR_FLAG(FLAG)(((FLAG) == HASH_FLAG_DINIS) || \ + ((FLAG) == HASH_FLAG_DCIS)) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the HASH configuration to the default reset state ****/ +void HASH_DeInit(void); + +/* HASH Configuration function ************************************************/ +void HASH_Init(HASH_InitTypeDef* HASH_InitStruct); +void HASH_StructInit(HASH_InitTypeDef* HASH_InitStruct); +void HASH_Reset(void); + +/* HASH Message Digest generation functions ***********************************/ +void HASH_DataIn(uint32_t Data); +uint8_t HASH_GetInFIFOWordsNbr(void); +void HASH_SetLastWordValidBitsNbr(uint16_t ValidNumber); +void HASH_StartDigest(void); +void HASH_GetDigest(HASH_MsgDigest* HASH_MessageDigest); + +/* HASH Context swapping functions ********************************************/ +void HASH_SaveContext(HASH_Context* HASH_ContextSave); +void HASH_RestoreContext(HASH_Context* HASH_ContextRestore); + +/* HASH's DMA interface function **********************************************/ +void HASH_DMACmd(FunctionalState NewState); + +/* HASH Interrupts and flags management functions *****************************/ +void HASH_ITConfig(uint8_t HASH_IT, FunctionalState NewState); +FlagStatus HASH_GetFlagStatus(uint16_t HASH_FLAG); +void HASH_ClearFlag(uint16_t HASH_FLAG); +ITStatus HASH_GetITStatus(uint8_t HASH_IT); +void HASH_ClearITPendingBit(uint8_t HASH_IT); + +/* High Level SHA1 functions **************************************************/ +ErrorStatus HASH_SHA1(uint8_t *Input, uint32_t Ilen, uint8_t Output[20]); +ErrorStatus HMAC_SHA1(uint8_t *Key, uint32_t Keylen, + uint8_t *Input, uint32_t Ilen, + uint8_t Output[20]); + +/* High Level MD5 functions ***************************************************/ +ErrorStatus HASH_MD5(uint8_t *Input, uint32_t Ilen, uint8_t Output[16]); +ErrorStatus HMAC_MD5(uint8_t *Key, uint32_t Keylen, + uint8_t *Input, uint32_t Ilen, + uint8_t Output[16]); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_HASH_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_i2c.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_i2c.h new file mode 100644 index 000000000..ea5e36dbb --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_i2c.h @@ -0,0 +1,692 @@ +/** + ****************************************************************************** + * @file stm32f4xx_i2c.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the I2C firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_I2C_H +#define __STM32F4xx_I2C_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup I2C + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief I2C Init structure definition + */ + +typedef struct +{ + uint32_t I2C_ClockSpeed; /*!< Specifies the clock frequency. + This parameter must be set to a value lower than 400kHz */ + + uint16_t I2C_Mode; /*!< Specifies the I2C mode. + This parameter can be a value of @ref I2C_mode */ + + uint16_t I2C_DutyCycle; /*!< Specifies the I2C fast mode duty cycle. + This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */ + + uint16_t I2C_OwnAddress1; /*!< Specifies the first device own address. + This parameter can be a 7-bit or 10-bit address. */ + + uint16_t I2C_Ack; /*!< Enables or disables the acknowledgement. + This parameter can be a value of @ref I2C_acknowledgement */ + + uint16_t I2C_AcknowledgedAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged. + This parameter can be a value of @ref I2C_acknowledged_address */ +}I2C_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + + +/** @defgroup I2C_Exported_Constants + * @{ + */ + +#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C1) || \ + ((PERIPH) == I2C2) || \ + ((PERIPH) == I2C3)) +/** @defgroup I2C_mode + * @{ + */ + +#define I2C_Mode_I2C ((uint16_t)0x0000) +#define I2C_Mode_SMBusDevice ((uint16_t)0x0002) +#define I2C_Mode_SMBusHost ((uint16_t)0x000A) +#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \ + ((MODE) == I2C_Mode_SMBusDevice) || \ + ((MODE) == I2C_Mode_SMBusHost)) +/** + * @} + */ + +/** @defgroup I2C_duty_cycle_in_fast_mode + * @{ + */ + +#define I2C_DutyCycle_16_9 ((uint16_t)0x4000) /*!< I2C fast mode Tlow/Thigh = 16/9 */ +#define I2C_DutyCycle_2 ((uint16_t)0xBFFF) /*!< I2C fast mode Tlow/Thigh = 2 */ +#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \ + ((CYCLE) == I2C_DutyCycle_2)) +/** + * @} + */ + +/** @defgroup I2C_acknowledgement + * @{ + */ + +#define I2C_Ack_Enable ((uint16_t)0x0400) +#define I2C_Ack_Disable ((uint16_t)0x0000) +#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \ + ((STATE) == I2C_Ack_Disable)) +/** + * @} + */ + +/** @defgroup I2C_transfer_direction + * @{ + */ + +#define I2C_Direction_Transmitter ((uint8_t)0x00) +#define I2C_Direction_Receiver ((uint8_t)0x01) +#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \ + ((DIRECTION) == I2C_Direction_Receiver)) +/** + * @} + */ + +/** @defgroup I2C_acknowledged_address + * @{ + */ + +#define I2C_AcknowledgedAddress_7bit ((uint16_t)0x4000) +#define I2C_AcknowledgedAddress_10bit ((uint16_t)0xC000) +#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \ + ((ADDRESS) == I2C_AcknowledgedAddress_10bit)) +/** + * @} + */ + +/** @defgroup I2C_registers + * @{ + */ + +#define I2C_Register_CR1 ((uint8_t)0x00) +#define I2C_Register_CR2 ((uint8_t)0x04) +#define I2C_Register_OAR1 ((uint8_t)0x08) +#define I2C_Register_OAR2 ((uint8_t)0x0C) +#define I2C_Register_DR ((uint8_t)0x10) +#define I2C_Register_SR1 ((uint8_t)0x14) +#define I2C_Register_SR2 ((uint8_t)0x18) +#define I2C_Register_CCR ((uint8_t)0x1C) +#define I2C_Register_TRISE ((uint8_t)0x20) +#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \ + ((REGISTER) == I2C_Register_CR2) || \ + ((REGISTER) == I2C_Register_OAR1) || \ + ((REGISTER) == I2C_Register_OAR2) || \ + ((REGISTER) == I2C_Register_DR) || \ + ((REGISTER) == I2C_Register_SR1) || \ + ((REGISTER) == I2C_Register_SR2) || \ + ((REGISTER) == I2C_Register_CCR) || \ + ((REGISTER) == I2C_Register_TRISE)) +/** + * @} + */ + +/** @defgroup I2C_NACK_position + * @{ + */ + +#define I2C_NACKPosition_Next ((uint16_t)0x0800) +#define I2C_NACKPosition_Current ((uint16_t)0xF7FF) +#define IS_I2C_NACK_POSITION(POSITION) (((POSITION) == I2C_NACKPosition_Next) || \ + ((POSITION) == I2C_NACKPosition_Current)) +/** + * @} + */ + +/** @defgroup I2C_SMBus_alert_pin_level + * @{ + */ + +#define I2C_SMBusAlert_Low ((uint16_t)0x2000) +#define I2C_SMBusAlert_High ((uint16_t)0xDFFF) +#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \ + ((ALERT) == I2C_SMBusAlert_High)) +/** + * @} + */ + +/** @defgroup I2C_PEC_position + * @{ + */ + +#define I2C_PECPosition_Next ((uint16_t)0x0800) +#define I2C_PECPosition_Current ((uint16_t)0xF7FF) +#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \ + ((POSITION) == I2C_PECPosition_Current)) +/** + * @} + */ + +/** @defgroup I2C_interrupts_definition + * @{ + */ + +#define I2C_IT_BUF ((uint16_t)0x0400) +#define I2C_IT_EVT ((uint16_t)0x0200) +#define I2C_IT_ERR ((uint16_t)0x0100) +#define IS_I2C_CONFIG_IT(IT) ((((IT) & (uint16_t)0xF8FF) == 0x00) && ((IT) != 0x00)) +/** + * @} + */ + +/** @defgroup I2C_interrupts_definition + * @{ + */ + +#define I2C_IT_SMBALERT ((uint32_t)0x01008000) +#define I2C_IT_TIMEOUT ((uint32_t)0x01004000) +#define I2C_IT_PECERR ((uint32_t)0x01001000) +#define I2C_IT_OVR ((uint32_t)0x01000800) +#define I2C_IT_AF ((uint32_t)0x01000400) +#define I2C_IT_ARLO ((uint32_t)0x01000200) +#define I2C_IT_BERR ((uint32_t)0x01000100) +#define I2C_IT_TXE ((uint32_t)0x06000080) +#define I2C_IT_RXNE ((uint32_t)0x06000040) +#define I2C_IT_STOPF ((uint32_t)0x02000010) +#define I2C_IT_ADD10 ((uint32_t)0x02000008) +#define I2C_IT_BTF ((uint32_t)0x02000004) +#define I2C_IT_ADDR ((uint32_t)0x02000002) +#define I2C_IT_SB ((uint32_t)0x02000001) + +#define IS_I2C_CLEAR_IT(IT) ((((IT) & (uint16_t)0x20FF) == 0x00) && ((IT) != (uint16_t)0x00)) + +#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \ + ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \ + ((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \ + ((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \ + ((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \ + ((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \ + ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB)) +/** + * @} + */ + +/** @defgroup I2C_flags_definition + * @{ + */ + +/** + * @brief SR2 register flags + */ + +#define I2C_FLAG_DUALF ((uint32_t)0x00800000) +#define I2C_FLAG_SMBHOST ((uint32_t)0x00400000) +#define I2C_FLAG_SMBDEFAULT ((uint32_t)0x00200000) +#define I2C_FLAG_GENCALL ((uint32_t)0x00100000) +#define I2C_FLAG_TRA ((uint32_t)0x00040000) +#define I2C_FLAG_BUSY ((uint32_t)0x00020000) +#define I2C_FLAG_MSL ((uint32_t)0x00010000) + +/** + * @brief SR1 register flags + */ + +#define I2C_FLAG_SMBALERT ((uint32_t)0x10008000) +#define I2C_FLAG_TIMEOUT ((uint32_t)0x10004000) +#define I2C_FLAG_PECERR ((uint32_t)0x10001000) +#define I2C_FLAG_OVR ((uint32_t)0x10000800) +#define I2C_FLAG_AF ((uint32_t)0x10000400) +#define I2C_FLAG_ARLO ((uint32_t)0x10000200) +#define I2C_FLAG_BERR ((uint32_t)0x10000100) +#define I2C_FLAG_TXE ((uint32_t)0x10000080) +#define I2C_FLAG_RXNE ((uint32_t)0x10000040) +#define I2C_FLAG_STOPF ((uint32_t)0x10000010) +#define I2C_FLAG_ADD10 ((uint32_t)0x10000008) +#define I2C_FLAG_BTF ((uint32_t)0x10000004) +#define I2C_FLAG_ADDR ((uint32_t)0x10000002) +#define I2C_FLAG_SB ((uint32_t)0x10000001) + +#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0x20FF) == 0x00) && ((FLAG) != (uint16_t)0x00)) + +#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \ + ((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \ + ((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \ + ((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \ + ((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \ + ((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \ + ((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \ + ((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \ + ((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \ + ((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \ + ((FLAG) == I2C_FLAG_SB)) +/** + * @} + */ + +/** @defgroup I2C_Events + * @{ + */ + +/** + =============================================================================== + I2C Master Events (Events grouped in order of communication) + =============================================================================== + */ + +/** + * @brief Communication start + * + * After sending the START condition (I2C_GenerateSTART() function) the master + * has to wait for this event. It means that the Start condition has been correctly + * released on the I2C bus (the bus is free, no other devices is communicating). + * + */ +/* --EV5 */ +#define I2C_EVENT_MASTER_MODE_SELECT ((uint32_t)0x00030001) /* BUSY, MSL and SB flag */ + +/** + * @brief Address Acknowledge + * + * After checking on EV5 (start condition correctly released on the bus), the + * master sends the address of the slave(s) with which it will communicate + * (I2C_Send7bitAddress() function, it also determines the direction of the communication: + * Master transmitter or Receiver). Then the master has to wait that a slave acknowledges + * his address. If an acknowledge is sent on the bus, one of the following events will + * be set: + * + * 1) In case of Master Receiver (7-bit addressing): the I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED + * event is set. + * + * 2) In case of Master Transmitter (7-bit addressing): the I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED + * is set + * + * 3) In case of 10-Bit addressing mode, the master (just after generating the START + * and checking on EV5) has to send the header of 10-bit addressing mode (I2C_SendData() + * function). Then master should wait on EV9. It means that the 10-bit addressing + * header has been correctly sent on the bus. Then master should send the second part of + * the 10-bit address (LSB) using the function I2C_Send7bitAddress(). Then master + * should wait for event EV6. + * + */ + +/* --EV6 */ +#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED ((uint32_t)0x00070082) /* BUSY, MSL, ADDR, TXE and TRA flags */ +#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED ((uint32_t)0x00030002) /* BUSY, MSL and ADDR flags */ +/* --EV9 */ +#define I2C_EVENT_MASTER_MODE_ADDRESS10 ((uint32_t)0x00030008) /* BUSY, MSL and ADD10 flags */ + +/** + * @brief Communication events + * + * If a communication is established (START condition generated and slave address + * acknowledged) then the master has to check on one of the following events for + * communication procedures: + * + * 1) Master Receiver mode: The master has to wait on the event EV7 then to read + * the data received from the slave (I2C_ReceiveData() function). + * + * 2) Master Transmitter mode: The master has to send data (I2C_SendData() + * function) then to wait on event EV8 or EV8_2. + * These two events are similar: + * - EV8 means that the data has been written in the data register and is + * being shifted out. + * - EV8_2 means that the data has been physically shifted out and output + * on the bus. + * In most cases, using EV8 is sufficient for the application. + * Using EV8_2 leads to a slower communication but ensure more reliable test. + * EV8_2 is also more suitable than EV8 for testing on the last data transmission + * (before Stop condition generation). + * + * @note In case the user software does not guarantee that this event EV7 is + * managed before the current byte end of transfer, then user may check on EV7 + * and BTF flag at the same time (ie. (I2C_EVENT_MASTER_BYTE_RECEIVED | I2C_FLAG_BTF)). + * In this case the communication may be slower. + * + */ + +/* Master RECEIVER mode -----------------------------*/ +/* --EV7 */ +#define I2C_EVENT_MASTER_BYTE_RECEIVED ((uint32_t)0x00030040) /* BUSY, MSL and RXNE flags */ + +/* Master TRANSMITTER mode --------------------------*/ +/* --EV8 */ +#define I2C_EVENT_MASTER_BYTE_TRANSMITTING ((uint32_t)0x00070080) /* TRA, BUSY, MSL, TXE flags */ +/* --EV8_2 */ +#define I2C_EVENT_MASTER_BYTE_TRANSMITTED ((uint32_t)0x00070084) /* TRA, BUSY, MSL, TXE and BTF flags */ + + +/** + =============================================================================== + I2C Slave Events (Events grouped in order of communication) + =============================================================================== + */ + + +/** + * @brief Communication start events + * + * Wait on one of these events at the start of the communication. It means that + * the I2C peripheral detected a Start condition on the bus (generated by master + * device) followed by the peripheral address. The peripheral generates an ACK + * condition on the bus (if the acknowledge feature is enabled through function + * I2C_AcknowledgeConfig()) and the events listed above are set : + * + * 1) In normal case (only one address managed by the slave), when the address + * sent by the master matches the own address of the peripheral (configured by + * I2C_OwnAddress1 field) the I2C_EVENT_SLAVE_XXX_ADDRESS_MATCHED event is set + * (where XXX could be TRANSMITTER or RECEIVER). + * + * 2) In case the address sent by the master matches the second address of the + * peripheral (configured by the function I2C_OwnAddress2Config() and enabled + * by the function I2C_DualAddressCmd()) the events I2C_EVENT_SLAVE_XXX_SECONDADDRESS_MATCHED + * (where XXX could be TRANSMITTER or RECEIVER) are set. + * + * 3) In case the address sent by the master is General Call (address 0x00) and + * if the General Call is enabled for the peripheral (using function I2C_GeneralCallCmd()) + * the following event is set I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED. + * + */ + +/* --EV1 (all the events below are variants of EV1) */ +/* 1) Case of One Single Address managed by the slave */ +#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((uint32_t)0x00020002) /* BUSY and ADDR flags */ +#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */ + +/* 2) Case of Dual address managed by the slave */ +#define I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED ((uint32_t)0x00820000) /* DUALF and BUSY flags */ +#define I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((uint32_t)0x00860080) /* DUALF, TRA, BUSY and TXE flags */ + +/* 3) Case of General Call enabled for the slave */ +#define I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED ((uint32_t)0x00120000) /* GENCALL and BUSY flags */ + +/** + * @brief Communication events + * + * Wait on one of these events when EV1 has already been checked and: + * + * - Slave RECEIVER mode: + * - EV2: When the application is expecting a data byte to be received. + * - EV4: When the application is expecting the end of the communication: master + * sends a stop condition and data transmission is stopped. + * + * - Slave Transmitter mode: + * - EV3: When a byte has been transmitted by the slave and the application is expecting + * the end of the byte transmission. The two events I2C_EVENT_SLAVE_BYTE_TRANSMITTED and + * I2C_EVENT_SLAVE_BYTE_TRANSMITTING are similar. The second one can optionally be + * used when the user software doesn't guarantee the EV3 is managed before the + * current byte end of transfer. + * - EV3_2: When the master sends a NACK in order to tell slave that data transmission + * shall end (before sending the STOP condition). In this case slave has to stop sending + * data bytes and expect a Stop condition on the bus. + * + * @note In case the user software does not guarantee that the event EV2 is + * managed before the current byte end of transfer, then user may check on EV2 + * and BTF flag at the same time (ie. (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_BTF)). + * In this case the communication may be slower. + * + */ + +/* Slave RECEIVER mode --------------------------*/ +/* --EV2 */ +#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((uint32_t)0x00020040) /* BUSY and RXNE flags */ +/* --EV4 */ +#define I2C_EVENT_SLAVE_STOP_DETECTED ((uint32_t)0x00000010) /* STOPF flag */ + +/* Slave TRANSMITTER mode -----------------------*/ +/* --EV3 */ +#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((uint32_t)0x00060084) /* TRA, BUSY, TXE and BTF flags */ +#define I2C_EVENT_SLAVE_BYTE_TRANSMITTING ((uint32_t)0x00060080) /* TRA, BUSY and TXE flags */ +/* --EV3_2 */ +#define I2C_EVENT_SLAVE_ACK_FAILURE ((uint32_t)0x00000400) /* AF flag */ + +/* + =============================================================================== + End of Events Description + =============================================================================== + */ + +#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \ + ((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \ + ((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \ + ((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTING) || \ + ((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \ + ((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE)) +/** + * @} + */ + +/** @defgroup I2C_own_address1 + * @{ + */ + +#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF) +/** + * @} + */ + +/** @defgroup I2C_clock_speed + * @{ + */ + +#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the I2C configuration to the default reset state *****/ +void I2C_DeInit(I2C_TypeDef* I2Cx); + +/* Initialization and Configuration functions *********************************/ +void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct); +void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct); +void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction); +void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address); +void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle); +void I2C_NACKPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_NACKPosition); +void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert); +void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); + +/* Data transfers functions ***************************************************/ +void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data); +uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx); + +/* PEC management functions ***************************************************/ +void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition); +void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState); +uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx); + +/* DMA transfers management functions *****************************************/ +void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); + +/* Interrupts, events and flags management functions **************************/ +uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register); +void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState); + +/* + =============================================================================== + I2C State Monitoring Functions + =============================================================================== + This I2C driver provides three different ways for I2C state monitoring + depending on the application requirements and constraints: + + + 1. Basic state monitoring (Using I2C_CheckEvent() function) + ----------------------------------------------------------- + It compares the status registers (SR1 and SR2) content to a given event + (can be the combination of one or more flags). + It returns SUCCESS if the current status includes the given flags + and returns ERROR if one or more flags are missing in the current status. + + - When to use + - This function is suitable for most applications as well as for startup + activity since the events are fully described in the product reference + manual (RM0090). + - It is also suitable for users who need to define their own events. + + - Limitations + - If an error occurs (ie. error flags are set besides to the monitored + flags), the I2C_CheckEvent() function may return SUCCESS despite + the communication hold or corrupted real state. + In this case, it is advised to use error interrupts to monitor + the error events and handle them in the interrupt IRQ handler. + + Note + For error management, it is advised to use the following functions: + - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR). + - I2Cx_ER_IRQHandler() which is called when the error interrupt occurs. + Where x is the peripheral instance (I2C1, I2C2 ...) + - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into the + I2Cx_ER_IRQHandler() function in order to determine which error occurred. + - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() + and/or I2C_GenerateStop() in order to clear the error flag and source + and return to correct communication status. + + + 2. Advanced state monitoring (Using the function I2C_GetLastEvent()) + -------------------------------------------------------------------- + Using the function I2C_GetLastEvent() which returns the image of both status + registers in a single word (uint32_t) (Status Register 2 value is shifted left + by 16 bits and concatenated to Status Register 1). + + - When to use + - This function is suitable for the same applications above but it + allows to overcome the mentioned limitation of I2C_GetFlagStatus() + function. + - The returned value could be compared to events already defined in + this file or to custom values defined by user. + This function is suitable when multiple flags are monitored at the + same time. + - At the opposite of I2C_CheckEvent() function, this function allows + user to choose when an event is accepted (when all events flags are + set and no other flags are set or just when the needed flags are set + like I2C_CheckEvent() function. + + - Limitations + - User may need to define his own events. + - Same remark concerning the error management is applicable for this + function if user decides to check only regular communication flags + (and ignores error flags). + + + 3. Flag-based state monitoring (Using the function I2C_GetFlagStatus()) + ----------------------------------------------------------------------- + + Using the function I2C_GetFlagStatus() which simply returns the status of + one single flag (ie. I2C_FLAG_RXNE ...). + + - When to use + - This function could be used for specific applications or in debug + phase. + - It is suitable when only one flag checking is needed (most I2C + events are monitored through multiple flags). + - Limitations: + - When calling this function, the Status register is accessed. + Some flags are cleared when the status register is accessed. + So checking the status of one Flag, may clear other ones. + - Function may need to be called twice or more in order to monitor + one single event. + */ + +/* + =============================================================================== + 1. Basic state monitoring + =============================================================================== + */ +ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT); +/* + =============================================================================== + 2. Advanced state monitoring + =============================================================================== + */ +uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx); +/* + =============================================================================== + 3. Flag-based state monitoring + =============================================================================== + */ +FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); + + +void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); +ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT); +void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_I2C_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_iwdg.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_iwdg.h new file mode 100644 index 000000000..fd5deb5af --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_iwdg.h @@ -0,0 +1,125 @@ +/** + ****************************************************************************** + * @file stm32f4xx_iwdg.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the IWDG + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_IWDG_H +#define __STM32F4xx_IWDG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup IWDG + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup IWDG_Exported_Constants + * @{ + */ + +/** @defgroup IWDG_WriteAccess + * @{ + */ +#define IWDG_WriteAccess_Enable ((uint16_t)0x5555) +#define IWDG_WriteAccess_Disable ((uint16_t)0x0000) +#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \ + ((ACCESS) == IWDG_WriteAccess_Disable)) +/** + * @} + */ + +/** @defgroup IWDG_prescaler + * @{ + */ +#define IWDG_Prescaler_4 ((uint8_t)0x00) +#define IWDG_Prescaler_8 ((uint8_t)0x01) +#define IWDG_Prescaler_16 ((uint8_t)0x02) +#define IWDG_Prescaler_32 ((uint8_t)0x03) +#define IWDG_Prescaler_64 ((uint8_t)0x04) +#define IWDG_Prescaler_128 ((uint8_t)0x05) +#define IWDG_Prescaler_256 ((uint8_t)0x06) +#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \ + ((PRESCALER) == IWDG_Prescaler_8) || \ + ((PRESCALER) == IWDG_Prescaler_16) || \ + ((PRESCALER) == IWDG_Prescaler_32) || \ + ((PRESCALER) == IWDG_Prescaler_64) || \ + ((PRESCALER) == IWDG_Prescaler_128)|| \ + ((PRESCALER) == IWDG_Prescaler_256)) +/** + * @} + */ + +/** @defgroup IWDG_Flag + * @{ + */ +#define IWDG_FLAG_PVU ((uint16_t)0x0001) +#define IWDG_FLAG_RVU ((uint16_t)0x0002) +#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU)) +#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Prescaler and Counter configuration functions ******************************/ +void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess); +void IWDG_SetPrescaler(uint8_t IWDG_Prescaler); +void IWDG_SetReload(uint16_t Reload); +void IWDG_ReloadCounter(void); + +/* IWDG activation function ***************************************************/ +void IWDG_Enable(void); + +/* Flag management function ***************************************************/ +FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_IWDG_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_pwr.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_pwr.h new file mode 100644 index 000000000..8f479841e --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_pwr.h @@ -0,0 +1,179 @@ +/** + ****************************************************************************** + * @file stm32f4xx_pwr.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the PWR firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_PWR_H +#define __STM32F4xx_PWR_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup PWR + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup PWR_Exported_Constants + * @{ + */ + +/** @defgroup PWR_PVD_detection_level + * @{ + */ + +#define PWR_PVDLevel_0 PWR_CR_PLS_LEV0 +#define PWR_PVDLevel_1 PWR_CR_PLS_LEV1 +#define PWR_PVDLevel_2 PWR_CR_PLS_LEV2 +#define PWR_PVDLevel_3 PWR_CR_PLS_LEV3 +#define PWR_PVDLevel_4 PWR_CR_PLS_LEV4 +#define PWR_PVDLevel_5 PWR_CR_PLS_LEV5 +#define PWR_PVDLevel_6 PWR_CR_PLS_LEV6 +#define PWR_PVDLevel_7 PWR_CR_PLS_LEV7 + +#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_0) || ((LEVEL) == PWR_PVDLevel_1)|| \ + ((LEVEL) == PWR_PVDLevel_2) || ((LEVEL) == PWR_PVDLevel_3)|| \ + ((LEVEL) == PWR_PVDLevel_4) || ((LEVEL) == PWR_PVDLevel_5)|| \ + ((LEVEL) == PWR_PVDLevel_6) || ((LEVEL) == PWR_PVDLevel_7)) +/** + * @} + */ + + +/** @defgroup PWR_Regulator_state_in_STOP_mode + * @{ + */ + +#define PWR_Regulator_ON ((uint32_t)0x00000000) +#define PWR_Regulator_LowPower PWR_CR_LPDS +#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \ + ((REGULATOR) == PWR_Regulator_LowPower)) +/** + * @} + */ + +/** @defgroup PWR_STOP_mode_entry + * @{ + */ + +#define PWR_STOPEntry_WFI ((uint8_t)0x01) +#define PWR_STOPEntry_WFE ((uint8_t)0x02) +#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE)) + +/** @defgroup PWR_Regulator_Voltage_Scale + * @{ + */ + +#define PWR_Regulator_Voltage_Scale1 ((uint32_t)0x00004000) +#define PWR_Regulator_Voltage_Scale2 ((uint32_t)0x00000000) +#define IS_PWR_REGULATOR_VOLTAGE(VOLTAGE) (((VOLTAGE) == PWR_Regulator_Voltage_Scale1) || ((VOLTAGE) == PWR_Regulator_Voltage_Scale2)) + +/** + * @} + */ + +/** @defgroup PWR_Flag + * @{ + */ + +#define PWR_FLAG_WU PWR_CSR_WUF +#define PWR_FLAG_SB PWR_CSR_SBF +#define PWR_FLAG_PVDO PWR_CSR_PVDO +#define PWR_FLAG_BRR PWR_CSR_BRR +#define PWR_FLAG_VOSRDY PWR_CSR_VOSRDY + +/** @defgroup PWR_Flag_Legacy + * @{ + */ +#define PWR_FLAG_REGRDY PWR_FLAG_VOSRDY +/** + * @} + */ + +#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \ + ((FLAG) == PWR_FLAG_PVDO) || ((FLAG) == PWR_FLAG_BRR) || \ + ((FLAG) == PWR_FLAG_VOSRDY)) + +#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the PWR configuration to the default reset state ******/ +void PWR_DeInit(void); + +/* Backup Domain Access function **********************************************/ +void PWR_BackupAccessCmd(FunctionalState NewState); + +/* PVD configuration functions ************************************************/ +void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel); +void PWR_PVDCmd(FunctionalState NewState); + +/* WakeUp pins configuration functions ****************************************/ +void PWR_WakeUpPinCmd(FunctionalState NewState); + +/* Main and Backup Regulators configuration functions *************************/ +void PWR_BackupRegulatorCmd(FunctionalState NewState); +void PWR_MainRegulatorModeConfig(uint32_t PWR_Regulator_Voltage); + +/* FLASH Power Down configuration functions ***********************************/ +void PWR_FlashPowerDownCmd(FunctionalState NewState); + +/* Low Power modes configuration functions ************************************/ +void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry); +void PWR_EnterSTANDBYMode(void); + +/* Flags management functions *************************************************/ +FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG); +void PWR_ClearFlag(uint32_t PWR_FLAG); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_PWR_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rcc.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rcc.h new file mode 100644 index 000000000..f06b643fc --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rcc.h @@ -0,0 +1,510 @@ +/** + ****************************************************************************** + * @file stm32f4xx_rcc.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the RCC firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_RCC_H +#define __STM32F4xx_RCC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RCC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +typedef struct +{ + uint32_t SYSCLK_Frequency; /*!< SYSCLK clock frequency expressed in Hz */ + uint32_t HCLK_Frequency; /*!< HCLK clock frequency expressed in Hz */ + uint32_t PCLK1_Frequency; /*!< PCLK1 clock frequency expressed in Hz */ + uint32_t PCLK2_Frequency; /*!< PCLK2 clock frequency expressed in Hz */ +}RCC_ClocksTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup RCC_Exported_Constants + * @{ + */ + +/** @defgroup RCC_HSE_configuration + * @{ + */ +#define RCC_HSE_OFF ((uint8_t)0x00) +#define RCC_HSE_ON ((uint8_t)0x01) +#define RCC_HSE_Bypass ((uint8_t)0x05) +#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \ + ((HSE) == RCC_HSE_Bypass)) +/** + * @} + */ + +/** @defgroup RCC_PLL_Clock_Source + * @{ + */ +#define RCC_PLLSource_HSI ((uint32_t)0x00000000) +#define RCC_PLLSource_HSE ((uint32_t)0x00400000) +#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI) || \ + ((SOURCE) == RCC_PLLSource_HSE)) +#define IS_RCC_PLLM_VALUE(VALUE) ((VALUE) <= 63) +#define IS_RCC_PLLN_VALUE(VALUE) ((192 <= (VALUE)) && ((VALUE) <= 432)) +#define IS_RCC_PLLP_VALUE(VALUE) (((VALUE) == 2) || ((VALUE) == 4) || ((VALUE) == 6) || ((VALUE) == 8)) +#define IS_RCC_PLLQ_VALUE(VALUE) ((4 <= (VALUE)) && ((VALUE) <= 15)) + +#define IS_RCC_PLLI2SN_VALUE(VALUE) ((192 <= (VALUE)) && ((VALUE) <= 432)) +#define IS_RCC_PLLI2SR_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 7)) +/** + * @} + */ + +/** @defgroup RCC_System_Clock_Source + * @{ + */ +#define RCC_SYSCLKSource_HSI ((uint32_t)0x00000000) +#define RCC_SYSCLKSource_HSE ((uint32_t)0x00000001) +#define RCC_SYSCLKSource_PLLCLK ((uint32_t)0x00000002) +#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \ + ((SOURCE) == RCC_SYSCLKSource_HSE) || \ + ((SOURCE) == RCC_SYSCLKSource_PLLCLK)) +/** + * @} + */ + +/** @defgroup RCC_AHB_Clock_Source + * @{ + */ +#define RCC_SYSCLK_Div1 ((uint32_t)0x00000000) +#define RCC_SYSCLK_Div2 ((uint32_t)0x00000080) +#define RCC_SYSCLK_Div4 ((uint32_t)0x00000090) +#define RCC_SYSCLK_Div8 ((uint32_t)0x000000A0) +#define RCC_SYSCLK_Div16 ((uint32_t)0x000000B0) +#define RCC_SYSCLK_Div64 ((uint32_t)0x000000C0) +#define RCC_SYSCLK_Div128 ((uint32_t)0x000000D0) +#define RCC_SYSCLK_Div256 ((uint32_t)0x000000E0) +#define RCC_SYSCLK_Div512 ((uint32_t)0x000000F0) +#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \ + ((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \ + ((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \ + ((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \ + ((HCLK) == RCC_SYSCLK_Div512)) +/** + * @} + */ + +/** @defgroup RCC_APB1_APB2_Clock_Source + * @{ + */ +#define RCC_HCLK_Div1 ((uint32_t)0x00000000) +#define RCC_HCLK_Div2 ((uint32_t)0x00001000) +#define RCC_HCLK_Div4 ((uint32_t)0x00001400) +#define RCC_HCLK_Div8 ((uint32_t)0x00001800) +#define RCC_HCLK_Div16 ((uint32_t)0x00001C00) +#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \ + ((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \ + ((PCLK) == RCC_HCLK_Div16)) +/** + * @} + */ + +/** @defgroup RCC_Interrupt_Source + * @{ + */ +#define RCC_IT_LSIRDY ((uint8_t)0x01) +#define RCC_IT_LSERDY ((uint8_t)0x02) +#define RCC_IT_HSIRDY ((uint8_t)0x04) +#define RCC_IT_HSERDY ((uint8_t)0x08) +#define RCC_IT_PLLRDY ((uint8_t)0x10) +#define RCC_IT_PLLI2SRDY ((uint8_t)0x20) +#define RCC_IT_CSS ((uint8_t)0x80) +#define IS_RCC_IT(IT) ((((IT) & (uint8_t)0xC0) == 0x00) && ((IT) != 0x00)) +#define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \ + ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \ + ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS) || \ + ((IT) == RCC_IT_PLLI2SRDY)) +#define IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x40) == 0x00) && ((IT) != 0x00)) +/** + * @} + */ + +/** @defgroup RCC_LSE_Configuration + * @{ + */ +#define RCC_LSE_OFF ((uint8_t)0x00) +#define RCC_LSE_ON ((uint8_t)0x01) +#define RCC_LSE_Bypass ((uint8_t)0x04) +#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \ + ((LSE) == RCC_LSE_Bypass)) +/** + * @} + */ + +/** @defgroup RCC_RTC_Clock_Source + * @{ + */ +#define RCC_RTCCLKSource_LSE ((uint32_t)0x00000100) +#define RCC_RTCCLKSource_LSI ((uint32_t)0x00000200) +#define RCC_RTCCLKSource_HSE_Div2 ((uint32_t)0x00020300) +#define RCC_RTCCLKSource_HSE_Div3 ((uint32_t)0x00030300) +#define RCC_RTCCLKSource_HSE_Div4 ((uint32_t)0x00040300) +#define RCC_RTCCLKSource_HSE_Div5 ((uint32_t)0x00050300) +#define RCC_RTCCLKSource_HSE_Div6 ((uint32_t)0x00060300) +#define RCC_RTCCLKSource_HSE_Div7 ((uint32_t)0x00070300) +#define RCC_RTCCLKSource_HSE_Div8 ((uint32_t)0x00080300) +#define RCC_RTCCLKSource_HSE_Div9 ((uint32_t)0x00090300) +#define RCC_RTCCLKSource_HSE_Div10 ((uint32_t)0x000A0300) +#define RCC_RTCCLKSource_HSE_Div11 ((uint32_t)0x000B0300) +#define RCC_RTCCLKSource_HSE_Div12 ((uint32_t)0x000C0300) +#define RCC_RTCCLKSource_HSE_Div13 ((uint32_t)0x000D0300) +#define RCC_RTCCLKSource_HSE_Div14 ((uint32_t)0x000E0300) +#define RCC_RTCCLKSource_HSE_Div15 ((uint32_t)0x000F0300) +#define RCC_RTCCLKSource_HSE_Div16 ((uint32_t)0x00100300) +#define RCC_RTCCLKSource_HSE_Div17 ((uint32_t)0x00110300) +#define RCC_RTCCLKSource_HSE_Div18 ((uint32_t)0x00120300) +#define RCC_RTCCLKSource_HSE_Div19 ((uint32_t)0x00130300) +#define RCC_RTCCLKSource_HSE_Div20 ((uint32_t)0x00140300) +#define RCC_RTCCLKSource_HSE_Div21 ((uint32_t)0x00150300) +#define RCC_RTCCLKSource_HSE_Div22 ((uint32_t)0x00160300) +#define RCC_RTCCLKSource_HSE_Div23 ((uint32_t)0x00170300) +#define RCC_RTCCLKSource_HSE_Div24 ((uint32_t)0x00180300) +#define RCC_RTCCLKSource_HSE_Div25 ((uint32_t)0x00190300) +#define RCC_RTCCLKSource_HSE_Div26 ((uint32_t)0x001A0300) +#define RCC_RTCCLKSource_HSE_Div27 ((uint32_t)0x001B0300) +#define RCC_RTCCLKSource_HSE_Div28 ((uint32_t)0x001C0300) +#define RCC_RTCCLKSource_HSE_Div29 ((uint32_t)0x001D0300) +#define RCC_RTCCLKSource_HSE_Div30 ((uint32_t)0x001E0300) +#define RCC_RTCCLKSource_HSE_Div31 ((uint32_t)0x001F0300) +#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \ + ((SOURCE) == RCC_RTCCLKSource_LSI) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div2) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div3) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div4) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div5) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div6) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div7) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div8) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div9) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div10) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div11) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div12) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div13) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div14) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div15) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div16) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div17) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div18) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div19) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div20) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div21) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div22) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div23) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div24) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div25) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div26) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div27) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div28) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div29) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div30) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div31)) +/** + * @} + */ + +/** @defgroup RCC_I2S_Clock_Source + * @{ + */ +#define RCC_I2S2CLKSource_PLLI2S ((uint8_t)0x00) +#define RCC_I2S2CLKSource_Ext ((uint8_t)0x01) + +#define IS_RCC_I2SCLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_PLLI2S) || ((SOURCE) == RCC_I2S2CLKSource_Ext)) +/** + * @} + */ + +/** @defgroup RCC_AHB1_Peripherals + * @{ + */ +#define RCC_AHB1Periph_GPIOA ((uint32_t)0x00000001) +#define RCC_AHB1Periph_GPIOB ((uint32_t)0x00000002) +#define RCC_AHB1Periph_GPIOC ((uint32_t)0x00000004) +#define RCC_AHB1Periph_GPIOD ((uint32_t)0x00000008) +#define RCC_AHB1Periph_GPIOE ((uint32_t)0x00000010) +#define RCC_AHB1Periph_GPIOF ((uint32_t)0x00000020) +#define RCC_AHB1Periph_GPIOG ((uint32_t)0x00000040) +#define RCC_AHB1Periph_GPIOH ((uint32_t)0x00000080) +#define RCC_AHB1Periph_GPIOI ((uint32_t)0x00000100) +#define RCC_AHB1Periph_CRC ((uint32_t)0x00001000) +#define RCC_AHB1Periph_FLITF ((uint32_t)0x00008000) +#define RCC_AHB1Periph_SRAM1 ((uint32_t)0x00010000) +#define RCC_AHB1Periph_SRAM2 ((uint32_t)0x00020000) +#define RCC_AHB1Periph_BKPSRAM ((uint32_t)0x00040000) +#define RCC_AHB1Periph_CCMDATARAMEN ((uint32_t)0x00100000) +#define RCC_AHB1Periph_DMA1 ((uint32_t)0x00200000) +#define RCC_AHB1Periph_DMA2 ((uint32_t)0x00400000) +#define RCC_AHB1Periph_ETH_MAC ((uint32_t)0x02000000) +#define RCC_AHB1Periph_ETH_MAC_Tx ((uint32_t)0x04000000) +#define RCC_AHB1Periph_ETH_MAC_Rx ((uint32_t)0x08000000) +#define RCC_AHB1Periph_ETH_MAC_PTP ((uint32_t)0x10000000) +#define RCC_AHB1Periph_OTG_HS ((uint32_t)0x20000000) +#define RCC_AHB1Periph_OTG_HS_ULPI ((uint32_t)0x40000000) +#define IS_RCC_AHB1_CLOCK_PERIPH(PERIPH) ((((PERIPH) & 0x818BEE00) == 0x00) && ((PERIPH) != 0x00)) +#define IS_RCC_AHB1_RESET_PERIPH(PERIPH) ((((PERIPH) & 0xDD9FEE00) == 0x00) && ((PERIPH) != 0x00)) +#define IS_RCC_AHB1_LPMODE_PERIPH(PERIPH) ((((PERIPH) & 0x81986E00) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup RCC_AHB2_Peripherals + * @{ + */ +#define RCC_AHB2Periph_DCMI ((uint32_t)0x00000001) +#define RCC_AHB2Periph_CRYP ((uint32_t)0x00000010) +#define RCC_AHB2Periph_HASH ((uint32_t)0x00000020) +#define RCC_AHB2Periph_RNG ((uint32_t)0x00000040) +#define RCC_AHB2Periph_OTG_FS ((uint32_t)0x00000080) +#define IS_RCC_AHB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFF0E) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup RCC_AHB3_Peripherals + * @{ + */ +#define RCC_AHB3Periph_FSMC ((uint32_t)0x00000001) +#define IS_RCC_AHB3_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFFE) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup RCC_APB1_Peripherals + * @{ + */ +#define RCC_APB1Periph_TIM2 ((uint32_t)0x00000001) +#define RCC_APB1Periph_TIM3 ((uint32_t)0x00000002) +#define RCC_APB1Periph_TIM4 ((uint32_t)0x00000004) +#define RCC_APB1Periph_TIM5 ((uint32_t)0x00000008) +#define RCC_APB1Periph_TIM6 ((uint32_t)0x00000010) +#define RCC_APB1Periph_TIM7 ((uint32_t)0x00000020) +#define RCC_APB1Periph_TIM12 ((uint32_t)0x00000040) +#define RCC_APB1Periph_TIM13 ((uint32_t)0x00000080) +#define RCC_APB1Periph_TIM14 ((uint32_t)0x00000100) +#define RCC_APB1Periph_WWDG ((uint32_t)0x00000800) +#define RCC_APB1Periph_SPI2 ((uint32_t)0x00004000) +#define RCC_APB1Periph_SPI3 ((uint32_t)0x00008000) +#define RCC_APB1Periph_USART2 ((uint32_t)0x00020000) +#define RCC_APB1Periph_USART3 ((uint32_t)0x00040000) +#define RCC_APB1Periph_UART4 ((uint32_t)0x00080000) +#define RCC_APB1Periph_UART5 ((uint32_t)0x00100000) +#define RCC_APB1Periph_I2C1 ((uint32_t)0x00200000) +#define RCC_APB1Periph_I2C2 ((uint32_t)0x00400000) +#define RCC_APB1Periph_I2C3 ((uint32_t)0x00800000) +#define RCC_APB1Periph_CAN1 ((uint32_t)0x02000000) +#define RCC_APB1Periph_CAN2 ((uint32_t)0x04000000) +#define RCC_APB1Periph_PWR ((uint32_t)0x10000000) +#define RCC_APB1Periph_DAC ((uint32_t)0x20000000) +#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0xC9013600) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup RCC_APB2_Peripherals + * @{ + */ +#define RCC_APB2Periph_TIM1 ((uint32_t)0x00000001) +#define RCC_APB2Periph_TIM8 ((uint32_t)0x00000002) +#define RCC_APB2Periph_USART1 ((uint32_t)0x00000010) +#define RCC_APB2Periph_USART6 ((uint32_t)0x00000020) +#define RCC_APB2Periph_ADC ((uint32_t)0x00000100) +#define RCC_APB2Periph_ADC1 ((uint32_t)0x00000100) +#define RCC_APB2Periph_ADC2 ((uint32_t)0x00000200) +#define RCC_APB2Periph_ADC3 ((uint32_t)0x00000400) +#define RCC_APB2Periph_SDIO ((uint32_t)0x00000800) +#define RCC_APB2Periph_SPI1 ((uint32_t)0x00001000) +#define RCC_APB2Periph_SYSCFG ((uint32_t)0x00004000) +#define RCC_APB2Periph_TIM9 ((uint32_t)0x00010000) +#define RCC_APB2Periph_TIM10 ((uint32_t)0x00020000) +#define RCC_APB2Periph_TIM11 ((uint32_t)0x00040000) +#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFF8A0CC) == 0x00) && ((PERIPH) != 0x00)) +#define IS_RCC_APB2_RESET_PERIPH(PERIPH) ((((PERIPH) & 0xFFF8A6CC) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup RCC_MCO1_Clock_Source_Prescaler + * @{ + */ +#define RCC_MCO1Source_HSI ((uint32_t)0x00000000) +#define RCC_MCO1Source_LSE ((uint32_t)0x00200000) +#define RCC_MCO1Source_HSE ((uint32_t)0x00400000) +#define RCC_MCO1Source_PLLCLK ((uint32_t)0x00600000) +#define RCC_MCO1Div_1 ((uint32_t)0x00000000) +#define RCC_MCO1Div_2 ((uint32_t)0x04000000) +#define RCC_MCO1Div_3 ((uint32_t)0x05000000) +#define RCC_MCO1Div_4 ((uint32_t)0x06000000) +#define RCC_MCO1Div_5 ((uint32_t)0x07000000) +#define IS_RCC_MCO1SOURCE(SOURCE) (((SOURCE) == RCC_MCO1Source_HSI) || ((SOURCE) == RCC_MCO1Source_LSE) || \ + ((SOURCE) == RCC_MCO1Source_HSE) || ((SOURCE) == RCC_MCO1Source_PLLCLK)) + +#define IS_RCC_MCO1DIV(DIV) (((DIV) == RCC_MCO1Div_1) || ((DIV) == RCC_MCO1Div_2) || \ + ((DIV) == RCC_MCO1Div_3) || ((DIV) == RCC_MCO1Div_4) || \ + ((DIV) == RCC_MCO1Div_5)) +/** + * @} + */ + +/** @defgroup RCC_MCO2_Clock_Source_Prescaler + * @{ + */ +#define RCC_MCO2Source_SYSCLK ((uint32_t)0x00000000) +#define RCC_MCO2Source_PLLI2SCLK ((uint32_t)0x40000000) +#define RCC_MCO2Source_HSE ((uint32_t)0x80000000) +#define RCC_MCO2Source_PLLCLK ((uint32_t)0xC0000000) +#define RCC_MCO2Div_1 ((uint32_t)0x00000000) +#define RCC_MCO2Div_2 ((uint32_t)0x20000000) +#define RCC_MCO2Div_3 ((uint32_t)0x28000000) +#define RCC_MCO2Div_4 ((uint32_t)0x30000000) +#define RCC_MCO2Div_5 ((uint32_t)0x38000000) +#define IS_RCC_MCO2SOURCE(SOURCE) (((SOURCE) == RCC_MCO2Source_SYSCLK) || ((SOURCE) == RCC_MCO2Source_PLLI2SCLK)|| \ + ((SOURCE) == RCC_MCO2Source_HSE) || ((SOURCE) == RCC_MCO2Source_PLLCLK)) + +#define IS_RCC_MCO2DIV(DIV) (((DIV) == RCC_MCO2Div_1) || ((DIV) == RCC_MCO2Div_2) || \ + ((DIV) == RCC_MCO2Div_3) || ((DIV) == RCC_MCO2Div_4) || \ + ((DIV) == RCC_MCO2Div_5)) +/** + * @} + */ + +/** @defgroup RCC_Flag + * @{ + */ +#define RCC_FLAG_HSIRDY ((uint8_t)0x21) +#define RCC_FLAG_HSERDY ((uint8_t)0x31) +#define RCC_FLAG_PLLRDY ((uint8_t)0x39) +#define RCC_FLAG_PLLI2SRDY ((uint8_t)0x3B) +#define RCC_FLAG_LSERDY ((uint8_t)0x41) +#define RCC_FLAG_LSIRDY ((uint8_t)0x61) +#define RCC_FLAG_BORRST ((uint8_t)0x79) +#define RCC_FLAG_PINRST ((uint8_t)0x7A) +#define RCC_FLAG_PORRST ((uint8_t)0x7B) +#define RCC_FLAG_SFTRST ((uint8_t)0x7C) +#define RCC_FLAG_IWDGRST ((uint8_t)0x7D) +#define RCC_FLAG_WWDGRST ((uint8_t)0x7E) +#define RCC_FLAG_LPWRRST ((uint8_t)0x7F) +#define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \ + ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \ + ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_BORRST) || \ + ((FLAG) == RCC_FLAG_PINRST) || ((FLAG) == RCC_FLAG_PORRST) || \ + ((FLAG) == RCC_FLAG_SFTRST) || ((FLAG) == RCC_FLAG_IWDGRST)|| \ + ((FLAG) == RCC_FLAG_WWDGRST)|| ((FLAG) == RCC_FLAG_LPWRRST)|| \ + ((FLAG) == RCC_FLAG_PLLI2SRDY)) +#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the RCC clock configuration to the default reset state */ +void RCC_DeInit(void); + +/* Internal/external clocks, PLL, CSS and MCO configuration functions *********/ +void RCC_HSEConfig(uint8_t RCC_HSE); +ErrorStatus RCC_WaitForHSEStartUp(void); +void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue); +void RCC_HSICmd(FunctionalState NewState); +void RCC_LSEConfig(uint8_t RCC_LSE); +void RCC_LSICmd(FunctionalState NewState); + +void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ); +void RCC_PLLCmd(FunctionalState NewState); +void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SR); +void RCC_PLLI2SCmd(FunctionalState NewState); + +void RCC_ClockSecuritySystemCmd(FunctionalState NewState); +void RCC_MCO1Config(uint32_t RCC_MCO1Source, uint32_t RCC_MCO1Div); +void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div); + +/* System, AHB and APB busses clocks configuration functions ******************/ +void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource); +uint8_t RCC_GetSYSCLKSource(void); +void RCC_HCLKConfig(uint32_t RCC_SYSCLK); +void RCC_PCLK1Config(uint32_t RCC_HCLK); +void RCC_PCLK2Config(uint32_t RCC_HCLK); +void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks); + +/* Peripheral clocks configuration functions **********************************/ +void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource); +void RCC_RTCCLKCmd(FunctionalState NewState); +void RCC_BackupResetCmd(FunctionalState NewState); +void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource); + +void RCC_AHB1PeriphClockCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState); +void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState); +void RCC_AHB3PeriphClockCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState); +void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); +void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); + +void RCC_AHB1PeriphResetCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState); +void RCC_AHB2PeriphResetCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState); +void RCC_AHB3PeriphResetCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState); +void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); +void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); + +void RCC_AHB1PeriphClockLPModeCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState); +void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState); +void RCC_AHB3PeriphClockLPModeCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState); +void RCC_APB1PeriphClockLPModeCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); +void RCC_APB2PeriphClockLPModeCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); + +/* Interrupts and flags management functions **********************************/ +void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState); +FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG); +void RCC_ClearFlag(void); +ITStatus RCC_GetITStatus(uint8_t RCC_IT); +void RCC_ClearITPendingBit(uint8_t RCC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_RCC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rng.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rng.h new file mode 100644 index 000000000..5a080a3b6 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rng.h @@ -0,0 +1,114 @@ +/** + ****************************************************************************** + * @file stm32f4xx_rng.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the Random + * Number Generator(RNG) firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_RNG_H +#define __STM32F4xx_RNG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RNG + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup RNG_Exported_Constants + * @{ + */ + +/** @defgroup RNG_flags_definition + * @{ + */ +#define RNG_FLAG_DRDY ((uint8_t)0x0001) /*!< Data ready */ +#define RNG_FLAG_CECS ((uint8_t)0x0002) /*!< Clock error current status */ +#define RNG_FLAG_SECS ((uint8_t)0x0004) /*!< Seed error current status */ + +#define IS_RNG_GET_FLAG(RNG_FLAG) (((RNG_FLAG) == RNG_FLAG_DRDY) || \ + ((RNG_FLAG) == RNG_FLAG_CECS) || \ + ((RNG_FLAG) == RNG_FLAG_SECS)) +#define IS_RNG_CLEAR_FLAG(RNG_FLAG) (((RNG_FLAG) == RNG_FLAG_CECS) || \ + ((RNG_FLAG) == RNG_FLAG_SECS)) +/** + * @} + */ + +/** @defgroup RNG_interrupts_definition + * @{ + */ +#define RNG_IT_CEI ((uint8_t)0x20) /*!< Clock error interrupt */ +#define RNG_IT_SEI ((uint8_t)0x40) /*!< Seed error interrupt */ + +#define IS_RNG_IT(IT) ((((IT) & (uint8_t)0x9F) == 0x00) && ((IT) != 0x00)) +#define IS_RNG_GET_IT(RNG_IT) (((RNG_IT) == RNG_IT_CEI) || ((RNG_IT) == RNG_IT_SEI)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the RNG configuration to the default reset state *****/ +void RNG_DeInit(void); + +/* Configuration function *****************************************************/ +void RNG_Cmd(FunctionalState NewState); + +/* Get 32 bit Random number function ******************************************/ +uint32_t RNG_GetRandomNumber(void); + +/* Interrupts and flags management functions **********************************/ +void RNG_ITConfig(FunctionalState NewState); +FlagStatus RNG_GetFlagStatus(uint8_t RNG_FLAG); +void RNG_ClearFlag(uint8_t RNG_FLAG); +ITStatus RNG_GetITStatus(uint8_t RNG_IT); +void RNG_ClearITPendingBit(uint8_t RNG_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_RNG_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rtc.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rtc.h new file mode 100644 index 000000000..d5e5794cc --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rtc.h @@ -0,0 +1,875 @@ +/** + ****************************************************************************** + * @file stm32f4xx_rtc.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the RTC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_RTC_H +#define __STM32F4xx_RTC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RTC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief RTC Init structures definition + */ +typedef struct +{ + uint32_t RTC_HourFormat; /*!< Specifies the RTC Hour Format. + This parameter can be a value of @ref RTC_Hour_Formats */ + + uint32_t RTC_AsynchPrediv; /*!< Specifies the RTC Asynchronous Predivider value. + This parameter must be set to a value lower than 0x7F */ + + uint32_t RTC_SynchPrediv; /*!< Specifies the RTC Synchronous Predivider value. + This parameter must be set to a value lower than 0x7FFF */ +}RTC_InitTypeDef; + +/** + * @brief RTC Time structure definition + */ +typedef struct +{ + uint8_t RTC_Hours; /*!< Specifies the RTC Time Hour. + This parameter must be set to a value in the 0-12 range + if the RTC_HourFormat_12 is selected or 0-23 range if + the RTC_HourFormat_24 is selected. */ + + uint8_t RTC_Minutes; /*!< Specifies the RTC Time Minutes. + This parameter must be set to a value in the 0-59 range. */ + + uint8_t RTC_Seconds; /*!< Specifies the RTC Time Seconds. + This parameter must be set to a value in the 0-59 range. */ + + uint8_t RTC_H12; /*!< Specifies the RTC AM/PM Time. + This parameter can be a value of @ref RTC_AM_PM_Definitions */ +}RTC_TimeTypeDef; + +/** + * @brief RTC Date structure definition + */ +typedef struct +{ + uint8_t RTC_WeekDay; /*!< Specifies the RTC Date WeekDay. + This parameter can be a value of @ref RTC_WeekDay_Definitions */ + + uint8_t RTC_Month; /*!< Specifies the RTC Date Month (in BCD format). + This parameter can be a value of @ref RTC_Month_Date_Definitions */ + + uint8_t RTC_Date; /*!< Specifies the RTC Date. + This parameter must be set to a value in the 1-31 range. */ + + uint8_t RTC_Year; /*!< Specifies the RTC Date Year. + This parameter must be set to a value in the 0-99 range. */ +}RTC_DateTypeDef; + +/** + * @brief RTC Alarm structure definition + */ +typedef struct +{ + RTC_TimeTypeDef RTC_AlarmTime; /*!< Specifies the RTC Alarm Time members. */ + + uint32_t RTC_AlarmMask; /*!< Specifies the RTC Alarm Masks. + This parameter can be a value of @ref RTC_AlarmMask_Definitions */ + + uint32_t RTC_AlarmDateWeekDaySel; /*!< Specifies the RTC Alarm is on Date or WeekDay. + This parameter can be a value of @ref RTC_AlarmDateWeekDay_Definitions */ + + uint8_t RTC_AlarmDateWeekDay; /*!< Specifies the RTC Alarm Date/WeekDay. + If the Alarm Date is selected, this parameter + must be set to a value in the 1-31 range. + If the Alarm WeekDay is selected, this + parameter can be a value of @ref RTC_WeekDay_Definitions */ +}RTC_AlarmTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup RTC_Exported_Constants + * @{ + */ + + +/** @defgroup RTC_Hour_Formats + * @{ + */ +#define RTC_HourFormat_24 ((uint32_t)0x00000000) +#define RTC_HourFormat_12 ((uint32_t)0x00000040) +#define IS_RTC_HOUR_FORMAT(FORMAT) (((FORMAT) == RTC_HourFormat_12) || \ + ((FORMAT) == RTC_HourFormat_24)) +/** + * @} + */ + +/** @defgroup RTC_Asynchronous_Predivider + * @{ + */ +#define IS_RTC_ASYNCH_PREDIV(PREDIV) ((PREDIV) <= 0x7F) + +/** + * @} + */ + + +/** @defgroup RTC_Synchronous_Predivider + * @{ + */ +#define IS_RTC_SYNCH_PREDIV(PREDIV) ((PREDIV) <= 0x7FFF) + +/** + * @} + */ + +/** @defgroup RTC_Time_Definitions + * @{ + */ +#define IS_RTC_HOUR12(HOUR) (((HOUR) > 0) && ((HOUR) <= 12)) +#define IS_RTC_HOUR24(HOUR) ((HOUR) <= 23) +#define IS_RTC_MINUTES(MINUTES) ((MINUTES) <= 59) +#define IS_RTC_SECONDS(SECONDS) ((SECONDS) <= 59) + +/** + * @} + */ + +/** @defgroup RTC_AM_PM_Definitions + * @{ + */ +#define RTC_H12_AM ((uint8_t)0x00) +#define RTC_H12_PM ((uint8_t)0x40) +#define IS_RTC_H12(PM) (((PM) == RTC_H12_AM) || ((PM) == RTC_H12_PM)) + +/** + * @} + */ + +/** @defgroup RTC_Year_Date_Definitions + * @{ + */ +#define IS_RTC_YEAR(YEAR) ((YEAR) <= 99) + +/** + * @} + */ + +/** @defgroup RTC_Month_Date_Definitions + * @{ + */ + +/* Coded in BCD format */ +#define RTC_Month_January ((uint8_t)0x01) +#define RTC_Month_February ((uint8_t)0x02) +#define RTC_Month_March ((uint8_t)0x03) +#define RTC_Month_April ((uint8_t)0x04) +#define RTC_Month_May ((uint8_t)0x05) +#define RTC_Month_June ((uint8_t)0x06) +#define RTC_Month_July ((uint8_t)0x07) +#define RTC_Month_August ((uint8_t)0x08) +#define RTC_Month_September ((uint8_t)0x09) +#define RTC_Month_October ((uint8_t)0x10) +#define RTC_Month_November ((uint8_t)0x11) +#define RTC_Month_December ((uint8_t)0x12) +#define IS_RTC_MONTH(MONTH) (((MONTH) >= 1) && ((MONTH) <= 12)) +#define IS_RTC_DATE(DATE) (((DATE) >= 1) && ((DATE) <= 31)) + +/** + * @} + */ + +/** @defgroup RTC_WeekDay_Definitions + * @{ + */ + +#define RTC_Weekday_Monday ((uint8_t)0x01) +#define RTC_Weekday_Tuesday ((uint8_t)0x02) +#define RTC_Weekday_Wednesday ((uint8_t)0x03) +#define RTC_Weekday_Thursday ((uint8_t)0x04) +#define RTC_Weekday_Friday ((uint8_t)0x05) +#define RTC_Weekday_Saturday ((uint8_t)0x06) +#define RTC_Weekday_Sunday ((uint8_t)0x07) +#define IS_RTC_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_Weekday_Monday) || \ + ((WEEKDAY) == RTC_Weekday_Tuesday) || \ + ((WEEKDAY) == RTC_Weekday_Wednesday) || \ + ((WEEKDAY) == RTC_Weekday_Thursday) || \ + ((WEEKDAY) == RTC_Weekday_Friday) || \ + ((WEEKDAY) == RTC_Weekday_Saturday) || \ + ((WEEKDAY) == RTC_Weekday_Sunday)) +/** + * @} + */ + + +/** @defgroup RTC_Alarm_Definitions + * @{ + */ +#define IS_RTC_ALARM_DATE_WEEKDAY_DATE(DATE) (((DATE) > 0) && ((DATE) <= 31)) +#define IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_Weekday_Monday) || \ + ((WEEKDAY) == RTC_Weekday_Tuesday) || \ + ((WEEKDAY) == RTC_Weekday_Wednesday) || \ + ((WEEKDAY) == RTC_Weekday_Thursday) || \ + ((WEEKDAY) == RTC_Weekday_Friday) || \ + ((WEEKDAY) == RTC_Weekday_Saturday) || \ + ((WEEKDAY) == RTC_Weekday_Sunday)) + +/** + * @} + */ + + +/** @defgroup RTC_AlarmDateWeekDay_Definitions + * @{ + */ +#define RTC_AlarmDateWeekDaySel_Date ((uint32_t)0x00000000) +#define RTC_AlarmDateWeekDaySel_WeekDay ((uint32_t)0x40000000) + +#define IS_RTC_ALARM_DATE_WEEKDAY_SEL(SEL) (((SEL) == RTC_AlarmDateWeekDaySel_Date) || \ + ((SEL) == RTC_AlarmDateWeekDaySel_WeekDay)) + +/** + * @} + */ + + +/** @defgroup RTC_AlarmMask_Definitions + * @{ + */ +#define RTC_AlarmMask_None ((uint32_t)0x00000000) +#define RTC_AlarmMask_DateWeekDay ((uint32_t)0x80000000) +#define RTC_AlarmMask_Hours ((uint32_t)0x00800000) +#define RTC_AlarmMask_Minutes ((uint32_t)0x00008000) +#define RTC_AlarmMask_Seconds ((uint32_t)0x00000080) +#define RTC_AlarmMask_All ((uint32_t)0x80808080) +#define IS_ALARM_MASK(MASK) (((MASK) & 0x7F7F7F7F) == (uint32_t)RESET) + +/** + * @} + */ + +/** @defgroup RTC_Alarms_Definitions + * @{ + */ +#define RTC_Alarm_A ((uint32_t)0x00000100) +#define RTC_Alarm_B ((uint32_t)0x00000200) +#define IS_RTC_ALARM(ALARM) (((ALARM) == RTC_Alarm_A) || ((ALARM) == RTC_Alarm_B)) +#define IS_RTC_CMD_ALARM(ALARM) (((ALARM) & (RTC_Alarm_A | RTC_Alarm_B)) != (uint32_t)RESET) + +/** + * @} + */ + + /** @defgroup RTC_Alarm_Sub_Seconds_Masks_Definitions + * @{ + */ +#define RTC_AlarmSubSecondMask_All ((uint32_t)0x00000000) /*!< All Alarm SS fields are masked. + There is no comparison on sub seconds + for Alarm */ +#define RTC_AlarmSubSecondMask_SS14_1 ((uint32_t)0x01000000) /*!< SS[14:1] are don't care in Alarm + comparison. Only SS[0] is compared. */ +#define RTC_AlarmSubSecondMask_SS14_2 ((uint32_t)0x02000000) /*!< SS[14:2] are don't care in Alarm + comparison. Only SS[1:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_3 ((uint32_t)0x03000000) /*!< SS[14:3] are don't care in Alarm + comparison. Only SS[2:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_4 ((uint32_t)0x04000000) /*!< SS[14:4] are don't care in Alarm + comparison. Only SS[3:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_5 ((uint32_t)0x05000000) /*!< SS[14:5] are don't care in Alarm + comparison. Only SS[4:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_6 ((uint32_t)0x06000000) /*!< SS[14:6] are don't care in Alarm + comparison. Only SS[5:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_7 ((uint32_t)0x07000000) /*!< SS[14:7] are don't care in Alarm + comparison. Only SS[6:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_8 ((uint32_t)0x08000000) /*!< SS[14:8] are don't care in Alarm + comparison. Only SS[7:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_9 ((uint32_t)0x09000000) /*!< SS[14:9] are don't care in Alarm + comparison. Only SS[8:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_10 ((uint32_t)0x0A000000) /*!< SS[14:10] are don't care in Alarm + comparison. Only SS[9:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_11 ((uint32_t)0x0B000000) /*!< SS[14:11] are don't care in Alarm + comparison. Only SS[10:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_12 ((uint32_t)0x0C000000) /*!< SS[14:12] are don't care in Alarm + comparison.Only SS[11:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_13 ((uint32_t)0x0D000000) /*!< SS[14:13] are don't care in Alarm + comparison. Only SS[12:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14 ((uint32_t)0x0E000000) /*!< SS[14] is don't care in Alarm + comparison.Only SS[13:0] are compared */ +#define RTC_AlarmSubSecondMask_None ((uint32_t)0x0F000000) /*!< SS[14:0] are compared and must match + to activate alarm. */ +#define IS_RTC_ALARM_SUB_SECOND_MASK(MASK) (((MASK) == RTC_AlarmSubSecondMask_All) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_1) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_2) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_3) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_4) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_5) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_6) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_7) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_8) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_9) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_10) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_11) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_12) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_13) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14) || \ + ((MASK) == RTC_AlarmSubSecondMask_None)) +/** + * @} + */ + +/** @defgroup RTC_Alarm_Sub_Seconds_Value + * @{ + */ + +#define IS_RTC_ALARM_SUB_SECOND_VALUE(VALUE) ((VALUE) <= 0x00007FFF) + +/** + * @} + */ + +/** @defgroup RTC_Wakeup_Timer_Definitions + * @{ + */ +#define RTC_WakeUpClock_RTCCLK_Div16 ((uint32_t)0x00000000) +#define RTC_WakeUpClock_RTCCLK_Div8 ((uint32_t)0x00000001) +#define RTC_WakeUpClock_RTCCLK_Div4 ((uint32_t)0x00000002) +#define RTC_WakeUpClock_RTCCLK_Div2 ((uint32_t)0x00000003) +#define RTC_WakeUpClock_CK_SPRE_16bits ((uint32_t)0x00000004) +#define RTC_WakeUpClock_CK_SPRE_17bits ((uint32_t)0x00000006) +#define IS_RTC_WAKEUP_CLOCK(CLOCK) (((CLOCK) == RTC_WakeUpClock_RTCCLK_Div16) || \ + ((CLOCK) == RTC_WakeUpClock_RTCCLK_Div8) || \ + ((CLOCK) == RTC_WakeUpClock_RTCCLK_Div4) || \ + ((CLOCK) == RTC_WakeUpClock_RTCCLK_Div2) || \ + ((CLOCK) == RTC_WakeUpClock_CK_SPRE_16bits) || \ + ((CLOCK) == RTC_WakeUpClock_CK_SPRE_17bits)) +#define IS_RTC_WAKEUP_COUNTER(COUNTER) ((COUNTER) <= 0xFFFF) +/** + * @} + */ + +/** @defgroup RTC_Time_Stamp_Edges_definitions + * @{ + */ +#define RTC_TimeStampEdge_Rising ((uint32_t)0x00000000) +#define RTC_TimeStampEdge_Falling ((uint32_t)0x00000008) +#define IS_RTC_TIMESTAMP_EDGE(EDGE) (((EDGE) == RTC_TimeStampEdge_Rising) || \ + ((EDGE) == RTC_TimeStampEdge_Falling)) +/** + * @} + */ + +/** @defgroup RTC_Output_selection_Definitions + * @{ + */ +#define RTC_Output_Disable ((uint32_t)0x00000000) +#define RTC_Output_AlarmA ((uint32_t)0x00200000) +#define RTC_Output_AlarmB ((uint32_t)0x00400000) +#define RTC_Output_WakeUp ((uint32_t)0x00600000) + +#define IS_RTC_OUTPUT(OUTPUT) (((OUTPUT) == RTC_Output_Disable) || \ + ((OUTPUT) == RTC_Output_AlarmA) || \ + ((OUTPUT) == RTC_Output_AlarmB) || \ + ((OUTPUT) == RTC_Output_WakeUp)) + +/** + * @} + */ + +/** @defgroup RTC_Output_Polarity_Definitions + * @{ + */ +#define RTC_OutputPolarity_High ((uint32_t)0x00000000) +#define RTC_OutputPolarity_Low ((uint32_t)0x00100000) +#define IS_RTC_OUTPUT_POL(POL) (((POL) == RTC_OutputPolarity_High) || \ + ((POL) == RTC_OutputPolarity_Low)) +/** + * @} + */ + + +/** @defgroup RTC_Digital_Calibration_Definitions + * @{ + */ +#define RTC_CalibSign_Positive ((uint32_t)0x00000000) +#define RTC_CalibSign_Negative ((uint32_t)0x00000080) +#define IS_RTC_CALIB_SIGN(SIGN) (((SIGN) == RTC_CalibSign_Positive) || \ + ((SIGN) == RTC_CalibSign_Negative)) +#define IS_RTC_CALIB_VALUE(VALUE) ((VALUE) < 0x20) + +/** + * @} + */ + + /** @defgroup RTC_Calib_Output_selection_Definitions + * @{ + */ +#define RTC_CalibOutput_512Hz ((uint32_t)0x00000000) +#define RTC_CalibOutput_1Hz ((uint32_t)0x00080000) +#define IS_RTC_CALIB_OUTPUT(OUTPUT) (((OUTPUT) == RTC_CalibOutput_512Hz) || \ + ((OUTPUT) == RTC_CalibOutput_1Hz)) +/** + * @} + */ + +/** @defgroup RTC_Smooth_calib_period_Definitions + * @{ + */ +#define RTC_SmoothCalibPeriod_32sec ((uint32_t)0x00000000) /*!< if RTCCLK = 32768 Hz, Smooth calibation + period is 32s, else 2exp20 RTCCLK seconds */ +#define RTC_SmoothCalibPeriod_16sec ((uint32_t)0x00002000) /*!< if RTCCLK = 32768 Hz, Smooth calibation + period is 16s, else 2exp19 RTCCLK seconds */ +#define RTC_SmoothCalibPeriod_8sec ((uint32_t)0x00004000) /*!< if RTCCLK = 32768 Hz, Smooth calibation + period is 8s, else 2exp18 RTCCLK seconds */ +#define IS_RTC_SMOOTH_CALIB_PERIOD(PERIOD) (((PERIOD) == RTC_SmoothCalibPeriod_32sec) || \ + ((PERIOD) == RTC_SmoothCalibPeriod_16sec) || \ + ((PERIOD) == RTC_SmoothCalibPeriod_8sec)) + +/** + * @} + */ + +/** @defgroup RTC_Smooth_calib_Plus_pulses_Definitions + * @{ + */ +#define RTC_SmoothCalibPlusPulses_Set ((uint32_t)0x00008000) /*!< The number of RTCCLK pulses added + during a X -second window = Y - CALM[8:0]. + with Y = 512, 256, 128 when X = 32, 16, 8 */ +#define RTC_SmoothCalibPlusPulses_Reset ((uint32_t)0x00000000) /*!< The number of RTCCLK pulses subbstited + during a 32-second window = CALM[8:0]. */ +#define IS_RTC_SMOOTH_CALIB_PLUS(PLUS) (((PLUS) == RTC_SmoothCalibPlusPulses_Set) || \ + ((PLUS) == RTC_SmoothCalibPlusPulses_Reset)) + +/** + * @} + */ + +/** @defgroup RTC_Smooth_calib_Minus_pulses_Definitions + * @{ + */ +#define IS_RTC_SMOOTH_CALIB_MINUS(VALUE) ((VALUE) <= 0x000001FF) + +/** + * @} + */ + +/** @defgroup RTC_DayLightSaving_Definitions + * @{ + */ +#define RTC_DayLightSaving_SUB1H ((uint32_t)0x00020000) +#define RTC_DayLightSaving_ADD1H ((uint32_t)0x00010000) +#define IS_RTC_DAYLIGHT_SAVING(SAVE) (((SAVE) == RTC_DayLightSaving_SUB1H) || \ + ((SAVE) == RTC_DayLightSaving_ADD1H)) + +#define RTC_StoreOperation_Reset ((uint32_t)0x00000000) +#define RTC_StoreOperation_Set ((uint32_t)0x00040000) +#define IS_RTC_STORE_OPERATION(OPERATION) (((OPERATION) == RTC_StoreOperation_Reset) || \ + ((OPERATION) == RTC_StoreOperation_Set)) +/** + * @} + */ + +/** @defgroup RTC_Tamper_Trigger_Definitions + * @{ + */ +#define RTC_TamperTrigger_RisingEdge ((uint32_t)0x00000000) +#define RTC_TamperTrigger_FallingEdge ((uint32_t)0x00000001) +#define RTC_TamperTrigger_LowLevel ((uint32_t)0x00000000) +#define RTC_TamperTrigger_HighLevel ((uint32_t)0x00000001) +#define IS_RTC_TAMPER_TRIGGER(TRIGGER) (((TRIGGER) == RTC_TamperTrigger_RisingEdge) || \ + ((TRIGGER) == RTC_TamperTrigger_FallingEdge) || \ + ((TRIGGER) == RTC_TamperTrigger_LowLevel) || \ + ((TRIGGER) == RTC_TamperTrigger_HighLevel)) + +/** + * @} + */ + +/** @defgroup RTC_Tamper_Filter_Definitions + * @{ + */ +#define RTC_TamperFilter_Disable ((uint32_t)0x00000000) /*!< Tamper filter is disabled */ + +#define RTC_TamperFilter_2Sample ((uint32_t)0x00000800) /*!< Tamper is activated after 2 + consecutive samples at the active level */ +#define RTC_TamperFilter_4Sample ((uint32_t)0x00001000) /*!< Tamper is activated after 4 + consecutive samples at the active level */ +#define RTC_TamperFilter_8Sample ((uint32_t)0x00001800) /*!< Tamper is activated after 8 + consecutive samples at the active leve. */ +#define IS_RTC_TAMPER_FILTER(FILTER) (((FILTER) == RTC_TamperFilter_Disable) || \ + ((FILTER) == RTC_TamperFilter_2Sample) || \ + ((FILTER) == RTC_TamperFilter_4Sample) || \ + ((FILTER) == RTC_TamperFilter_8Sample)) +/** + * @} + */ + +/** @defgroup RTC_Tamper_Sampling_Frequencies_Definitions + * @{ + */ +#define RTC_TamperSamplingFreq_RTCCLK_Div32768 ((uint32_t)0x00000000) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 32768 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div16384 ((uint32_t)0x000000100) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 16384 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div8192 ((uint32_t)0x00000200) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 8192 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div4096 ((uint32_t)0x00000300) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 4096 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div2048 ((uint32_t)0x00000400) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 2048 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div1024 ((uint32_t)0x00000500) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 1024 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div512 ((uint32_t)0x00000600) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 512 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div256 ((uint32_t)0x00000700) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 256 */ +#define IS_RTC_TAMPER_SAMPLING_FREQ(FREQ) (((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div32768) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div16384) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div8192) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div4096) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div2048) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div1024) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div512) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div256)) + +/** + * @} + */ + + /** @defgroup RTC_Tamper_Pin_Precharge_Duration_Definitions + * @{ + */ +#define RTC_TamperPrechargeDuration_1RTCCLK ((uint32_t)0x00000000) /*!< Tamper pins are pre-charged before + sampling during 1 RTCCLK cycle */ +#define RTC_TamperPrechargeDuration_2RTCCLK ((uint32_t)0x00002000) /*!< Tamper pins are pre-charged before + sampling during 2 RTCCLK cycles */ +#define RTC_TamperPrechargeDuration_4RTCCLK ((uint32_t)0x00004000) /*!< Tamper pins are pre-charged before + sampling during 4 RTCCLK cycles */ +#define RTC_TamperPrechargeDuration_8RTCCLK ((uint32_t)0x00006000) /*!< Tamper pins are pre-charged before + sampling during 8 RTCCLK cycles */ + +#define IS_RTC_TAMPER_PRECHARGE_DURATION(DURATION) (((DURATION) == RTC_TamperPrechargeDuration_1RTCCLK) || \ + ((DURATION) == RTC_TamperPrechargeDuration_2RTCCLK) || \ + ((DURATION) == RTC_TamperPrechargeDuration_4RTCCLK) || \ + ((DURATION) == RTC_TamperPrechargeDuration_8RTCCLK)) +/** + * @} + */ + +/** @defgroup RTC_Tamper_Pins_Definitions + * @{ + */ +#define RTC_Tamper_1 RTC_TAFCR_TAMP1E +#define IS_RTC_TAMPER(TAMPER) (((TAMPER) == RTC_Tamper_1)) + +/** + * @} + */ + +/** @defgroup RTC_Tamper_Pin_Selection + * @{ + */ +#define RTC_TamperPin_PC13 ((uint32_t)0x00000000) +#define RTC_TamperPin_PI8 ((uint32_t)0x00010000) +#define IS_RTC_TAMPER_PIN(PIN) (((PIN) == RTC_TamperPin_PC13) || \ + ((PIN) == RTC_TamperPin_PI8)) +/** + * @} + */ + +/** @defgroup RTC_TimeStamp_Pin_Selection + * @{ + */ +#define RTC_TimeStampPin_PC13 ((uint32_t)0x00000000) +#define RTC_TimeStampPin_PI8 ((uint32_t)0x00020000) +#define IS_RTC_TIMESTAMP_PIN(PIN) (((PIN) == RTC_TimeStampPin_PC13) || \ + ((PIN) == RTC_TimeStampPin_PI8)) +/** + * @} + */ + +/** @defgroup RTC_Output_Type_ALARM_OUT + * @{ + */ +#define RTC_OutputType_OpenDrain ((uint32_t)0x00000000) +#define RTC_OutputType_PushPull ((uint32_t)0x00040000) +#define IS_RTC_OUTPUT_TYPE(TYPE) (((TYPE) == RTC_OutputType_OpenDrain) || \ + ((TYPE) == RTC_OutputType_PushPull)) + +/** + * @} + */ + +/** @defgroup RTC_Add_1_Second_Parameter_Definitions + * @{ + */ +#define RTC_ShiftAdd1S_Reset ((uint32_t)0x00000000) +#define RTC_ShiftAdd1S_Set ((uint32_t)0x80000000) +#define IS_RTC_SHIFT_ADD1S(SEL) (((SEL) == RTC_ShiftAdd1S_Reset) || \ + ((SEL) == RTC_ShiftAdd1S_Set)) +/** + * @} + */ + +/** @defgroup RTC_Substract_Fraction_Of_Second_Value + * @{ + */ +#define IS_RTC_SHIFT_SUBFS(FS) ((FS) <= 0x00007FFF) + +/** + * @} + */ + +/** @defgroup RTC_Backup_Registers_Definitions + * @{ + */ + +#define RTC_BKP_DR0 ((uint32_t)0x00000000) +#define RTC_BKP_DR1 ((uint32_t)0x00000001) +#define RTC_BKP_DR2 ((uint32_t)0x00000002) +#define RTC_BKP_DR3 ((uint32_t)0x00000003) +#define RTC_BKP_DR4 ((uint32_t)0x00000004) +#define RTC_BKP_DR5 ((uint32_t)0x00000005) +#define RTC_BKP_DR6 ((uint32_t)0x00000006) +#define RTC_BKP_DR7 ((uint32_t)0x00000007) +#define RTC_BKP_DR8 ((uint32_t)0x00000008) +#define RTC_BKP_DR9 ((uint32_t)0x00000009) +#define RTC_BKP_DR10 ((uint32_t)0x0000000A) +#define RTC_BKP_DR11 ((uint32_t)0x0000000B) +#define RTC_BKP_DR12 ((uint32_t)0x0000000C) +#define RTC_BKP_DR13 ((uint32_t)0x0000000D) +#define RTC_BKP_DR14 ((uint32_t)0x0000000E) +#define RTC_BKP_DR15 ((uint32_t)0x0000000F) +#define RTC_BKP_DR16 ((uint32_t)0x00000010) +#define RTC_BKP_DR17 ((uint32_t)0x00000011) +#define RTC_BKP_DR18 ((uint32_t)0x00000012) +#define RTC_BKP_DR19 ((uint32_t)0x00000013) +#define IS_RTC_BKP(BKP) (((BKP) == RTC_BKP_DR0) || \ + ((BKP) == RTC_BKP_DR1) || \ + ((BKP) == RTC_BKP_DR2) || \ + ((BKP) == RTC_BKP_DR3) || \ + ((BKP) == RTC_BKP_DR4) || \ + ((BKP) == RTC_BKP_DR5) || \ + ((BKP) == RTC_BKP_DR6) || \ + ((BKP) == RTC_BKP_DR7) || \ + ((BKP) == RTC_BKP_DR8) || \ + ((BKP) == RTC_BKP_DR9) || \ + ((BKP) == RTC_BKP_DR10) || \ + ((BKP) == RTC_BKP_DR11) || \ + ((BKP) == RTC_BKP_DR12) || \ + ((BKP) == RTC_BKP_DR13) || \ + ((BKP) == RTC_BKP_DR14) || \ + ((BKP) == RTC_BKP_DR15) || \ + ((BKP) == RTC_BKP_DR16) || \ + ((BKP) == RTC_BKP_DR17) || \ + ((BKP) == RTC_BKP_DR18) || \ + ((BKP) == RTC_BKP_DR19)) +/** + * @} + */ + +/** @defgroup RTC_Input_parameter_format_definitions + * @{ + */ +#define RTC_Format_BIN ((uint32_t)0x000000000) +#define RTC_Format_BCD ((uint32_t)0x000000001) +#define IS_RTC_FORMAT(FORMAT) (((FORMAT) == RTC_Format_BIN) || ((FORMAT) == RTC_Format_BCD)) + +/** + * @} + */ + +/** @defgroup RTC_Flags_Definitions + * @{ + */ +#define RTC_FLAG_RECALPF ((uint32_t)0x00010000) +#define RTC_FLAG_TAMP1F ((uint32_t)0x00002000) +#define RTC_FLAG_TSOVF ((uint32_t)0x00001000) +#define RTC_FLAG_TSF ((uint32_t)0x00000800) +#define RTC_FLAG_WUTF ((uint32_t)0x00000400) +#define RTC_FLAG_ALRBF ((uint32_t)0x00000200) +#define RTC_FLAG_ALRAF ((uint32_t)0x00000100) +#define RTC_FLAG_INITF ((uint32_t)0x00000040) +#define RTC_FLAG_RSF ((uint32_t)0x00000020) +#define RTC_FLAG_INITS ((uint32_t)0x00000010) +#define RTC_FLAG_SHPF ((uint32_t)0x00000008) +#define RTC_FLAG_WUTWF ((uint32_t)0x00000004) +#define RTC_FLAG_ALRBWF ((uint32_t)0x00000002) +#define RTC_FLAG_ALRAWF ((uint32_t)0x00000001) +#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_TSOVF) || ((FLAG) == RTC_FLAG_TSF) || \ + ((FLAG) == RTC_FLAG_WUTF) || ((FLAG) == RTC_FLAG_ALRBF) || \ + ((FLAG) == RTC_FLAG_ALRAF) || ((FLAG) == RTC_FLAG_INITF) || \ + ((FLAG) == RTC_FLAG_RSF) || ((FLAG) == RTC_FLAG_WUTWF) || \ + ((FLAG) == RTC_FLAG_ALRBWF) || ((FLAG) == RTC_FLAG_ALRAWF) || \ + ((FLAG) == RTC_FLAG_TAMP1F) || ((FLAG) == RTC_FLAG_RECALPF) || \ + ((FLAG) == RTC_FLAG_SHPF)) +#define IS_RTC_CLEAR_FLAG(FLAG) (((FLAG) != (uint32_t)RESET) && (((FLAG) & 0xFFFF00DF) == (uint32_t)RESET)) +/** + * @} + */ + +/** @defgroup RTC_Interrupts_Definitions + * @{ + */ +#define RTC_IT_TS ((uint32_t)0x00008000) +#define RTC_IT_WUT ((uint32_t)0x00004000) +#define RTC_IT_ALRB ((uint32_t)0x00002000) +#define RTC_IT_ALRA ((uint32_t)0x00001000) +#define RTC_IT_TAMP ((uint32_t)0x00000004) /* Used only to Enable the Tamper Interrupt */ +#define RTC_IT_TAMP1 ((uint32_t)0x00020000) + +#define IS_RTC_CONFIG_IT(IT) (((IT) != (uint32_t)RESET) && (((IT) & 0xFFFF0FFB) == (uint32_t)RESET)) +#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_TS) || ((IT) == RTC_IT_WUT) || \ + ((IT) == RTC_IT_ALRB) || ((IT) == RTC_IT_ALRA) || \ + ((IT) == RTC_IT_TAMP1)) +#define IS_RTC_CLEAR_IT(IT) (((IT) != (uint32_t)RESET) && (((IT) & 0xFFFD0FFF) == (uint32_t)RESET)) + +/** + * @} + */ + +/** @defgroup RTC_Legacy + * @{ + */ +#define RTC_DigitalCalibConfig RTC_CoarseCalibConfig +#define RTC_DigitalCalibCmd RTC_CoarseCalibCmd + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the RTC configuration to the default reset state *****/ +ErrorStatus RTC_DeInit(void); + +/* Initialization and Configuration functions *********************************/ +ErrorStatus RTC_Init(RTC_InitTypeDef* RTC_InitStruct); +void RTC_StructInit(RTC_InitTypeDef* RTC_InitStruct); +void RTC_WriteProtectionCmd(FunctionalState NewState); +ErrorStatus RTC_EnterInitMode(void); +void RTC_ExitInitMode(void); +ErrorStatus RTC_WaitForSynchro(void); +ErrorStatus RTC_RefClockCmd(FunctionalState NewState); +void RTC_BypassShadowCmd(FunctionalState NewState); + +/* Time and Date configuration functions **************************************/ +ErrorStatus RTC_SetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct); +void RTC_TimeStructInit(RTC_TimeTypeDef* RTC_TimeStruct); +void RTC_GetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct); +uint32_t RTC_GetSubSecond(void); +ErrorStatus RTC_SetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct); +void RTC_DateStructInit(RTC_DateTypeDef* RTC_DateStruct); +void RTC_GetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct); + +/* Alarms (Alarm A and Alarm B) configuration functions **********************/ +void RTC_SetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct); +void RTC_AlarmStructInit(RTC_AlarmTypeDef* RTC_AlarmStruct); +void RTC_GetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct); +ErrorStatus RTC_AlarmCmd(uint32_t RTC_Alarm, FunctionalState NewState); +void RTC_AlarmSubSecondConfig(uint32_t RTC_Alarm, uint32_t RTC_AlarmSubSecondValue, uint32_t RTC_AlarmSubSecondMask); +uint32_t RTC_GetAlarmSubSecond(uint32_t RTC_Alarm); + +/* WakeUp Timer configuration functions ***************************************/ +void RTC_WakeUpClockConfig(uint32_t RTC_WakeUpClock); +void RTC_SetWakeUpCounter(uint32_t RTC_WakeUpCounter); +uint32_t RTC_GetWakeUpCounter(void); +ErrorStatus RTC_WakeUpCmd(FunctionalState NewState); + +/* Daylight Saving configuration functions ************************************/ +void RTC_DayLightSavingConfig(uint32_t RTC_DayLightSaving, uint32_t RTC_StoreOperation); +uint32_t RTC_GetStoreOperation(void); + +/* Output pin Configuration function ******************************************/ +void RTC_OutputConfig(uint32_t RTC_Output, uint32_t RTC_OutputPolarity); + +/* Digital Calibration configuration functions *********************************/ +ErrorStatus RTC_CoarseCalibConfig(uint32_t RTC_CalibSign, uint32_t Value); +ErrorStatus RTC_CoarseCalibCmd(FunctionalState NewState); +void RTC_CalibOutputCmd(FunctionalState NewState); +void RTC_CalibOutputConfig(uint32_t RTC_CalibOutput); +ErrorStatus RTC_SmoothCalibConfig(uint32_t RTC_SmoothCalibPeriod, + uint32_t RTC_SmoothCalibPlusPulses, + uint32_t RTC_SmouthCalibMinusPulsesValue); + +/* TimeStamp configuration functions ******************************************/ +void RTC_TimeStampCmd(uint32_t RTC_TimeStampEdge, FunctionalState NewState); +void RTC_GetTimeStamp(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_StampTimeStruct, + RTC_DateTypeDef* RTC_StampDateStruct); +uint32_t RTC_GetTimeStampSubSecond(void); + +/* Tampers configuration functions ********************************************/ +void RTC_TamperTriggerConfig(uint32_t RTC_Tamper, uint32_t RTC_TamperTrigger); +void RTC_TamperCmd(uint32_t RTC_Tamper, FunctionalState NewState); +void RTC_TamperFilterConfig(uint32_t RTC_TamperFilter); +void RTC_TamperSamplingFreqConfig(uint32_t RTC_TamperSamplingFreq); +void RTC_TamperPinsPrechargeDuration(uint32_t RTC_TamperPrechargeDuration); +void RTC_TimeStampOnTamperDetectionCmd(FunctionalState NewState); +void RTC_TamperPullUpCmd(FunctionalState NewState); + +/* Backup Data Registers configuration functions ******************************/ +void RTC_WriteBackupRegister(uint32_t RTC_BKP_DR, uint32_t Data); +uint32_t RTC_ReadBackupRegister(uint32_t RTC_BKP_DR); + +/* RTC Tamper and TimeStamp Pins Selection and Output Type Config configuration + functions ******************************************************************/ +void RTC_TamperPinSelection(uint32_t RTC_TamperPin); +void RTC_TimeStampPinSelection(uint32_t RTC_TimeStampPin); +void RTC_OutputTypeConfig(uint32_t RTC_OutputType); + +/* RTC_Shift_control_synchonisation_functions *********************************/ +ErrorStatus RTC_SynchroShiftConfig(uint32_t RTC_ShiftAdd1S, uint32_t RTC_ShiftSubFS); + +/* Interrupts and flags management functions **********************************/ +void RTC_ITConfig(uint32_t RTC_IT, FunctionalState NewState); +FlagStatus RTC_GetFlagStatus(uint32_t RTC_FLAG); +void RTC_ClearFlag(uint32_t RTC_FLAG); +ITStatus RTC_GetITStatus(uint32_t RTC_IT); +void RTC_ClearITPendingBit(uint32_t RTC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_RTC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sdio.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sdio.h new file mode 100644 index 000000000..315703d2d --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sdio.h @@ -0,0 +1,530 @@ +/** + ****************************************************************************** + * @file stm32f4xx_sdio.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the SDIO firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_SDIO_H +#define __STM32F4xx_SDIO_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SDIO + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +typedef struct +{ + uint32_t SDIO_ClockEdge; /*!< Specifies the clock transition on which the bit capture is made. + This parameter can be a value of @ref SDIO_Clock_Edge */ + + uint32_t SDIO_ClockBypass; /*!< Specifies whether the SDIO Clock divider bypass is + enabled or disabled. + This parameter can be a value of @ref SDIO_Clock_Bypass */ + + uint32_t SDIO_ClockPowerSave; /*!< Specifies whether SDIO Clock output is enabled or + disabled when the bus is idle. + This parameter can be a value of @ref SDIO_Clock_Power_Save */ + + uint32_t SDIO_BusWide; /*!< Specifies the SDIO bus width. + This parameter can be a value of @ref SDIO_Bus_Wide */ + + uint32_t SDIO_HardwareFlowControl; /*!< Specifies whether the SDIO hardware flow control is enabled or disabled. + This parameter can be a value of @ref SDIO_Hardware_Flow_Control */ + + uint8_t SDIO_ClockDiv; /*!< Specifies the clock frequency of the SDIO controller. + This parameter can be a value between 0x00 and 0xFF. */ + +} SDIO_InitTypeDef; + +typedef struct +{ + uint32_t SDIO_Argument; /*!< Specifies the SDIO command argument which is sent + to a card as part of a command message. If a command + contains an argument, it must be loaded into this register + before writing the command to the command register */ + + uint32_t SDIO_CmdIndex; /*!< Specifies the SDIO command index. It must be lower than 0x40. */ + + uint32_t SDIO_Response; /*!< Specifies the SDIO response type. + This parameter can be a value of @ref SDIO_Response_Type */ + + uint32_t SDIO_Wait; /*!< Specifies whether SDIO wait-for-interrupt request is enabled or disabled. + This parameter can be a value of @ref SDIO_Wait_Interrupt_State */ + + uint32_t SDIO_CPSM; /*!< Specifies whether SDIO Command path state machine (CPSM) + is enabled or disabled. + This parameter can be a value of @ref SDIO_CPSM_State */ +} SDIO_CmdInitTypeDef; + +typedef struct +{ + uint32_t SDIO_DataTimeOut; /*!< Specifies the data timeout period in card bus clock periods. */ + + uint32_t SDIO_DataLength; /*!< Specifies the number of data bytes to be transferred. */ + + uint32_t SDIO_DataBlockSize; /*!< Specifies the data block size for block transfer. + This parameter can be a value of @ref SDIO_Data_Block_Size */ + + uint32_t SDIO_TransferDir; /*!< Specifies the data transfer direction, whether the transfer + is a read or write. + This parameter can be a value of @ref SDIO_Transfer_Direction */ + + uint32_t SDIO_TransferMode; /*!< Specifies whether data transfer is in stream or block mode. + This parameter can be a value of @ref SDIO_Transfer_Type */ + + uint32_t SDIO_DPSM; /*!< Specifies whether SDIO Data path state machine (DPSM) + is enabled or disabled. + This parameter can be a value of @ref SDIO_DPSM_State */ +} SDIO_DataInitTypeDef; + + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup SDIO_Exported_Constants + * @{ + */ + +/** @defgroup SDIO_Clock_Edge + * @{ + */ + +#define SDIO_ClockEdge_Rising ((uint32_t)0x00000000) +#define SDIO_ClockEdge_Falling ((uint32_t)0x00002000) +#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_ClockEdge_Rising) || \ + ((EDGE) == SDIO_ClockEdge_Falling)) +/** + * @} + */ + +/** @defgroup SDIO_Clock_Bypass + * @{ + */ + +#define SDIO_ClockBypass_Disable ((uint32_t)0x00000000) +#define SDIO_ClockBypass_Enable ((uint32_t)0x00000400) +#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_ClockBypass_Disable) || \ + ((BYPASS) == SDIO_ClockBypass_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Clock_Power_Save + * @{ + */ + +#define SDIO_ClockPowerSave_Disable ((uint32_t)0x00000000) +#define SDIO_ClockPowerSave_Enable ((uint32_t)0x00000200) +#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_ClockPowerSave_Disable) || \ + ((SAVE) == SDIO_ClockPowerSave_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Bus_Wide + * @{ + */ + +#define SDIO_BusWide_1b ((uint32_t)0x00000000) +#define SDIO_BusWide_4b ((uint32_t)0x00000800) +#define SDIO_BusWide_8b ((uint32_t)0x00001000) +#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BusWide_1b) || ((WIDE) == SDIO_BusWide_4b) || \ + ((WIDE) == SDIO_BusWide_8b)) + +/** + * @} + */ + +/** @defgroup SDIO_Hardware_Flow_Control + * @{ + */ + +#define SDIO_HardwareFlowControl_Disable ((uint32_t)0x00000000) +#define SDIO_HardwareFlowControl_Enable ((uint32_t)0x00004000) +#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HardwareFlowControl_Disable) || \ + ((CONTROL) == SDIO_HardwareFlowControl_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Power_State + * @{ + */ + +#define SDIO_PowerState_OFF ((uint32_t)0x00000000) +#define SDIO_PowerState_ON ((uint32_t)0x00000003) +#define IS_SDIO_POWER_STATE(STATE) (((STATE) == SDIO_PowerState_OFF) || ((STATE) == SDIO_PowerState_ON)) +/** + * @} + */ + + +/** @defgroup SDIO_Interrupt_sources + * @{ + */ + +#define SDIO_IT_CCRCFAIL ((uint32_t)0x00000001) +#define SDIO_IT_DCRCFAIL ((uint32_t)0x00000002) +#define SDIO_IT_CTIMEOUT ((uint32_t)0x00000004) +#define SDIO_IT_DTIMEOUT ((uint32_t)0x00000008) +#define SDIO_IT_TXUNDERR ((uint32_t)0x00000010) +#define SDIO_IT_RXOVERR ((uint32_t)0x00000020) +#define SDIO_IT_CMDREND ((uint32_t)0x00000040) +#define SDIO_IT_CMDSENT ((uint32_t)0x00000080) +#define SDIO_IT_DATAEND ((uint32_t)0x00000100) +#define SDIO_IT_STBITERR ((uint32_t)0x00000200) +#define SDIO_IT_DBCKEND ((uint32_t)0x00000400) +#define SDIO_IT_CMDACT ((uint32_t)0x00000800) +#define SDIO_IT_TXACT ((uint32_t)0x00001000) +#define SDIO_IT_RXACT ((uint32_t)0x00002000) +#define SDIO_IT_TXFIFOHE ((uint32_t)0x00004000) +#define SDIO_IT_RXFIFOHF ((uint32_t)0x00008000) +#define SDIO_IT_TXFIFOF ((uint32_t)0x00010000) +#define SDIO_IT_RXFIFOF ((uint32_t)0x00020000) +#define SDIO_IT_TXFIFOE ((uint32_t)0x00040000) +#define SDIO_IT_RXFIFOE ((uint32_t)0x00080000) +#define SDIO_IT_TXDAVL ((uint32_t)0x00100000) +#define SDIO_IT_RXDAVL ((uint32_t)0x00200000) +#define SDIO_IT_SDIOIT ((uint32_t)0x00400000) +#define SDIO_IT_CEATAEND ((uint32_t)0x00800000) +#define IS_SDIO_IT(IT) ((((IT) & (uint32_t)0xFF000000) == 0x00) && ((IT) != (uint32_t)0x00)) +/** + * @} + */ + +/** @defgroup SDIO_Command_Index + * @{ + */ + +#define IS_SDIO_CMD_INDEX(INDEX) ((INDEX) < 0x40) +/** + * @} + */ + +/** @defgroup SDIO_Response_Type + * @{ + */ + +#define SDIO_Response_No ((uint32_t)0x00000000) +#define SDIO_Response_Short ((uint32_t)0x00000040) +#define SDIO_Response_Long ((uint32_t)0x000000C0) +#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_Response_No) || \ + ((RESPONSE) == SDIO_Response_Short) || \ + ((RESPONSE) == SDIO_Response_Long)) +/** + * @} + */ + +/** @defgroup SDIO_Wait_Interrupt_State + * @{ + */ + +#define SDIO_Wait_No ((uint32_t)0x00000000) /*!< SDIO No Wait, TimeOut is enabled */ +#define SDIO_Wait_IT ((uint32_t)0x00000100) /*!< SDIO Wait Interrupt Request */ +#define SDIO_Wait_Pend ((uint32_t)0x00000200) /*!< SDIO Wait End of transfer */ +#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_Wait_No) || ((WAIT) == SDIO_Wait_IT) || \ + ((WAIT) == SDIO_Wait_Pend)) +/** + * @} + */ + +/** @defgroup SDIO_CPSM_State + * @{ + */ + +#define SDIO_CPSM_Disable ((uint32_t)0x00000000) +#define SDIO_CPSM_Enable ((uint32_t)0x00000400) +#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_Enable) || ((CPSM) == SDIO_CPSM_Disable)) +/** + * @} + */ + +/** @defgroup SDIO_Response_Registers + * @{ + */ + +#define SDIO_RESP1 ((uint32_t)0x00000000) +#define SDIO_RESP2 ((uint32_t)0x00000004) +#define SDIO_RESP3 ((uint32_t)0x00000008) +#define SDIO_RESP4 ((uint32_t)0x0000000C) +#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || ((RESP) == SDIO_RESP2) || \ + ((RESP) == SDIO_RESP3) || ((RESP) == SDIO_RESP4)) +/** + * @} + */ + +/** @defgroup SDIO_Data_Length + * @{ + */ + +#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFF) +/** + * @} + */ + +/** @defgroup SDIO_Data_Block_Size + * @{ + */ + +#define SDIO_DataBlockSize_1b ((uint32_t)0x00000000) +#define SDIO_DataBlockSize_2b ((uint32_t)0x00000010) +#define SDIO_DataBlockSize_4b ((uint32_t)0x00000020) +#define SDIO_DataBlockSize_8b ((uint32_t)0x00000030) +#define SDIO_DataBlockSize_16b ((uint32_t)0x00000040) +#define SDIO_DataBlockSize_32b ((uint32_t)0x00000050) +#define SDIO_DataBlockSize_64b ((uint32_t)0x00000060) +#define SDIO_DataBlockSize_128b ((uint32_t)0x00000070) +#define SDIO_DataBlockSize_256b ((uint32_t)0x00000080) +#define SDIO_DataBlockSize_512b ((uint32_t)0x00000090) +#define SDIO_DataBlockSize_1024b ((uint32_t)0x000000A0) +#define SDIO_DataBlockSize_2048b ((uint32_t)0x000000B0) +#define SDIO_DataBlockSize_4096b ((uint32_t)0x000000C0) +#define SDIO_DataBlockSize_8192b ((uint32_t)0x000000D0) +#define SDIO_DataBlockSize_16384b ((uint32_t)0x000000E0) +#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DataBlockSize_1b) || \ + ((SIZE) == SDIO_DataBlockSize_2b) || \ + ((SIZE) == SDIO_DataBlockSize_4b) || \ + ((SIZE) == SDIO_DataBlockSize_8b) || \ + ((SIZE) == SDIO_DataBlockSize_16b) || \ + ((SIZE) == SDIO_DataBlockSize_32b) || \ + ((SIZE) == SDIO_DataBlockSize_64b) || \ + ((SIZE) == SDIO_DataBlockSize_128b) || \ + ((SIZE) == SDIO_DataBlockSize_256b) || \ + ((SIZE) == SDIO_DataBlockSize_512b) || \ + ((SIZE) == SDIO_DataBlockSize_1024b) || \ + ((SIZE) == SDIO_DataBlockSize_2048b) || \ + ((SIZE) == SDIO_DataBlockSize_4096b) || \ + ((SIZE) == SDIO_DataBlockSize_8192b) || \ + ((SIZE) == SDIO_DataBlockSize_16384b)) +/** + * @} + */ + +/** @defgroup SDIO_Transfer_Direction + * @{ + */ + +#define SDIO_TransferDir_ToCard ((uint32_t)0x00000000) +#define SDIO_TransferDir_ToSDIO ((uint32_t)0x00000002) +#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TransferDir_ToCard) || \ + ((DIR) == SDIO_TransferDir_ToSDIO)) +/** + * @} + */ + +/** @defgroup SDIO_Transfer_Type + * @{ + */ + +#define SDIO_TransferMode_Block ((uint32_t)0x00000000) +#define SDIO_TransferMode_Stream ((uint32_t)0x00000004) +#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TransferMode_Stream) || \ + ((MODE) == SDIO_TransferMode_Block)) +/** + * @} + */ + +/** @defgroup SDIO_DPSM_State + * @{ + */ + +#define SDIO_DPSM_Disable ((uint32_t)0x00000000) +#define SDIO_DPSM_Enable ((uint32_t)0x00000001) +#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_Enable) || ((DPSM) == SDIO_DPSM_Disable)) +/** + * @} + */ + +/** @defgroup SDIO_Flags + * @{ + */ + +#define SDIO_FLAG_CCRCFAIL ((uint32_t)0x00000001) +#define SDIO_FLAG_DCRCFAIL ((uint32_t)0x00000002) +#define SDIO_FLAG_CTIMEOUT ((uint32_t)0x00000004) +#define SDIO_FLAG_DTIMEOUT ((uint32_t)0x00000008) +#define SDIO_FLAG_TXUNDERR ((uint32_t)0x00000010) +#define SDIO_FLAG_RXOVERR ((uint32_t)0x00000020) +#define SDIO_FLAG_CMDREND ((uint32_t)0x00000040) +#define SDIO_FLAG_CMDSENT ((uint32_t)0x00000080) +#define SDIO_FLAG_DATAEND ((uint32_t)0x00000100) +#define SDIO_FLAG_STBITERR ((uint32_t)0x00000200) +#define SDIO_FLAG_DBCKEND ((uint32_t)0x00000400) +#define SDIO_FLAG_CMDACT ((uint32_t)0x00000800) +#define SDIO_FLAG_TXACT ((uint32_t)0x00001000) +#define SDIO_FLAG_RXACT ((uint32_t)0x00002000) +#define SDIO_FLAG_TXFIFOHE ((uint32_t)0x00004000) +#define SDIO_FLAG_RXFIFOHF ((uint32_t)0x00008000) +#define SDIO_FLAG_TXFIFOF ((uint32_t)0x00010000) +#define SDIO_FLAG_RXFIFOF ((uint32_t)0x00020000) +#define SDIO_FLAG_TXFIFOE ((uint32_t)0x00040000) +#define SDIO_FLAG_RXFIFOE ((uint32_t)0x00080000) +#define SDIO_FLAG_TXDAVL ((uint32_t)0x00100000) +#define SDIO_FLAG_RXDAVL ((uint32_t)0x00200000) +#define SDIO_FLAG_SDIOIT ((uint32_t)0x00400000) +#define SDIO_FLAG_CEATAEND ((uint32_t)0x00800000) +#define IS_SDIO_FLAG(FLAG) (((FLAG) == SDIO_FLAG_CCRCFAIL) || \ + ((FLAG) == SDIO_FLAG_DCRCFAIL) || \ + ((FLAG) == SDIO_FLAG_CTIMEOUT) || \ + ((FLAG) == SDIO_FLAG_DTIMEOUT) || \ + ((FLAG) == SDIO_FLAG_TXUNDERR) || \ + ((FLAG) == SDIO_FLAG_RXOVERR) || \ + ((FLAG) == SDIO_FLAG_CMDREND) || \ + ((FLAG) == SDIO_FLAG_CMDSENT) || \ + ((FLAG) == SDIO_FLAG_DATAEND) || \ + ((FLAG) == SDIO_FLAG_STBITERR) || \ + ((FLAG) == SDIO_FLAG_DBCKEND) || \ + ((FLAG) == SDIO_FLAG_CMDACT) || \ + ((FLAG) == SDIO_FLAG_TXACT) || \ + ((FLAG) == SDIO_FLAG_RXACT) || \ + ((FLAG) == SDIO_FLAG_TXFIFOHE) || \ + ((FLAG) == SDIO_FLAG_RXFIFOHF) || \ + ((FLAG) == SDIO_FLAG_TXFIFOF) || \ + ((FLAG) == SDIO_FLAG_RXFIFOF) || \ + ((FLAG) == SDIO_FLAG_TXFIFOE) || \ + ((FLAG) == SDIO_FLAG_RXFIFOE) || \ + ((FLAG) == SDIO_FLAG_TXDAVL) || \ + ((FLAG) == SDIO_FLAG_RXDAVL) || \ + ((FLAG) == SDIO_FLAG_SDIOIT) || \ + ((FLAG) == SDIO_FLAG_CEATAEND)) + +#define IS_SDIO_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFF3FF800) == 0x00) && ((FLAG) != (uint32_t)0x00)) + +#define IS_SDIO_GET_IT(IT) (((IT) == SDIO_IT_CCRCFAIL) || \ + ((IT) == SDIO_IT_DCRCFAIL) || \ + ((IT) == SDIO_IT_CTIMEOUT) || \ + ((IT) == SDIO_IT_DTIMEOUT) || \ + ((IT) == SDIO_IT_TXUNDERR) || \ + ((IT) == SDIO_IT_RXOVERR) || \ + ((IT) == SDIO_IT_CMDREND) || \ + ((IT) == SDIO_IT_CMDSENT) || \ + ((IT) == SDIO_IT_DATAEND) || \ + ((IT) == SDIO_IT_STBITERR) || \ + ((IT) == SDIO_IT_DBCKEND) || \ + ((IT) == SDIO_IT_CMDACT) || \ + ((IT) == SDIO_IT_TXACT) || \ + ((IT) == SDIO_IT_RXACT) || \ + ((IT) == SDIO_IT_TXFIFOHE) || \ + ((IT) == SDIO_IT_RXFIFOHF) || \ + ((IT) == SDIO_IT_TXFIFOF) || \ + ((IT) == SDIO_IT_RXFIFOF) || \ + ((IT) == SDIO_IT_TXFIFOE) || \ + ((IT) == SDIO_IT_RXFIFOE) || \ + ((IT) == SDIO_IT_TXDAVL) || \ + ((IT) == SDIO_IT_RXDAVL) || \ + ((IT) == SDIO_IT_SDIOIT) || \ + ((IT) == SDIO_IT_CEATAEND)) + +#define IS_SDIO_CLEAR_IT(IT) ((((IT) & (uint32_t)0xFF3FF800) == 0x00) && ((IT) != (uint32_t)0x00)) + +/** + * @} + */ + +/** @defgroup SDIO_Read_Wait_Mode + * @{ + */ + +#define SDIO_ReadWaitMode_CLK ((uint32_t)0x00000000) +#define SDIO_ReadWaitMode_DATA2 ((uint32_t)0x00000001) +#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_ReadWaitMode_CLK) || \ + ((MODE) == SDIO_ReadWaitMode_DATA2)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/* Function used to set the SDIO configuration to the default reset state ****/ +void SDIO_DeInit(void); + +/* Initialization and Configuration functions *********************************/ +void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct); +void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct); +void SDIO_ClockCmd(FunctionalState NewState); +void SDIO_SetPowerState(uint32_t SDIO_PowerState); +uint32_t SDIO_GetPowerState(void); + +/* Command path state machine (CPSM) management functions *********************/ +void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct); +void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct); +uint8_t SDIO_GetCommandResponse(void); +uint32_t SDIO_GetResponse(uint32_t SDIO_RESP); + +/* Data path state machine (DPSM) management functions ************************/ +void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct); +void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct); +uint32_t SDIO_GetDataCounter(void); +uint32_t SDIO_ReadData(void); +void SDIO_WriteData(uint32_t Data); +uint32_t SDIO_GetFIFOCount(void); + +/* SDIO IO Cards mode management functions ************************************/ +void SDIO_StartSDIOReadWait(FunctionalState NewState); +void SDIO_StopSDIOReadWait(FunctionalState NewState); +void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode); +void SDIO_SetSDIOOperation(FunctionalState NewState); +void SDIO_SendSDIOSuspendCmd(FunctionalState NewState); + +/* CE-ATA mode management functions *******************************************/ +void SDIO_CommandCompletionCmd(FunctionalState NewState); +void SDIO_CEATAITCmd(FunctionalState NewState); +void SDIO_SendCEATACmd(FunctionalState NewState); + +/* DMA transfers management functions *****************************************/ +void SDIO_DMACmd(FunctionalState NewState); + +/* Interrupts and flags management functions **********************************/ +void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState); +FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG); +void SDIO_ClearFlag(uint32_t SDIO_FLAG); +ITStatus SDIO_GetITStatus(uint32_t SDIO_IT); +void SDIO_ClearITPendingBit(uint32_t SDIO_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_SDIO_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spi.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spi.h new file mode 100644 index 000000000..3e0d79eb2 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spi.h @@ -0,0 +1,537 @@ +/** + ****************************************************************************** + * @file stm32f4xx_spi.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the SPI + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_SPI_H +#define __STM32F4xx_SPI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SPI + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief SPI Init structure definition + */ + +typedef struct +{ + uint16_t SPI_Direction; /*!< Specifies the SPI unidirectional or bidirectional data mode. + This parameter can be a value of @ref SPI_data_direction */ + + uint16_t SPI_Mode; /*!< Specifies the SPI operating mode. + This parameter can be a value of @ref SPI_mode */ + + uint16_t SPI_DataSize; /*!< Specifies the SPI data size. + This parameter can be a value of @ref SPI_data_size */ + + uint16_t SPI_CPOL; /*!< Specifies the serial clock steady state. + This parameter can be a value of @ref SPI_Clock_Polarity */ + + uint16_t SPI_CPHA; /*!< Specifies the clock active edge for the bit capture. + This parameter can be a value of @ref SPI_Clock_Phase */ + + uint16_t SPI_NSS; /*!< Specifies whether the NSS signal is managed by + hardware (NSS pin) or by software using the SSI bit. + This parameter can be a value of @ref SPI_Slave_Select_management */ + + uint16_t SPI_BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be + used to configure the transmit and receive SCK clock. + This parameter can be a value of @ref SPI_BaudRate_Prescaler + @note The communication clock is derived from the master + clock. The slave clock does not need to be set. */ + + uint16_t SPI_FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. + This parameter can be a value of @ref SPI_MSB_LSB_transmission */ + + uint16_t SPI_CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. */ +}SPI_InitTypeDef; + +/** + * @brief I2S Init structure definition + */ + +typedef struct +{ + + uint16_t I2S_Mode; /*!< Specifies the I2S operating mode. + This parameter can be a value of @ref I2S_Mode */ + + uint16_t I2S_Standard; /*!< Specifies the standard used for the I2S communication. + This parameter can be a value of @ref I2S_Standard */ + + uint16_t I2S_DataFormat; /*!< Specifies the data format for the I2S communication. + This parameter can be a value of @ref I2S_Data_Format */ + + uint16_t I2S_MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. + This parameter can be a value of @ref I2S_MCLK_Output */ + + uint32_t I2S_AudioFreq; /*!< Specifies the frequency selected for the I2S communication. + This parameter can be a value of @ref I2S_Audio_Frequency */ + + uint16_t I2S_CPOL; /*!< Specifies the idle state of the I2S clock. + This parameter can be a value of @ref I2S_Clock_Polarity */ +}I2S_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup SPI_Exported_Constants + * @{ + */ + +#define IS_SPI_ALL_PERIPH(PERIPH) (((PERIPH) == SPI1) || \ + ((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3)) + +#define IS_SPI_ALL_PERIPH_EXT(PERIPH) (((PERIPH) == SPI1) || \ + ((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3) || \ + ((PERIPH) == I2S2ext) || \ + ((PERIPH) == I2S3ext)) + +#define IS_SPI_23_PERIPH(PERIPH) (((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3)) + +#define IS_SPI_23_PERIPH_EXT(PERIPH) (((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3) || \ + ((PERIPH) == I2S2ext) || \ + ((PERIPH) == I2S3ext)) + +#define IS_I2S_EXT_PERIPH(PERIPH) (((PERIPH) == I2S2ext) || \ + ((PERIPH) == I2S3ext)) + + +/** @defgroup SPI_data_direction + * @{ + */ + +#define SPI_Direction_2Lines_FullDuplex ((uint16_t)0x0000) +#define SPI_Direction_2Lines_RxOnly ((uint16_t)0x0400) +#define SPI_Direction_1Line_Rx ((uint16_t)0x8000) +#define SPI_Direction_1Line_Tx ((uint16_t)0xC000) +#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \ + ((MODE) == SPI_Direction_2Lines_RxOnly) || \ + ((MODE) == SPI_Direction_1Line_Rx) || \ + ((MODE) == SPI_Direction_1Line_Tx)) +/** + * @} + */ + +/** @defgroup SPI_mode + * @{ + */ + +#define SPI_Mode_Master ((uint16_t)0x0104) +#define SPI_Mode_Slave ((uint16_t)0x0000) +#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \ + ((MODE) == SPI_Mode_Slave)) +/** + * @} + */ + +/** @defgroup SPI_data_size + * @{ + */ + +#define SPI_DataSize_16b ((uint16_t)0x0800) +#define SPI_DataSize_8b ((uint16_t)0x0000) +#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \ + ((DATASIZE) == SPI_DataSize_8b)) +/** + * @} + */ + +/** @defgroup SPI_Clock_Polarity + * @{ + */ + +#define SPI_CPOL_Low ((uint16_t)0x0000) +#define SPI_CPOL_High ((uint16_t)0x0002) +#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \ + ((CPOL) == SPI_CPOL_High)) +/** + * @} + */ + +/** @defgroup SPI_Clock_Phase + * @{ + */ + +#define SPI_CPHA_1Edge ((uint16_t)0x0000) +#define SPI_CPHA_2Edge ((uint16_t)0x0001) +#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \ + ((CPHA) == SPI_CPHA_2Edge)) +/** + * @} + */ + +/** @defgroup SPI_Slave_Select_management + * @{ + */ + +#define SPI_NSS_Soft ((uint16_t)0x0200) +#define SPI_NSS_Hard ((uint16_t)0x0000) +#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \ + ((NSS) == SPI_NSS_Hard)) +/** + * @} + */ + +/** @defgroup SPI_BaudRate_Prescaler + * @{ + */ + +#define SPI_BaudRatePrescaler_2 ((uint16_t)0x0000) +#define SPI_BaudRatePrescaler_4 ((uint16_t)0x0008) +#define SPI_BaudRatePrescaler_8 ((uint16_t)0x0010) +#define SPI_BaudRatePrescaler_16 ((uint16_t)0x0018) +#define SPI_BaudRatePrescaler_32 ((uint16_t)0x0020) +#define SPI_BaudRatePrescaler_64 ((uint16_t)0x0028) +#define SPI_BaudRatePrescaler_128 ((uint16_t)0x0030) +#define SPI_BaudRatePrescaler_256 ((uint16_t)0x0038) +#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_4) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_8) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_16) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_32) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_64) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_128) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_256)) +/** + * @} + */ + +/** @defgroup SPI_MSB_LSB_transmission + * @{ + */ + +#define SPI_FirstBit_MSB ((uint16_t)0x0000) +#define SPI_FirstBit_LSB ((uint16_t)0x0080) +#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \ + ((BIT) == SPI_FirstBit_LSB)) +/** + * @} + */ + +/** @defgroup SPI_I2S_Mode + * @{ + */ + +#define I2S_Mode_SlaveTx ((uint16_t)0x0000) +#define I2S_Mode_SlaveRx ((uint16_t)0x0100) +#define I2S_Mode_MasterTx ((uint16_t)0x0200) +#define I2S_Mode_MasterRx ((uint16_t)0x0300) +#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \ + ((MODE) == I2S_Mode_SlaveRx) || \ + ((MODE) == I2S_Mode_MasterTx)|| \ + ((MODE) == I2S_Mode_MasterRx)) +/** + * @} + */ + + +/** @defgroup SPI_I2S_Standard + * @{ + */ + +#define I2S_Standard_Phillips ((uint16_t)0x0000) +#define I2S_Standard_MSB ((uint16_t)0x0010) +#define I2S_Standard_LSB ((uint16_t)0x0020) +#define I2S_Standard_PCMShort ((uint16_t)0x0030) +#define I2S_Standard_PCMLong ((uint16_t)0x00B0) +#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \ + ((STANDARD) == I2S_Standard_MSB) || \ + ((STANDARD) == I2S_Standard_LSB) || \ + ((STANDARD) == I2S_Standard_PCMShort) || \ + ((STANDARD) == I2S_Standard_PCMLong)) +/** + * @} + */ + +/** @defgroup SPI_I2S_Data_Format + * @{ + */ + +#define I2S_DataFormat_16b ((uint16_t)0x0000) +#define I2S_DataFormat_16bextended ((uint16_t)0x0001) +#define I2S_DataFormat_24b ((uint16_t)0x0003) +#define I2S_DataFormat_32b ((uint16_t)0x0005) +#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \ + ((FORMAT) == I2S_DataFormat_16bextended) || \ + ((FORMAT) == I2S_DataFormat_24b) || \ + ((FORMAT) == I2S_DataFormat_32b)) +/** + * @} + */ + +/** @defgroup SPI_I2S_MCLK_Output + * @{ + */ + +#define I2S_MCLKOutput_Enable ((uint16_t)0x0200) +#define I2S_MCLKOutput_Disable ((uint16_t)0x0000) +#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \ + ((OUTPUT) == I2S_MCLKOutput_Disable)) +/** + * @} + */ + +/** @defgroup SPI_I2S_Audio_Frequency + * @{ + */ + +#define I2S_AudioFreq_192k ((uint32_t)192000) +#define I2S_AudioFreq_96k ((uint32_t)96000) +#define I2S_AudioFreq_48k ((uint32_t)48000) +#define I2S_AudioFreq_44k ((uint32_t)44100) +#define I2S_AudioFreq_32k ((uint32_t)32000) +#define I2S_AudioFreq_22k ((uint32_t)22050) +#define I2S_AudioFreq_16k ((uint32_t)16000) +#define I2S_AudioFreq_11k ((uint32_t)11025) +#define I2S_AudioFreq_8k ((uint32_t)8000) +#define I2S_AudioFreq_Default ((uint32_t)2) + +#define IS_I2S_AUDIO_FREQ(FREQ) ((((FREQ) >= I2S_AudioFreq_8k) && \ + ((FREQ) <= I2S_AudioFreq_192k)) || \ + ((FREQ) == I2S_AudioFreq_Default)) +/** + * @} + */ + +/** @defgroup SPI_I2S_Clock_Polarity + * @{ + */ + +#define I2S_CPOL_Low ((uint16_t)0x0000) +#define I2S_CPOL_High ((uint16_t)0x0008) +#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \ + ((CPOL) == I2S_CPOL_High)) +/** + * @} + */ + +/** @defgroup SPI_I2S_DMA_transfer_requests + * @{ + */ + +#define SPI_I2S_DMAReq_Tx ((uint16_t)0x0002) +#define SPI_I2S_DMAReq_Rx ((uint16_t)0x0001) +#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFFFC) == 0x00) && ((DMAREQ) != 0x00)) +/** + * @} + */ + +/** @defgroup SPI_NSS_internal_software_management + * @{ + */ + +#define SPI_NSSInternalSoft_Set ((uint16_t)0x0100) +#define SPI_NSSInternalSoft_Reset ((uint16_t)0xFEFF) +#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \ + ((INTERNAL) == SPI_NSSInternalSoft_Reset)) +/** + * @} + */ + +/** @defgroup SPI_CRC_Transmit_Receive + * @{ + */ + +#define SPI_CRC_Tx ((uint8_t)0x00) +#define SPI_CRC_Rx ((uint8_t)0x01) +#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx)) +/** + * @} + */ + +/** @defgroup SPI_direction_transmit_receive + * @{ + */ + +#define SPI_Direction_Rx ((uint16_t)0xBFFF) +#define SPI_Direction_Tx ((uint16_t)0x4000) +#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \ + ((DIRECTION) == SPI_Direction_Tx)) +/** + * @} + */ + +/** @defgroup SPI_I2S_interrupts_definition + * @{ + */ + +#define SPI_I2S_IT_TXE ((uint8_t)0x71) +#define SPI_I2S_IT_RXNE ((uint8_t)0x60) +#define SPI_I2S_IT_ERR ((uint8_t)0x50) +#define I2S_IT_UDR ((uint8_t)0x53) +#define SPI_I2S_IT_TIFRFE ((uint8_t)0x58) + +#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \ + ((IT) == SPI_I2S_IT_RXNE) || \ + ((IT) == SPI_I2S_IT_ERR)) + +#define SPI_I2S_IT_OVR ((uint8_t)0x56) +#define SPI_IT_MODF ((uint8_t)0x55) +#define SPI_IT_CRCERR ((uint8_t)0x54) + +#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_IT_CRCERR)) + +#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE)|| ((IT) == SPI_I2S_IT_TXE) || \ + ((IT) == SPI_IT_CRCERR) || ((IT) == SPI_IT_MODF) || \ + ((IT) == SPI_I2S_IT_OVR) || ((IT) == I2S_IT_UDR) ||\ + ((IT) == SPI_I2S_IT_TIFRFE)) +/** + * @} + */ + +/** @defgroup SPI_I2S_flags_definition + * @{ + */ + +#define SPI_I2S_FLAG_RXNE ((uint16_t)0x0001) +#define SPI_I2S_FLAG_TXE ((uint16_t)0x0002) +#define I2S_FLAG_CHSIDE ((uint16_t)0x0004) +#define I2S_FLAG_UDR ((uint16_t)0x0008) +#define SPI_FLAG_CRCERR ((uint16_t)0x0010) +#define SPI_FLAG_MODF ((uint16_t)0x0020) +#define SPI_I2S_FLAG_OVR ((uint16_t)0x0040) +#define SPI_I2S_FLAG_BSY ((uint16_t)0x0080) +#define SPI_I2S_FLAG_TIFRFE ((uint16_t)0x0100) + +#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR)) +#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \ + ((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \ + ((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \ + ((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE)|| \ + ((FLAG) == SPI_I2S_FLAG_TIFRFE)) +/** + * @} + */ + +/** @defgroup SPI_CRC_polynomial + * @{ + */ + +#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1) +/** + * @} + */ + +/** @defgroup SPI_I2S_Legacy + * @{ + */ + +#define SPI_DMAReq_Tx SPI_I2S_DMAReq_Tx +#define SPI_DMAReq_Rx SPI_I2S_DMAReq_Rx +#define SPI_IT_TXE SPI_I2S_IT_TXE +#define SPI_IT_RXNE SPI_I2S_IT_RXNE +#define SPI_IT_ERR SPI_I2S_IT_ERR +#define SPI_IT_OVR SPI_I2S_IT_OVR +#define SPI_FLAG_RXNE SPI_I2S_FLAG_RXNE +#define SPI_FLAG_TXE SPI_I2S_FLAG_TXE +#define SPI_FLAG_OVR SPI_I2S_FLAG_OVR +#define SPI_FLAG_BSY SPI_I2S_FLAG_BSY +#define SPI_DeInit SPI_I2S_DeInit +#define SPI_ITConfig SPI_I2S_ITConfig +#define SPI_DMACmd SPI_I2S_DMACmd +#define SPI_SendData SPI_I2S_SendData +#define SPI_ReceiveData SPI_I2S_ReceiveData +#define SPI_GetFlagStatus SPI_I2S_GetFlagStatus +#define SPI_ClearFlag SPI_I2S_ClearFlag +#define SPI_GetITStatus SPI_I2S_GetITStatus +#define SPI_ClearITPendingBit SPI_I2S_ClearITPendingBit +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the SPI configuration to the default reset state *****/ +void SPI_I2S_DeInit(SPI_TypeDef* SPIx); + +/* Initialization and Configuration functions *********************************/ +void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct); +void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct); +void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct); +void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct); +void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize); +void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction); +void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft); +void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_TIModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState); + +void I2S_FullDuplexConfig(SPI_TypeDef* I2Sxext, I2S_InitTypeDef* I2S_InitStruct); + +/* Data transfers functions ***************************************************/ +void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data); +uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx); + +/* Hardware CRC Calculation functions *****************************************/ +void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_TransmitCRC(SPI_TypeDef* SPIx); +uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC); +uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx); + +/* DMA transfers management functions *****************************************/ +void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState); + +/* Interrupts and flags management functions **********************************/ +void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState); +FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); +void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); +ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); +void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_SPI_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_syscfg.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_syscfg.h new file mode 100644 index 000000000..e8505e7a9 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_syscfg.h @@ -0,0 +1,173 @@ +/** + ****************************************************************************** + * @file stm32f4xx_syscfg.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the SYSCFG firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_SYSCFG_H +#define __STM32F4xx_SYSCFG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SYSCFG + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup SYSCFG_Exported_Constants + * @{ + */ + +/** @defgroup SYSCFG_EXTI_Port_Sources + * @{ + */ +#define EXTI_PortSourceGPIOA ((uint8_t)0x00) +#define EXTI_PortSourceGPIOB ((uint8_t)0x01) +#define EXTI_PortSourceGPIOC ((uint8_t)0x02) +#define EXTI_PortSourceGPIOD ((uint8_t)0x03) +#define EXTI_PortSourceGPIOE ((uint8_t)0x04) +#define EXTI_PortSourceGPIOF ((uint8_t)0x05) +#define EXTI_PortSourceGPIOG ((uint8_t)0x06) +#define EXTI_PortSourceGPIOH ((uint8_t)0x07) +#define EXTI_PortSourceGPIOI ((uint8_t)0x08) + +#define IS_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == EXTI_PortSourceGPIOA) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOB) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOC) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOD) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOE) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOF) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOG) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOH) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOI)) +/** + * @} + */ + + +/** @defgroup SYSCFG_EXTI_Pin_Sources + * @{ + */ +#define EXTI_PinSource0 ((uint8_t)0x00) +#define EXTI_PinSource1 ((uint8_t)0x01) +#define EXTI_PinSource2 ((uint8_t)0x02) +#define EXTI_PinSource3 ((uint8_t)0x03) +#define EXTI_PinSource4 ((uint8_t)0x04) +#define EXTI_PinSource5 ((uint8_t)0x05) +#define EXTI_PinSource6 ((uint8_t)0x06) +#define EXTI_PinSource7 ((uint8_t)0x07) +#define EXTI_PinSource8 ((uint8_t)0x08) +#define EXTI_PinSource9 ((uint8_t)0x09) +#define EXTI_PinSource10 ((uint8_t)0x0A) +#define EXTI_PinSource11 ((uint8_t)0x0B) +#define EXTI_PinSource12 ((uint8_t)0x0C) +#define EXTI_PinSource13 ((uint8_t)0x0D) +#define EXTI_PinSource14 ((uint8_t)0x0E) +#define EXTI_PinSource15 ((uint8_t)0x0F) +#define IS_EXTI_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == EXTI_PinSource0) || \ + ((PINSOURCE) == EXTI_PinSource1) || \ + ((PINSOURCE) == EXTI_PinSource2) || \ + ((PINSOURCE) == EXTI_PinSource3) || \ + ((PINSOURCE) == EXTI_PinSource4) || \ + ((PINSOURCE) == EXTI_PinSource5) || \ + ((PINSOURCE) == EXTI_PinSource6) || \ + ((PINSOURCE) == EXTI_PinSource7) || \ + ((PINSOURCE) == EXTI_PinSource8) || \ + ((PINSOURCE) == EXTI_PinSource9) || \ + ((PINSOURCE) == EXTI_PinSource10) || \ + ((PINSOURCE) == EXTI_PinSource11) || \ + ((PINSOURCE) == EXTI_PinSource12) || \ + ((PINSOURCE) == EXTI_PinSource13) || \ + ((PINSOURCE) == EXTI_PinSource14) || \ + ((PINSOURCE) == EXTI_PinSource15)) +/** + * @} + */ + + +/** @defgroup SYSCFG_Memory_Remap_Config + * @{ + */ +#define SYSCFG_MemoryRemap_Flash ((uint8_t)0x00) +#define SYSCFG_MemoryRemap_SystemFlash ((uint8_t)0x01) +#define SYSCFG_MemoryRemap_FSMC ((uint8_t)0x02) +#define SYSCFG_MemoryRemap_SRAM ((uint8_t)0x03) + +#define IS_SYSCFG_MEMORY_REMAP_CONFING(REMAP) (((REMAP) == SYSCFG_MemoryRemap_Flash) || \ + ((REMAP) == SYSCFG_MemoryRemap_SystemFlash) || \ + ((REMAP) == SYSCFG_MemoryRemap_SRAM) || \ + ((REMAP) == SYSCFG_MemoryRemap_FSMC)) +/** + * @} + */ + + +/** @defgroup SYSCFG_ETHERNET_Media_Interface + * @{ + */ +#define SYSCFG_ETH_MediaInterface_MII ((uint32_t)0x00000000) +#define SYSCFG_ETH_MediaInterface_RMII ((uint32_t)0x00000001) + +#define IS_SYSCFG_ETH_MEDIA_INTERFACE(INTERFACE) (((INTERFACE) == SYSCFG_ETH_MediaInterface_MII) || \ + ((INTERFACE) == SYSCFG_ETH_MediaInterface_RMII)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +void SYSCFG_DeInit(void); +void SYSCFG_MemoryRemapConfig(uint8_t SYSCFG_MemoryRemap); +void SYSCFG_EXTILineConfig(uint8_t EXTI_PortSourceGPIOx, uint8_t EXTI_PinSourcex); +void SYSCFG_ETH_MediaInterfaceConfig(uint32_t SYSCFG_ETH_MediaInterface); +void SYSCFG_CompensationCellCmd(FunctionalState NewState); +FlagStatus SYSCFG_GetCompensationCellStatus(void); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_SYSCFG_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_tim.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_tim.h new file mode 100644 index 000000000..83420d537 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_tim.h @@ -0,0 +1,1144 @@ +/** + ****************************************************************************** + * @file stm32f4xx_tim.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the TIM firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_TIM_H +#define __STM32F4xx_TIM_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup TIM + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief TIM Time Base Init structure definition + * @note This structure is used with all TIMx except for TIM6 and TIM7. + */ + +typedef struct +{ + uint16_t TIM_Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. + This parameter can be a number between 0x0000 and 0xFFFF */ + + uint16_t TIM_CounterMode; /*!< Specifies the counter mode. + This parameter can be a value of @ref TIM_Counter_Mode */ + + uint32_t TIM_Period; /*!< Specifies the period value to be loaded into the active + Auto-Reload Register at the next update event. + This parameter must be a number between 0x0000 and 0xFFFF. */ + + uint16_t TIM_ClockDivision; /*!< Specifies the clock division. + This parameter can be a value of @ref TIM_Clock_Division_CKD */ + + uint8_t TIM_RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter + reaches zero, an update event is generated and counting restarts + from the RCR value (N). + This means in PWM mode that (N+1) corresponds to: + - the number of PWM periods in edge-aligned mode + - the number of half PWM period in center-aligned mode + This parameter must be a number between 0x00 and 0xFF. + @note This parameter is valid only for TIM1 and TIM8. */ +} TIM_TimeBaseInitTypeDef; + +/** + * @brief TIM Output Compare Init structure definition + */ + +typedef struct +{ + uint16_t TIM_OCMode; /*!< Specifies the TIM mode. + This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ + + uint16_t TIM_OutputState; /*!< Specifies the TIM Output Compare state. + This parameter can be a value of @ref TIM_Output_Compare_State */ + + uint16_t TIM_OutputNState; /*!< Specifies the TIM complementary Output Compare state. + This parameter can be a value of @ref TIM_Output_Compare_N_State + @note This parameter is valid only for TIM1 and TIM8. */ + + uint32_t TIM_Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. + This parameter can be a number between 0x0000 and 0xFFFF */ + + uint16_t TIM_OCPolarity; /*!< Specifies the output polarity. + This parameter can be a value of @ref TIM_Output_Compare_Polarity */ + + uint16_t TIM_OCNPolarity; /*!< Specifies the complementary output polarity. + This parameter can be a value of @ref TIM_Output_Compare_N_Polarity + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_Idle_State + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State + @note This parameter is valid only for TIM1 and TIM8. */ +} TIM_OCInitTypeDef; + +/** + * @brief TIM Input Capture Init structure definition + */ + +typedef struct +{ + + uint16_t TIM_Channel; /*!< Specifies the TIM channel. + This parameter can be a value of @ref TIM_Channel */ + + uint16_t TIM_ICPolarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Input_Capture_Polarity */ + + uint16_t TIM_ICSelection; /*!< Specifies the input. + This parameter can be a value of @ref TIM_Input_Capture_Selection */ + + uint16_t TIM_ICPrescaler; /*!< Specifies the Input Capture Prescaler. + This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ + + uint16_t TIM_ICFilter; /*!< Specifies the input capture filter. + This parameter can be a number between 0x0 and 0xF */ +} TIM_ICInitTypeDef; + +/** + * @brief BDTR structure definition + * @note This structure is used only with TIM1 and TIM8. + */ + +typedef struct +{ + + uint16_t TIM_OSSRState; /*!< Specifies the Off-State selection used in Run mode. + This parameter can be a value of @ref TIM_OSSR_Off_State_Selection_for_Run_mode_state */ + + uint16_t TIM_OSSIState; /*!< Specifies the Off-State used in Idle state. + This parameter can be a value of @ref TIM_OSSI_Off_State_Selection_for_Idle_mode_state */ + + uint16_t TIM_LOCKLevel; /*!< Specifies the LOCK level parameters. + This parameter can be a value of @ref TIM_Lock_level */ + + uint16_t TIM_DeadTime; /*!< Specifies the delay time between the switching-off and the + switching-on of the outputs. + This parameter can be a number between 0x00 and 0xFF */ + + uint16_t TIM_Break; /*!< Specifies whether the TIM Break input is enabled or not. + This parameter can be a value of @ref TIM_Break_Input_enable_disable */ + + uint16_t TIM_BreakPolarity; /*!< Specifies the TIM Break Input pin polarity. + This parameter can be a value of @ref TIM_Break_Polarity */ + + uint16_t TIM_AutomaticOutput; /*!< Specifies whether the TIM Automatic Output feature is enabled or not. + This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */ +} TIM_BDTRInitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup TIM_Exported_constants + * @{ + */ + +#define IS_TIM_ALL_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM10) || \ + ((PERIPH) == TIM11) || \ + ((PERIPH) == TIM12) || \ + (((PERIPH) == TIM13) || \ + ((PERIPH) == TIM14))) +/* LIST1: TIM1, TIM2, TIM3, TIM4, TIM5, TIM8, TIM9, TIM10, TIM11, TIM12, TIM13 and TIM14 */ +#define IS_TIM_LIST1_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM10) || \ + ((PERIPH) == TIM11) || \ + ((PERIPH) == TIM12) || \ + ((PERIPH) == TIM13) || \ + ((PERIPH) == TIM14)) + +/* LIST2: TIM1, TIM2, TIM3, TIM4, TIM5, TIM8, TIM9 and TIM12 */ +#define IS_TIM_LIST2_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM12)) +/* LIST3: TIM1, TIM2, TIM3, TIM4, TIM5 and TIM8 */ +#define IS_TIM_LIST3_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8)) +/* LIST4: TIM1 and TIM8 */ +#define IS_TIM_LIST4_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM8)) +/* LIST5: TIM1, TIM2, TIM3, TIM4, TIM5, TIM6, TIM7 and TIM8 */ +#define IS_TIM_LIST5_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8)) +/* LIST6: TIM2, TIM5 and TIM11 */ +#define IS_TIM_LIST6_PERIPH(TIMx)(((TIMx) == TIM2) || \ + ((TIMx) == TIM5) || \ + ((TIMx) == TIM11)) + +/** @defgroup TIM_Output_Compare_and_PWM_modes + * @{ + */ + +#define TIM_OCMode_Timing ((uint16_t)0x0000) +#define TIM_OCMode_Active ((uint16_t)0x0010) +#define TIM_OCMode_Inactive ((uint16_t)0x0020) +#define TIM_OCMode_Toggle ((uint16_t)0x0030) +#define TIM_OCMode_PWM1 ((uint16_t)0x0060) +#define TIM_OCMode_PWM2 ((uint16_t)0x0070) +#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \ + ((MODE) == TIM_OCMode_Active) || \ + ((MODE) == TIM_OCMode_Inactive) || \ + ((MODE) == TIM_OCMode_Toggle)|| \ + ((MODE) == TIM_OCMode_PWM1) || \ + ((MODE) == TIM_OCMode_PWM2)) +#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \ + ((MODE) == TIM_OCMode_Active) || \ + ((MODE) == TIM_OCMode_Inactive) || \ + ((MODE) == TIM_OCMode_Toggle)|| \ + ((MODE) == TIM_OCMode_PWM1) || \ + ((MODE) == TIM_OCMode_PWM2) || \ + ((MODE) == TIM_ForcedAction_Active) || \ + ((MODE) == TIM_ForcedAction_InActive)) +/** + * @} + */ + +/** @defgroup TIM_One_Pulse_Mode + * @{ + */ + +#define TIM_OPMode_Single ((uint16_t)0x0008) +#define TIM_OPMode_Repetitive ((uint16_t)0x0000) +#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \ + ((MODE) == TIM_OPMode_Repetitive)) +/** + * @} + */ + +/** @defgroup TIM_Channel + * @{ + */ + +#define TIM_Channel_1 ((uint16_t)0x0000) +#define TIM_Channel_2 ((uint16_t)0x0004) +#define TIM_Channel_3 ((uint16_t)0x0008) +#define TIM_Channel_4 ((uint16_t)0x000C) + +#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2) || \ + ((CHANNEL) == TIM_Channel_3) || \ + ((CHANNEL) == TIM_Channel_4)) + +#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2)) +#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2) || \ + ((CHANNEL) == TIM_Channel_3)) +/** + * @} + */ + +/** @defgroup TIM_Clock_Division_CKD + * @{ + */ + +#define TIM_CKD_DIV1 ((uint16_t)0x0000) +#define TIM_CKD_DIV2 ((uint16_t)0x0100) +#define TIM_CKD_DIV4 ((uint16_t)0x0200) +#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \ + ((DIV) == TIM_CKD_DIV2) || \ + ((DIV) == TIM_CKD_DIV4)) +/** + * @} + */ + +/** @defgroup TIM_Counter_Mode + * @{ + */ + +#define TIM_CounterMode_Up ((uint16_t)0x0000) +#define TIM_CounterMode_Down ((uint16_t)0x0010) +#define TIM_CounterMode_CenterAligned1 ((uint16_t)0x0020) +#define TIM_CounterMode_CenterAligned2 ((uint16_t)0x0040) +#define TIM_CounterMode_CenterAligned3 ((uint16_t)0x0060) +#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) || \ + ((MODE) == TIM_CounterMode_Down) || \ + ((MODE) == TIM_CounterMode_CenterAligned1) || \ + ((MODE) == TIM_CounterMode_CenterAligned2) || \ + ((MODE) == TIM_CounterMode_CenterAligned3)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Polarity + * @{ + */ + +#define TIM_OCPolarity_High ((uint16_t)0x0000) +#define TIM_OCPolarity_Low ((uint16_t)0x0002) +#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \ + ((POLARITY) == TIM_OCPolarity_Low)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Polarity + * @{ + */ + +#define TIM_OCNPolarity_High ((uint16_t)0x0000) +#define TIM_OCNPolarity_Low ((uint16_t)0x0008) +#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \ + ((POLARITY) == TIM_OCNPolarity_Low)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_State + * @{ + */ + +#define TIM_OutputState_Disable ((uint16_t)0x0000) +#define TIM_OutputState_Enable ((uint16_t)0x0001) +#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \ + ((STATE) == TIM_OutputState_Enable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_State + * @{ + */ + +#define TIM_OutputNState_Disable ((uint16_t)0x0000) +#define TIM_OutputNState_Enable ((uint16_t)0x0004) +#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \ + ((STATE) == TIM_OutputNState_Enable)) +/** + * @} + */ + +/** @defgroup TIM_Capture_Compare_State + * @{ + */ + +#define TIM_CCx_Enable ((uint16_t)0x0001) +#define TIM_CCx_Disable ((uint16_t)0x0000) +#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \ + ((CCX) == TIM_CCx_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Capture_Compare_N_State + * @{ + */ + +#define TIM_CCxN_Enable ((uint16_t)0x0004) +#define TIM_CCxN_Disable ((uint16_t)0x0000) +#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \ + ((CCXN) == TIM_CCxN_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Break_Input_enable_disable + * @{ + */ + +#define TIM_Break_Enable ((uint16_t)0x1000) +#define TIM_Break_Disable ((uint16_t)0x0000) +#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \ + ((STATE) == TIM_Break_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Break_Polarity + * @{ + */ + +#define TIM_BreakPolarity_Low ((uint16_t)0x0000) +#define TIM_BreakPolarity_High ((uint16_t)0x2000) +#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \ + ((POLARITY) == TIM_BreakPolarity_High)) +/** + * @} + */ + +/** @defgroup TIM_AOE_Bit_Set_Reset + * @{ + */ + +#define TIM_AutomaticOutput_Enable ((uint16_t)0x4000) +#define TIM_AutomaticOutput_Disable ((uint16_t)0x0000) +#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \ + ((STATE) == TIM_AutomaticOutput_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Lock_level + * @{ + */ + +#define TIM_LOCKLevel_OFF ((uint16_t)0x0000) +#define TIM_LOCKLevel_1 ((uint16_t)0x0100) +#define TIM_LOCKLevel_2 ((uint16_t)0x0200) +#define TIM_LOCKLevel_3 ((uint16_t)0x0300) +#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \ + ((LEVEL) == TIM_LOCKLevel_1) || \ + ((LEVEL) == TIM_LOCKLevel_2) || \ + ((LEVEL) == TIM_LOCKLevel_3)) +/** + * @} + */ + +/** @defgroup TIM_OSSI_Off_State_Selection_for_Idle_mode_state + * @{ + */ + +#define TIM_OSSIState_Enable ((uint16_t)0x0400) +#define TIM_OSSIState_Disable ((uint16_t)0x0000) +#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \ + ((STATE) == TIM_OSSIState_Disable)) +/** + * @} + */ + +/** @defgroup TIM_OSSR_Off_State_Selection_for_Run_mode_state + * @{ + */ + +#define TIM_OSSRState_Enable ((uint16_t)0x0800) +#define TIM_OSSRState_Disable ((uint16_t)0x0000) +#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \ + ((STATE) == TIM_OSSRState_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Idle_State + * @{ + */ + +#define TIM_OCIdleState_Set ((uint16_t)0x0100) +#define TIM_OCIdleState_Reset ((uint16_t)0x0000) +#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \ + ((STATE) == TIM_OCIdleState_Reset)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Idle_State + * @{ + */ + +#define TIM_OCNIdleState_Set ((uint16_t)0x0200) +#define TIM_OCNIdleState_Reset ((uint16_t)0x0000) +#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \ + ((STATE) == TIM_OCNIdleState_Reset)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Polarity + * @{ + */ + +#define TIM_ICPolarity_Rising ((uint16_t)0x0000) +#define TIM_ICPolarity_Falling ((uint16_t)0x0002) +#define TIM_ICPolarity_BothEdge ((uint16_t)0x000A) +#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \ + ((POLARITY) == TIM_ICPolarity_Falling)|| \ + ((POLARITY) == TIM_ICPolarity_BothEdge)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Selection + * @{ + */ + +#define TIM_ICSelection_DirectTI ((uint16_t)0x0001) /*!< TIM Input 1, 2, 3 or 4 is selected to be + connected to IC1, IC2, IC3 or IC4, respectively */ +#define TIM_ICSelection_IndirectTI ((uint16_t)0x0002) /*!< TIM Input 1, 2, 3 or 4 is selected to be + connected to IC2, IC1, IC4 or IC3, respectively. */ +#define TIM_ICSelection_TRC ((uint16_t)0x0003) /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC. */ +#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \ + ((SELECTION) == TIM_ICSelection_IndirectTI) || \ + ((SELECTION) == TIM_ICSelection_TRC)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Prescaler + * @{ + */ + +#define TIM_ICPSC_DIV1 ((uint16_t)0x0000) /*!< Capture performed each time an edge is detected on the capture input. */ +#define TIM_ICPSC_DIV2 ((uint16_t)0x0004) /*!< Capture performed once every 2 events. */ +#define TIM_ICPSC_DIV4 ((uint16_t)0x0008) /*!< Capture performed once every 4 events. */ +#define TIM_ICPSC_DIV8 ((uint16_t)0x000C) /*!< Capture performed once every 8 events. */ +#define IS_TIM_IC_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ICPSC_DIV1) || \ + ((PRESCALER) == TIM_ICPSC_DIV2) || \ + ((PRESCALER) == TIM_ICPSC_DIV4) || \ + ((PRESCALER) == TIM_ICPSC_DIV8)) +/** + * @} + */ + +/** @defgroup TIM_interrupt_sources + * @{ + */ + +#define TIM_IT_Update ((uint16_t)0x0001) +#define TIM_IT_CC1 ((uint16_t)0x0002) +#define TIM_IT_CC2 ((uint16_t)0x0004) +#define TIM_IT_CC3 ((uint16_t)0x0008) +#define TIM_IT_CC4 ((uint16_t)0x0010) +#define TIM_IT_COM ((uint16_t)0x0020) +#define TIM_IT_Trigger ((uint16_t)0x0040) +#define TIM_IT_Break ((uint16_t)0x0080) +#define IS_TIM_IT(IT) ((((IT) & (uint16_t)0xFF00) == 0x0000) && ((IT) != 0x0000)) + +#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \ + ((IT) == TIM_IT_CC1) || \ + ((IT) == TIM_IT_CC2) || \ + ((IT) == TIM_IT_CC3) || \ + ((IT) == TIM_IT_CC4) || \ + ((IT) == TIM_IT_COM) || \ + ((IT) == TIM_IT_Trigger) || \ + ((IT) == TIM_IT_Break)) +/** + * @} + */ + +/** @defgroup TIM_DMA_Base_address + * @{ + */ + +#define TIM_DMABase_CR1 ((uint16_t)0x0000) +#define TIM_DMABase_CR2 ((uint16_t)0x0001) +#define TIM_DMABase_SMCR ((uint16_t)0x0002) +#define TIM_DMABase_DIER ((uint16_t)0x0003) +#define TIM_DMABase_SR ((uint16_t)0x0004) +#define TIM_DMABase_EGR ((uint16_t)0x0005) +#define TIM_DMABase_CCMR1 ((uint16_t)0x0006) +#define TIM_DMABase_CCMR2 ((uint16_t)0x0007) +#define TIM_DMABase_CCER ((uint16_t)0x0008) +#define TIM_DMABase_CNT ((uint16_t)0x0009) +#define TIM_DMABase_PSC ((uint16_t)0x000A) +#define TIM_DMABase_ARR ((uint16_t)0x000B) +#define TIM_DMABase_RCR ((uint16_t)0x000C) +#define TIM_DMABase_CCR1 ((uint16_t)0x000D) +#define TIM_DMABase_CCR2 ((uint16_t)0x000E) +#define TIM_DMABase_CCR3 ((uint16_t)0x000F) +#define TIM_DMABase_CCR4 ((uint16_t)0x0010) +#define TIM_DMABase_BDTR ((uint16_t)0x0011) +#define TIM_DMABase_DCR ((uint16_t)0x0012) +#define TIM_DMABase_OR ((uint16_t)0x0013) +#define IS_TIM_DMA_BASE(BASE) (((BASE) == TIM_DMABase_CR1) || \ + ((BASE) == TIM_DMABase_CR2) || \ + ((BASE) == TIM_DMABase_SMCR) || \ + ((BASE) == TIM_DMABase_DIER) || \ + ((BASE) == TIM_DMABase_SR) || \ + ((BASE) == TIM_DMABase_EGR) || \ + ((BASE) == TIM_DMABase_CCMR1) || \ + ((BASE) == TIM_DMABase_CCMR2) || \ + ((BASE) == TIM_DMABase_CCER) || \ + ((BASE) == TIM_DMABase_CNT) || \ + ((BASE) == TIM_DMABase_PSC) || \ + ((BASE) == TIM_DMABase_ARR) || \ + ((BASE) == TIM_DMABase_RCR) || \ + ((BASE) == TIM_DMABase_CCR1) || \ + ((BASE) == TIM_DMABase_CCR2) || \ + ((BASE) == TIM_DMABase_CCR3) || \ + ((BASE) == TIM_DMABase_CCR4) || \ + ((BASE) == TIM_DMABase_BDTR) || \ + ((BASE) == TIM_DMABase_DCR) || \ + ((BASE) == TIM_DMABase_OR)) +/** + * @} + */ + +/** @defgroup TIM_DMA_Burst_Length + * @{ + */ + +#define TIM_DMABurstLength_1Transfer ((uint16_t)0x0000) +#define TIM_DMABurstLength_2Transfers ((uint16_t)0x0100) +#define TIM_DMABurstLength_3Transfers ((uint16_t)0x0200) +#define TIM_DMABurstLength_4Transfers ((uint16_t)0x0300) +#define TIM_DMABurstLength_5Transfers ((uint16_t)0x0400) +#define TIM_DMABurstLength_6Transfers ((uint16_t)0x0500) +#define TIM_DMABurstLength_7Transfers ((uint16_t)0x0600) +#define TIM_DMABurstLength_8Transfers ((uint16_t)0x0700) +#define TIM_DMABurstLength_9Transfers ((uint16_t)0x0800) +#define TIM_DMABurstLength_10Transfers ((uint16_t)0x0900) +#define TIM_DMABurstLength_11Transfers ((uint16_t)0x0A00) +#define TIM_DMABurstLength_12Transfers ((uint16_t)0x0B00) +#define TIM_DMABurstLength_13Transfers ((uint16_t)0x0C00) +#define TIM_DMABurstLength_14Transfers ((uint16_t)0x0D00) +#define TIM_DMABurstLength_15Transfers ((uint16_t)0x0E00) +#define TIM_DMABurstLength_16Transfers ((uint16_t)0x0F00) +#define TIM_DMABurstLength_17Transfers ((uint16_t)0x1000) +#define TIM_DMABurstLength_18Transfers ((uint16_t)0x1100) +#define IS_TIM_DMA_LENGTH(LENGTH) (((LENGTH) == TIM_DMABurstLength_1Transfer) || \ + ((LENGTH) == TIM_DMABurstLength_2Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_3Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_4Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_5Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_6Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_7Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_8Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_9Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_10Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_11Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_12Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_13Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_14Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_15Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_16Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_17Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_18Transfers)) +/** + * @} + */ + +/** @defgroup TIM_DMA_sources + * @{ + */ + +#define TIM_DMA_Update ((uint16_t)0x0100) +#define TIM_DMA_CC1 ((uint16_t)0x0200) +#define TIM_DMA_CC2 ((uint16_t)0x0400) +#define TIM_DMA_CC3 ((uint16_t)0x0800) +#define TIM_DMA_CC4 ((uint16_t)0x1000) +#define TIM_DMA_COM ((uint16_t)0x2000) +#define TIM_DMA_Trigger ((uint16_t)0x4000) +#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0x80FF) == 0x0000) && ((SOURCE) != 0x0000)) + +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Prescaler + * @{ + */ + +#define TIM_ExtTRGPSC_OFF ((uint16_t)0x0000) +#define TIM_ExtTRGPSC_DIV2 ((uint16_t)0x1000) +#define TIM_ExtTRGPSC_DIV4 ((uint16_t)0x2000) +#define TIM_ExtTRGPSC_DIV8 ((uint16_t)0x3000) +#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV8)) +/** + * @} + */ + +/** @defgroup TIM_Internal_Trigger_Selection + * @{ + */ + +#define TIM_TS_ITR0 ((uint16_t)0x0000) +#define TIM_TS_ITR1 ((uint16_t)0x0010) +#define TIM_TS_ITR2 ((uint16_t)0x0020) +#define TIM_TS_ITR3 ((uint16_t)0x0030) +#define TIM_TS_TI1F_ED ((uint16_t)0x0040) +#define TIM_TS_TI1FP1 ((uint16_t)0x0050) +#define TIM_TS_TI2FP2 ((uint16_t)0x0060) +#define TIM_TS_ETRF ((uint16_t)0x0070) +#define IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ + ((SELECTION) == TIM_TS_ITR1) || \ + ((SELECTION) == TIM_TS_ITR2) || \ + ((SELECTION) == TIM_TS_ITR3) || \ + ((SELECTION) == TIM_TS_TI1F_ED) || \ + ((SELECTION) == TIM_TS_TI1FP1) || \ + ((SELECTION) == TIM_TS_TI2FP2) || \ + ((SELECTION) == TIM_TS_ETRF)) +#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ + ((SELECTION) == TIM_TS_ITR1) || \ + ((SELECTION) == TIM_TS_ITR2) || \ + ((SELECTION) == TIM_TS_ITR3)) +/** + * @} + */ + +/** @defgroup TIM_TIx_External_Clock_Source + * @{ + */ + +#define TIM_TIxExternalCLK1Source_TI1 ((uint16_t)0x0050) +#define TIM_TIxExternalCLK1Source_TI2 ((uint16_t)0x0060) +#define TIM_TIxExternalCLK1Source_TI1ED ((uint16_t)0x0040) + +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Polarity + * @{ + */ +#define TIM_ExtTRGPolarity_Inverted ((uint16_t)0x8000) +#define TIM_ExtTRGPolarity_NonInverted ((uint16_t)0x0000) +#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \ + ((POLARITY) == TIM_ExtTRGPolarity_NonInverted)) +/** + * @} + */ + +/** @defgroup TIM_Prescaler_Reload_Mode + * @{ + */ + +#define TIM_PSCReloadMode_Update ((uint16_t)0x0000) +#define TIM_PSCReloadMode_Immediate ((uint16_t)0x0001) +#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \ + ((RELOAD) == TIM_PSCReloadMode_Immediate)) +/** + * @} + */ + +/** @defgroup TIM_Forced_Action + * @{ + */ + +#define TIM_ForcedAction_Active ((uint16_t)0x0050) +#define TIM_ForcedAction_InActive ((uint16_t)0x0040) +#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \ + ((ACTION) == TIM_ForcedAction_InActive)) +/** + * @} + */ + +/** @defgroup TIM_Encoder_Mode + * @{ + */ + +#define TIM_EncoderMode_TI1 ((uint16_t)0x0001) +#define TIM_EncoderMode_TI2 ((uint16_t)0x0002) +#define TIM_EncoderMode_TI12 ((uint16_t)0x0003) +#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \ + ((MODE) == TIM_EncoderMode_TI2) || \ + ((MODE) == TIM_EncoderMode_TI12)) +/** + * @} + */ + + +/** @defgroup TIM_Event_Source + * @{ + */ + +#define TIM_EventSource_Update ((uint16_t)0x0001) +#define TIM_EventSource_CC1 ((uint16_t)0x0002) +#define TIM_EventSource_CC2 ((uint16_t)0x0004) +#define TIM_EventSource_CC3 ((uint16_t)0x0008) +#define TIM_EventSource_CC4 ((uint16_t)0x0010) +#define TIM_EventSource_COM ((uint16_t)0x0020) +#define TIM_EventSource_Trigger ((uint16_t)0x0040) +#define TIM_EventSource_Break ((uint16_t)0x0080) +#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0xFF00) == 0x0000) && ((SOURCE) != 0x0000)) + +/** + * @} + */ + +/** @defgroup TIM_Update_Source + * @{ + */ + +#define TIM_UpdateSource_Global ((uint16_t)0x0000) /*!< Source of update is the counter overflow/underflow + or the setting of UG bit, or an update generation + through the slave mode controller. */ +#define TIM_UpdateSource_Regular ((uint16_t)0x0001) /*!< Source of update is counter overflow/underflow. */ +#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \ + ((SOURCE) == TIM_UpdateSource_Regular)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Preload_State + * @{ + */ + +#define TIM_OCPreload_Enable ((uint16_t)0x0008) +#define TIM_OCPreload_Disable ((uint16_t)0x0000) +#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \ + ((STATE) == TIM_OCPreload_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Fast_State + * @{ + */ + +#define TIM_OCFast_Enable ((uint16_t)0x0004) +#define TIM_OCFast_Disable ((uint16_t)0x0000) +#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \ + ((STATE) == TIM_OCFast_Disable)) + +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Clear_State + * @{ + */ + +#define TIM_OCClear_Enable ((uint16_t)0x0080) +#define TIM_OCClear_Disable ((uint16_t)0x0000) +#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \ + ((STATE) == TIM_OCClear_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Trigger_Output_Source + * @{ + */ + +#define TIM_TRGOSource_Reset ((uint16_t)0x0000) +#define TIM_TRGOSource_Enable ((uint16_t)0x0010) +#define TIM_TRGOSource_Update ((uint16_t)0x0020) +#define TIM_TRGOSource_OC1 ((uint16_t)0x0030) +#define TIM_TRGOSource_OC1Ref ((uint16_t)0x0040) +#define TIM_TRGOSource_OC2Ref ((uint16_t)0x0050) +#define TIM_TRGOSource_OC3Ref ((uint16_t)0x0060) +#define TIM_TRGOSource_OC4Ref ((uint16_t)0x0070) +#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \ + ((SOURCE) == TIM_TRGOSource_Enable) || \ + ((SOURCE) == TIM_TRGOSource_Update) || \ + ((SOURCE) == TIM_TRGOSource_OC1) || \ + ((SOURCE) == TIM_TRGOSource_OC1Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC2Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC3Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC4Ref)) +/** + * @} + */ + +/** @defgroup TIM_Slave_Mode + * @{ + */ + +#define TIM_SlaveMode_Reset ((uint16_t)0x0004) +#define TIM_SlaveMode_Gated ((uint16_t)0x0005) +#define TIM_SlaveMode_Trigger ((uint16_t)0x0006) +#define TIM_SlaveMode_External1 ((uint16_t)0x0007) +#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \ + ((MODE) == TIM_SlaveMode_Gated) || \ + ((MODE) == TIM_SlaveMode_Trigger) || \ + ((MODE) == TIM_SlaveMode_External1)) +/** + * @} + */ + +/** @defgroup TIM_Master_Slave_Mode + * @{ + */ + +#define TIM_MasterSlaveMode_Enable ((uint16_t)0x0080) +#define TIM_MasterSlaveMode_Disable ((uint16_t)0x0000) +#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \ + ((STATE) == TIM_MasterSlaveMode_Disable)) +/** + * @} + */ +/** @defgroup TIM_Remap + * @{ + */ + +#define TIM2_TIM8_TRGO ((uint16_t)0x0000) +#define TIM2_ETH_PTP ((uint16_t)0x0400) +#define TIM2_USBFS_SOF ((uint16_t)0x0800) +#define TIM2_USBHS_SOF ((uint16_t)0x0C00) + +#define TIM5_GPIO ((uint16_t)0x0000) +#define TIM5_LSI ((uint16_t)0x0040) +#define TIM5_LSE ((uint16_t)0x0080) +#define TIM5_RTC ((uint16_t)0x00C0) + +#define TIM11_GPIO ((uint16_t)0x0000) +#define TIM11_HSE ((uint16_t)0x0002) + +#define IS_TIM_REMAP(TIM_REMAP) (((TIM_REMAP) == TIM2_TIM8_TRGO)||\ + ((TIM_REMAP) == TIM2_ETH_PTP)||\ + ((TIM_REMAP) == TIM2_USBFS_SOF)||\ + ((TIM_REMAP) == TIM2_USBHS_SOF)||\ + ((TIM_REMAP) == TIM5_GPIO)||\ + ((TIM_REMAP) == TIM5_LSI)||\ + ((TIM_REMAP) == TIM5_LSE)||\ + ((TIM_REMAP) == TIM5_RTC)||\ + ((TIM_REMAP) == TIM11_GPIO)||\ + ((TIM_REMAP) == TIM11_HSE)) + +/** + * @} + */ +/** @defgroup TIM_Flags + * @{ + */ + +#define TIM_FLAG_Update ((uint16_t)0x0001) +#define TIM_FLAG_CC1 ((uint16_t)0x0002) +#define TIM_FLAG_CC2 ((uint16_t)0x0004) +#define TIM_FLAG_CC3 ((uint16_t)0x0008) +#define TIM_FLAG_CC4 ((uint16_t)0x0010) +#define TIM_FLAG_COM ((uint16_t)0x0020) +#define TIM_FLAG_Trigger ((uint16_t)0x0040) +#define TIM_FLAG_Break ((uint16_t)0x0080) +#define TIM_FLAG_CC1OF ((uint16_t)0x0200) +#define TIM_FLAG_CC2OF ((uint16_t)0x0400) +#define TIM_FLAG_CC3OF ((uint16_t)0x0800) +#define TIM_FLAG_CC4OF ((uint16_t)0x1000) +#define IS_TIM_GET_FLAG(FLAG) (((FLAG) == TIM_FLAG_Update) || \ + ((FLAG) == TIM_FLAG_CC1) || \ + ((FLAG) == TIM_FLAG_CC2) || \ + ((FLAG) == TIM_FLAG_CC3) || \ + ((FLAG) == TIM_FLAG_CC4) || \ + ((FLAG) == TIM_FLAG_COM) || \ + ((FLAG) == TIM_FLAG_Trigger) || \ + ((FLAG) == TIM_FLAG_Break) || \ + ((FLAG) == TIM_FLAG_CC1OF) || \ + ((FLAG) == TIM_FLAG_CC2OF) || \ + ((FLAG) == TIM_FLAG_CC3OF) || \ + ((FLAG) == TIM_FLAG_CC4OF)) + +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Filer_Value + * @{ + */ + +#define IS_TIM_IC_FILTER(ICFILTER) ((ICFILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Filter + * @{ + */ + +#define IS_TIM_EXT_FILTER(EXTFILTER) ((EXTFILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_Legacy + * @{ + */ + +#define TIM_DMABurstLength_1Byte TIM_DMABurstLength_1Transfer +#define TIM_DMABurstLength_2Bytes TIM_DMABurstLength_2Transfers +#define TIM_DMABurstLength_3Bytes TIM_DMABurstLength_3Transfers +#define TIM_DMABurstLength_4Bytes TIM_DMABurstLength_4Transfers +#define TIM_DMABurstLength_5Bytes TIM_DMABurstLength_5Transfers +#define TIM_DMABurstLength_6Bytes TIM_DMABurstLength_6Transfers +#define TIM_DMABurstLength_7Bytes TIM_DMABurstLength_7Transfers +#define TIM_DMABurstLength_8Bytes TIM_DMABurstLength_8Transfers +#define TIM_DMABurstLength_9Bytes TIM_DMABurstLength_9Transfers +#define TIM_DMABurstLength_10Bytes TIM_DMABurstLength_10Transfers +#define TIM_DMABurstLength_11Bytes TIM_DMABurstLength_11Transfers +#define TIM_DMABurstLength_12Bytes TIM_DMABurstLength_12Transfers +#define TIM_DMABurstLength_13Bytes TIM_DMABurstLength_13Transfers +#define TIM_DMABurstLength_14Bytes TIM_DMABurstLength_14Transfers +#define TIM_DMABurstLength_15Bytes TIM_DMABurstLength_15Transfers +#define TIM_DMABurstLength_16Bytes TIM_DMABurstLength_16Transfers +#define TIM_DMABurstLength_17Bytes TIM_DMABurstLength_17Transfers +#define TIM_DMABurstLength_18Bytes TIM_DMABurstLength_18Transfers +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* TimeBase management ********************************************************/ +void TIM_DeInit(TIM_TypeDef* TIMx); +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, const TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode); +void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode); +void TIM_SetCounter(TIM_TypeDef* TIMx, uint32_t Counter); +void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint32_t Autoreload); +uint32_t TIM_GetCounter(TIM_TypeDef* TIMx); +uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx); +void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource); +void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode); +void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD); +void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState); + +/* Output Compare management **************************************************/ +void TIM_OC1Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC2Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC3Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC4Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode); +void TIM_SetCompare1(TIM_TypeDef* TIMx, uint32_t Compare1); +void TIM_SetCompare2(TIM_TypeDef* TIMx, uint32_t Compare2); +void TIM_SetCompare3(TIM_TypeDef* TIMx, uint32_t Compare3); +void TIM_SetCompare4(TIM_TypeDef* TIMx, uint32_t Compare4); +void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx); +void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN); + +/* Input Capture management ***************************************************/ +void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +uint32_t TIM_GetCapture1(TIM_TypeDef* TIMx); +uint32_t TIM_GetCapture2(TIM_TypeDef* TIMx); +uint32_t TIM_GetCapture3(TIM_TypeDef* TIMx); +uint32_t TIM_GetCapture4(TIM_TypeDef* TIMx); +void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); + +/* Advanced-control timers (TIM1 and TIM8) specific features ******************/ +void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct); +void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct); +void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState); + +/* Interrupts, DMA and flags management ***************************************/ +void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState); +void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource); +FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); +void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); +ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT); +void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT); +void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength); +void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState); +void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState); + +/* Clocks management **********************************************************/ +void TIM_InternalClockConfig(TIM_TypeDef* TIMx); +void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); +void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, + uint16_t TIM_ICPolarity, uint16_t ICFilter); +void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); +void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter); + +/* Synchronization management *************************************************/ +void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); +void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource); +void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); +void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode); +void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); + +/* Specific interface management **********************************************/ +void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, + uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity); +void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState); + +/* Specific remapping management **********************************************/ +void TIM_RemapConfig(TIM_TypeDef* TIMx, uint16_t TIM_Remap); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F4xx_TIM_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_usart.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_usart.h new file mode 100644 index 000000000..c4025e315 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_usart.h @@ -0,0 +1,423 @@ +/** + ****************************************************************************** + * @file stm32f4xx_usart.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the USART + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_USART_H +#define __STM32F4xx_USART_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup USART + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief USART Init Structure definition + */ + +typedef struct +{ + uint32_t USART_BaudRate; /*!< This member configures the USART communication baud rate. + The baud rate is computed using the following formula: + - IntegerDivider = ((PCLKx) / (8 * (OVR8+1) * (USART_InitStruct->USART_BaudRate))) + - FractionalDivider = ((IntegerDivider - ((u32) IntegerDivider)) * 8 * (OVR8+1)) + 0.5 + Where OVR8 is the "oversampling by 8 mode" configuration bit in the CR1 register. */ + + uint16_t USART_WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. + This parameter can be a value of @ref USART_Word_Length */ + + uint16_t USART_StopBits; /*!< Specifies the number of stop bits transmitted. + This parameter can be a value of @ref USART_Stop_Bits */ + + uint16_t USART_Parity; /*!< Specifies the parity mode. + This parameter can be a value of @ref USART_Parity + @note When parity is enabled, the computed parity is inserted + at the MSB position of the transmitted data (9th bit when + the word length is set to 9 data bits; 8th bit when the + word length is set to 8 data bits). */ + + uint16_t USART_Mode; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled. + This parameter can be a value of @ref USART_Mode */ + + uint16_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled + or disabled. + This parameter can be a value of @ref USART_Hardware_Flow_Control */ +} USART_InitTypeDef; + +/** + * @brief USART Clock Init Structure definition + */ + +typedef struct +{ + + uint16_t USART_Clock; /*!< Specifies whether the USART clock is enabled or disabled. + This parameter can be a value of @ref USART_Clock */ + + uint16_t USART_CPOL; /*!< Specifies the steady state of the serial clock. + This parameter can be a value of @ref USART_Clock_Polarity */ + + uint16_t USART_CPHA; /*!< Specifies the clock transition on which the bit capture is made. + This parameter can be a value of @ref USART_Clock_Phase */ + + uint16_t USART_LastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted + data bit (MSB) has to be output on the SCLK pin in synchronous mode. + This parameter can be a value of @ref USART_Last_Bit */ +} USART_ClockInitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup USART_Exported_Constants + * @{ + */ + +#define IS_USART_ALL_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3) || \ + ((PERIPH) == UART4) || \ + ((PERIPH) == UART5) || \ + ((PERIPH) == USART6)) + +#define IS_USART_1236_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3) || \ + ((PERIPH) == USART6)) + +/** @defgroup USART_Word_Length + * @{ + */ + +#define USART_WordLength_8b ((uint16_t)0x0000) +#define USART_WordLength_9b ((uint16_t)0x1000) + +#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \ + ((LENGTH) == USART_WordLength_9b)) +/** + * @} + */ + +/** @defgroup USART_Stop_Bits + * @{ + */ + +#define USART_StopBits_1 ((uint16_t)0x0000) +#define USART_StopBits_0_5 ((uint16_t)0x1000) +#define USART_StopBits_2 ((uint16_t)0x2000) +#define USART_StopBits_1_5 ((uint16_t)0x3000) +#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \ + ((STOPBITS) == USART_StopBits_0_5) || \ + ((STOPBITS) == USART_StopBits_2) || \ + ((STOPBITS) == USART_StopBits_1_5)) +/** + * @} + */ + +/** @defgroup USART_Parity + * @{ + */ + +#define USART_Parity_No ((uint16_t)0x0000) +#define USART_Parity_Even ((uint16_t)0x0400) +#define USART_Parity_Odd ((uint16_t)0x0600) +#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \ + ((PARITY) == USART_Parity_Even) || \ + ((PARITY) == USART_Parity_Odd)) +/** + * @} + */ + +/** @defgroup USART_Mode + * @{ + */ + +#define USART_Mode_Rx ((uint16_t)0x0004) +#define USART_Mode_Tx ((uint16_t)0x0008) +#define IS_USART_MODE(MODE) ((((MODE) & (uint16_t)0xFFF3) == 0x00) && ((MODE) != (uint16_t)0x00)) +/** + * @} + */ + +/** @defgroup USART_Hardware_Flow_Control + * @{ + */ +#define USART_HardwareFlowControl_None ((uint16_t)0x0000) +#define USART_HardwareFlowControl_RTS ((uint16_t)0x0100) +#define USART_HardwareFlowControl_CTS ((uint16_t)0x0200) +#define USART_HardwareFlowControl_RTS_CTS ((uint16_t)0x0300) +#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\ + (((CONTROL) == USART_HardwareFlowControl_None) || \ + ((CONTROL) == USART_HardwareFlowControl_RTS) || \ + ((CONTROL) == USART_HardwareFlowControl_CTS) || \ + ((CONTROL) == USART_HardwareFlowControl_RTS_CTS)) +/** + * @} + */ + +/** @defgroup USART_Clock + * @{ + */ +#define USART_Clock_Disable ((uint16_t)0x0000) +#define USART_Clock_Enable ((uint16_t)0x0800) +#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \ + ((CLOCK) == USART_Clock_Enable)) +/** + * @} + */ + +/** @defgroup USART_Clock_Polarity + * @{ + */ + +#define USART_CPOL_Low ((uint16_t)0x0000) +#define USART_CPOL_High ((uint16_t)0x0400) +#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High)) + +/** + * @} + */ + +/** @defgroup USART_Clock_Phase + * @{ + */ + +#define USART_CPHA_1Edge ((uint16_t)0x0000) +#define USART_CPHA_2Edge ((uint16_t)0x0200) +#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge)) + +/** + * @} + */ + +/** @defgroup USART_Last_Bit + * @{ + */ + +#define USART_LastBit_Disable ((uint16_t)0x0000) +#define USART_LastBit_Enable ((uint16_t)0x0100) +#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \ + ((LASTBIT) == USART_LastBit_Enable)) +/** + * @} + */ + +/** @defgroup USART_Interrupt_definition + * @{ + */ + +#define USART_IT_PE ((uint16_t)0x0028) +#define USART_IT_TXE ((uint16_t)0x0727) +#define USART_IT_TC ((uint16_t)0x0626) +#define USART_IT_RXNE ((uint16_t)0x0525) +#define USART_IT_ORE_RX ((uint16_t)0x0325) /* In case interrupt is generated if the RXNEIE bit is set */ +#define USART_IT_IDLE ((uint16_t)0x0424) +#define USART_IT_LBD ((uint16_t)0x0846) +#define USART_IT_CTS ((uint16_t)0x096A) +#define USART_IT_ERR ((uint16_t)0x0060) +#define USART_IT_ORE_ER ((uint16_t)0x0360) /* In case interrupt is generated if the EIE bit is set */ +#define USART_IT_NE ((uint16_t)0x0260) +#define USART_IT_FE ((uint16_t)0x0160) + +/** @defgroup USART_Legacy + * @{ + */ +#define USART_IT_ORE USART_IT_ORE_ER +/** + * @} + */ + +#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ + ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ + ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR)) +#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ + ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ + ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \ + ((IT) == USART_IT_ORE_RX) || ((IT) == USART_IT_ORE_ER) || \ + ((IT) == USART_IT_NE) || ((IT) == USART_IT_FE)) +#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS)) +/** + * @} + */ + +/** @defgroup USART_DMA_Requests + * @{ + */ + +#define USART_DMAReq_Tx ((uint16_t)0x0080) +#define USART_DMAReq_Rx ((uint16_t)0x0040) +#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFF3F) == 0x00) && ((DMAREQ) != (uint16_t)0x00)) + +/** + * @} + */ + +/** @defgroup USART_WakeUp_methods + * @{ + */ + +#define USART_WakeUp_IdleLine ((uint16_t)0x0000) +#define USART_WakeUp_AddressMark ((uint16_t)0x0800) +#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \ + ((WAKEUP) == USART_WakeUp_AddressMark)) +/** + * @} + */ + +/** @defgroup USART_LIN_Break_Detection_Length + * @{ + */ + +#define USART_LINBreakDetectLength_10b ((uint16_t)0x0000) +#define USART_LINBreakDetectLength_11b ((uint16_t)0x0020) +#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \ + (((LENGTH) == USART_LINBreakDetectLength_10b) || \ + ((LENGTH) == USART_LINBreakDetectLength_11b)) +/** + * @} + */ + +/** @defgroup USART_IrDA_Low_Power + * @{ + */ + +#define USART_IrDAMode_LowPower ((uint16_t)0x0004) +#define USART_IrDAMode_Normal ((uint16_t)0x0000) +#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \ + ((MODE) == USART_IrDAMode_Normal)) +/** + * @} + */ + +/** @defgroup USART_Flags + * @{ + */ + +#define USART_FLAG_CTS ((uint16_t)0x0200) +#define USART_FLAG_LBD ((uint16_t)0x0100) +#define USART_FLAG_TXE ((uint16_t)0x0080) +#define USART_FLAG_TC ((uint16_t)0x0040) +#define USART_FLAG_RXNE ((uint16_t)0x0020) +#define USART_FLAG_IDLE ((uint16_t)0x0010) +#define USART_FLAG_ORE ((uint16_t)0x0008) +#define USART_FLAG_NE ((uint16_t)0x0004) +#define USART_FLAG_FE ((uint16_t)0x0002) +#define USART_FLAG_PE ((uint16_t)0x0001) +#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \ + ((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \ + ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \ + ((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \ + ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE)) + +#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFC9F) == 0x00) && ((FLAG) != (uint16_t)0x00)) + +#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 7500001)) +#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF) +#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the USART configuration to the default reset state ***/ +void USART_DeInit(USART_TypeDef* USARTx); + +/* Initialization and Configuration functions *********************************/ +void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct); +void USART_StructInit(USART_InitTypeDef* USART_InitStruct); +void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct); +void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct); +void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler); +void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState); + +/* Data transfers functions ***************************************************/ +void USART_SendData(USART_TypeDef* USARTx, uint16_t Data); +uint16_t USART_ReceiveData(USART_TypeDef* USARTx); + +/* Multi-Processor Communication functions ************************************/ +void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address); +void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp); +void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState); + +/* LIN mode functions *********************************************************/ +void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength); +void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SendBreak(USART_TypeDef* USARTx); + +/* Half-duplex mode function **************************************************/ +void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState); + +/* Smartcard mode functions ***************************************************/ +void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime); + +/* IrDA mode functions ********************************************************/ +void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode); +void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState); + +/* DMA transfers management functions *****************************************/ +void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState); + +/* Interrupts and flags management functions **********************************/ +void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState); +FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG); +void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG); +ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT); +void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_USART_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_wwdg.h b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_wwdg.h new file mode 100644 index 000000000..b054e68c6 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_wwdg.h @@ -0,0 +1,105 @@ +/** + ****************************************************************************** + * @file stm32f4xx_wwdg.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file contains all the functions prototypes for the WWDG firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_WWDG_H +#define __STM32F4xx_WWDG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @addtogroup WWDG + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup WWDG_Exported_Constants + * @{ + */ + +/** @defgroup WWDG_Prescaler + * @{ + */ + +#define WWDG_Prescaler_1 ((uint32_t)0x00000000) +#define WWDG_Prescaler_2 ((uint32_t)0x00000080) +#define WWDG_Prescaler_4 ((uint32_t)0x00000100) +#define WWDG_Prescaler_8 ((uint32_t)0x00000180) +#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \ + ((PRESCALER) == WWDG_Prescaler_2) || \ + ((PRESCALER) == WWDG_Prescaler_4) || \ + ((PRESCALER) == WWDG_Prescaler_8)) +#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F) +#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F)) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the WWDG configuration to the default reset state ****/ +void WWDG_DeInit(void); + +/* Prescaler, Refresh window and Counter configuration functions **************/ +void WWDG_SetPrescaler(uint32_t WWDG_Prescaler); +void WWDG_SetWindowValue(uint8_t WindowValue); +void WWDG_EnableIT(void); +void WWDG_SetCounter(uint8_t Counter); + +/* WWDG activation function ***************************************************/ +void WWDG_Enable(uint8_t Counter); + +/* Interrupts and flags management functions **********************************/ +FlagStatus WWDG_GetFlagStatus(void); +void WWDG_ClearFlag(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_WWDG_H */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/misc.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/misc.c new file mode 100644 index 000000000..524c78a69 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/misc.c @@ -0,0 +1,243 @@ +/** + ****************************************************************************** + * @file misc.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides all the miscellaneous firmware functions (add-on + * to CMSIS functions). + * + * @verbatim + * + * =================================================================== + * How to configure Interrupts using driver + * =================================================================== + * + * This section provide functions allowing to configure the NVIC interrupts (IRQ). + * The Cortex-M4 exceptions are managed by CMSIS functions. + * + * 1. Configure the NVIC Priority Grouping using NVIC_PriorityGroupConfig() + * function according to the following table. + + * The table below gives the allowed values of the pre-emption priority and subpriority according + * to the Priority Grouping configuration performed by NVIC_PriorityGroupConfig function + * ========================================================================================================================== + * NVIC_PriorityGroup | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority | Description + * ========================================================================================================================== + * NVIC_PriorityGroup_0 | 0 | 0-15 | 0 bits for pre-emption priority + * | | | 4 bits for subpriority + * -------------------------------------------------------------------------------------------------------------------------- + * NVIC_PriorityGroup_1 | 0-1 | 0-7 | 1 bits for pre-emption priority + * | | | 3 bits for subpriority + * -------------------------------------------------------------------------------------------------------------------------- + * NVIC_PriorityGroup_2 | 0-3 | 0-3 | 2 bits for pre-emption priority + * | | | 2 bits for subpriority + * -------------------------------------------------------------------------------------------------------------------------- + * NVIC_PriorityGroup_3 | 0-7 | 0-1 | 3 bits for pre-emption priority + * | | | 1 bits for subpriority + * -------------------------------------------------------------------------------------------------------------------------- + * NVIC_PriorityGroup_4 | 0-15 | 0 | 4 bits for pre-emption priority + * | | | 0 bits for subpriority + * ========================================================================================================================== + * + * 2. Enable and Configure the priority of the selected IRQ Channels using NVIC_Init() + * + * @note When the NVIC_PriorityGroup_0 is selected, IRQ pre-emption is no more possible. + * The pending IRQ priority will be managed only by the subpriority. + * + * @note IRQ priority order (sorted by highest to lowest priority): + * - Lowest pre-emption priority + * - Lowest subpriority + * - Lowest hardware priority (IRQ number) + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "misc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup MISC + * @brief MISC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup MISC_Private_Functions + * @{ + */ + +/** + * @brief Configures the priority grouping: pre-emption priority and subpriority. + * @param NVIC_PriorityGroup: specifies the priority grouping bits length. + * This parameter can be one of the following values: + * @arg NVIC_PriorityGroup_0: 0 bits for pre-emption priority + * 4 bits for subpriority + * @arg NVIC_PriorityGroup_1: 1 bits for pre-emption priority + * 3 bits for subpriority + * @arg NVIC_PriorityGroup_2: 2 bits for pre-emption priority + * 2 bits for subpriority + * @arg NVIC_PriorityGroup_3: 3 bits for pre-emption priority + * 1 bits for subpriority + * @arg NVIC_PriorityGroup_4: 4 bits for pre-emption priority + * 0 bits for subpriority + * @note When the NVIC_PriorityGroup_0 is selected, IRQ pre-emption is no more possible. + * The pending IRQ priority will be managed only by the subpriority. + * @retval None + */ +void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup) +{ + /* Check the parameters */ + assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup)); + + /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */ + SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup; +} + +/** + * @brief Initializes the NVIC peripheral according to the specified + * parameters in the NVIC_InitStruct. + * @note To configure interrupts priority correctly, the NVIC_PriorityGroupConfig() + * function should be called before. + * @param NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure that contains + * the configuration information for the specified NVIC peripheral. + * @retval None + */ +void NVIC_Init(const NVIC_InitTypeDef* NVIC_InitStruct) +{ + uint8_t tmppriority = 0x00, tmppre = 0x00, tmpsub = 0x0F; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd)); + assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority)); + assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority)); + + if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE) + { + /* Compute the Corresponding IRQ Priority --------------------------------*/ + tmppriority = (0x700 - ((SCB->AIRCR) & (uint32_t)0x700))>> 0x08; + tmppre = (0x4 - tmppriority); + tmpsub = tmpsub >> tmppriority; + + tmppriority = NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre; + tmppriority |= (uint8_t)(NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub); + + tmppriority = tmppriority << 0x04; + + NVIC->IP[NVIC_InitStruct->NVIC_IRQChannel] = tmppriority; + + /* Enable the Selected IRQ Channels --------------------------------------*/ + NVIC->ISER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = + (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); + } + else + { + /* Disable the Selected IRQ Channels -------------------------------------*/ + NVIC->ICER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = + (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); + } +} + +/** + * @brief Sets the vector table location and Offset. + * @param NVIC_VectTab: specifies if the vector table is in RAM or FLASH memory. + * This parameter can be one of the following values: + * @arg NVIC_VectTab_RAM: Vector Table in internal SRAM. + * @arg NVIC_VectTab_FLASH: Vector Table in internal FLASH. + * @param Offset: Vector Table base offset field. This value must be a multiple of 0x200. + * @retval None + */ +void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset) +{ + /* Check the parameters */ + assert_param(IS_NVIC_VECTTAB(NVIC_VectTab)); + assert_param(IS_NVIC_OFFSET(Offset)); + + SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80); +} + +/** + * @brief Selects the condition for the system to enter low power mode. + * @param LowPowerMode: Specifies the new mode for the system to enter low power mode. + * This parameter can be one of the following values: + * @arg NVIC_LP_SEVONPEND: Low Power SEV on Pend. + * @arg NVIC_LP_SLEEPDEEP: Low Power DEEPSLEEP request. + * @arg NVIC_LP_SLEEPONEXIT: Low Power Sleep on Exit. + * @param NewState: new state of LP condition. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_NVIC_LP(LowPowerMode)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + SCB->SCR |= LowPowerMode; + } + else + { + SCB->SCR &= (uint32_t)(~(uint32_t)LowPowerMode); + } +} + +/** + * @brief Configures the SysTick clock source. + * @param SysTick_CLKSource: specifies the SysTick clock source. + * This parameter can be one of the following values: + * @arg SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source. + * @arg SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source. + * @retval None + */ +void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource) +{ + /* Check the parameters */ + assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource)); + if (SysTick_CLKSource == SysTick_CLKSource_HCLK) + { + SysTick->CTRL |= SysTick_CLKSource_HCLK; + } + else + { + SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c new file mode 100644 index 000000000..d0206c3c7 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c @@ -0,0 +1,1742 @@ +/** + ****************************************************************************** + * @file stm32f4xx_adc.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Analog to Digital Convertor (ADC) peripheral: + * - Initialization and Configuration (in addition to ADC multi mode + * selection) + * - Analog Watchdog configuration + * - Temperature Sensor & Vrefint (Voltage Reference internal) & VBAT + * management + * - Regular Channels Configuration + * - Regular Channels DMA Configuration + * - Injected channels Configuration + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + + * 1. Enable the ADC interface clock using + * RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADCx, ENABLE); + * + * 2. ADC pins configuration + * - Enable the clock for the ADC GPIOs using the following function: + * RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE); + * - Configure these ADC pins in analog mode using GPIO_Init(); + * + * 3. Configure the ADC Prescaler, conversion resolution and data + * alignment using the ADC_Init() function. + * 4. Activate the ADC peripheral using ADC_Cmd() function. + * + * Regular channels group configuration + * ==================================== + * - To configure the ADC regular channels group features, use + * ADC_Init() and ADC_RegularChannelConfig() functions. + * - To activate the continuous mode, use the ADC_continuousModeCmd() + * function. + * - To configurate and activate the Discontinuous mode, use the + * ADC_DiscModeChannelCountConfig() and ADC_DiscModeCmd() functions. + * - To read the ADC converted values, use the ADC_GetConversionValue() + * function. + * + * Multi mode ADCs Regular channels configuration + * =============================================== + * - Refer to "Regular channels group configuration" description to + * configure the ADC1, ADC2 and ADC3 regular channels. + * - Select the Multi mode ADC regular channels features (dual or + * triple mode) using ADC_CommonInit() function and configure + * the DMA mode using ADC_MultiModeDMARequestAfterLastTransferCmd() + * functions. + * - Read the ADCs converted values using the + * ADC_GetMultiModeConversionValue() function. + * + * DMA for Regular channels group features configuration + * ====================================================== + * - To enable the DMA mode for regular channels group, use the + * ADC_DMACmd() function. + * - To enable the generation of DMA requests continuously at the end + * of the last DMA transfer, use the ADC_DMARequestAfterLastTransferCmd() + * function. + * + * Injected channels group configuration + * ===================================== + * - To configure the ADC Injected channels group features, use + * ADC_InjectedChannelConfig() and ADC_InjectedSequencerLengthConfig() + * functions. + * - To activate the continuous mode, use the ADC_continuousModeCmd() + * function. + * - To activate the Injected Discontinuous mode, use the + * ADC_InjectedDiscModeCmd() function. + * - To activate the AutoInjected mode, use the ADC_AutoInjectedConvCmd() + * function. + * - To read the ADC converted values, use the ADC_GetInjectedConversionValue() + * function. + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_adc.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup ADC + * @brief ADC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* ADC DISCNUM mask */ +#define CR1_DISCNUM_RESET ((uint32_t)0xFFFF1FFF) + +/* ADC AWDCH mask */ +#define CR1_AWDCH_RESET ((uint32_t)0xFFFFFFE0) + +/* ADC Analog watchdog enable mode mask */ +#define CR1_AWDMode_RESET ((uint32_t)0xFF3FFDFF) + +/* CR1 register Mask */ +#define CR1_CLEAR_MASK ((uint32_t)0xFCFFFEFF) + +/* ADC EXTEN mask */ +#define CR2_EXTEN_RESET ((uint32_t)0xCFFFFFFF) + +/* ADC JEXTEN mask */ +#define CR2_JEXTEN_RESET ((uint32_t)0xFFCFFFFF) + +/* ADC JEXTSEL mask */ +#define CR2_JEXTSEL_RESET ((uint32_t)0xFFF0FFFF) + +/* CR2 register Mask */ +#define CR2_CLEAR_MASK ((uint32_t)0xC0FFF7FD) + +/* ADC SQx mask */ +#define SQR3_SQ_SET ((uint32_t)0x0000001F) +#define SQR2_SQ_SET ((uint32_t)0x0000001F) +#define SQR1_SQ_SET ((uint32_t)0x0000001F) + +/* ADC L Mask */ +#define SQR1_L_RESET ((uint32_t)0xFF0FFFFF) + +/* ADC JSQx mask */ +#define JSQR_JSQ_SET ((uint32_t)0x0000001F) + +/* ADC JL mask */ +#define JSQR_JL_SET ((uint32_t)0x00300000) +#define JSQR_JL_RESET ((uint32_t)0xFFCFFFFF) + +/* ADC SMPx mask */ +#define SMPR1_SMP_SET ((uint32_t)0x00000007) +#define SMPR2_SMP_SET ((uint32_t)0x00000007) + +/* ADC JDRx registers offset */ +#define JDR_OFFSET ((uint8_t)0x28) + +/* ADC CDR register base address */ +#define CDR_ADDRESS ((uint32_t)0x40012308) + +/* ADC CCR register Mask */ +#define CR_CLEAR_MASK ((uint32_t)0xFFFC30E0) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup ADC_Private_Functions + * @{ + */ + +/** @defgroup ADC_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + This section provides functions allowing to: + - Initialize and configure the ADC Prescaler + - ADC Conversion Resolution (12bit..6bit) + - Scan Conversion Mode (multichannels or one channel) for regular group + - ADC Continuous Conversion Mode (Continuous or Single conversion) for + regular group + - External trigger Edge and source of regular group, + - Converted data alignment (left or right) + - The number of ADC conversions that will be done using the sequencer for + regular channel group + - Multi ADC mode selection + - Direct memory access mode selection for multi ADC mode + - Delay between 2 sampling phases (used in dual or triple interleaved modes) + - Enable or disable the ADC peripheral + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes all ADCs peripherals registers to their default reset + * values. + * @param None + * @retval None + */ +void ADC_DeInit(void) +{ + /* Enable all ADCs reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC, ENABLE); + + /* Release all ADCs from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC, DISABLE); +} + +/** + * @brief Initializes the ADCx peripheral according to the specified parameters + * in the ADC_InitStruct. + * @note This function is used to configure the global features of the ADC ( + * Resolution and Data Alignment), however, the rest of the configuration + * parameters are specific to the regular channels group (scan mode + * activation, continuous mode activation, External trigger source and + * edge, number of conversion in the regular channels group sequencer). + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InitStruct: pointer to an ADC_InitTypeDef structure that contains + * the configuration information for the specified ADC peripheral. + * @retval None + */ +void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct) +{ + uint32_t tmpreg1 = 0; + uint8_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_RESOLUTION(ADC_InitStruct->ADC_Resolution)); + assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ScanConvMode)); + assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG_EDGE(ADC_InitStruct->ADC_ExternalTrigConvEdge)); + assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConv)); + assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign)); + assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfConversion)); + + /*---------------------------- ADCx CR1 Configuration -----------------*/ + /* Get the ADCx CR1 value */ + tmpreg1 = ADCx->CR1; + + /* Clear RES and SCAN bits */ + tmpreg1 &= CR1_CLEAR_MASK; + + /* Configure ADCx: scan conversion mode and resolution */ + /* Set SCAN bit according to ADC_ScanConvMode value */ + /* Set RES bit according to ADC_Resolution value */ + tmpreg1 |= (uint32_t)(((uint32_t)ADC_InitStruct->ADC_ScanConvMode << 8) | \ + ADC_InitStruct->ADC_Resolution); + /* Write to ADCx CR1 */ + ADCx->CR1 = tmpreg1; + /*---------------------------- ADCx CR2 Configuration -----------------*/ + /* Get the ADCx CR2 value */ + tmpreg1 = ADCx->CR2; + + /* Clear CONT, ALIGN, EXTEN and EXTSEL bits */ + tmpreg1 &= CR2_CLEAR_MASK; + + /* Configure ADCx: external trigger event and edge, data alignment and + continuous conversion mode */ + /* Set ALIGN bit according to ADC_DataAlign value */ + /* Set EXTEN bits according to ADC_ExternalTrigConvEdge value */ + /* Set EXTSEL bits according to ADC_ExternalTrigConv value */ + /* Set CONT bit according to ADC_ContinuousConvMode value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_DataAlign | \ + ADC_InitStruct->ADC_ExternalTrigConv | + ADC_InitStruct->ADC_ExternalTrigConvEdge | \ + ((uint32_t)ADC_InitStruct->ADC_ContinuousConvMode << 1)); + + /* Write to ADCx CR2 */ + ADCx->CR2 = tmpreg1; + /*---------------------------- ADCx SQR1 Configuration -----------------*/ + /* Get the ADCx SQR1 value */ + tmpreg1 = ADCx->SQR1; + + /* Clear L bits */ + tmpreg1 &= SQR1_L_RESET; + + /* Configure ADCx: regular channel sequence length */ + /* Set L bits according to ADC_NbrOfConversion value */ + tmpreg2 |= (uint8_t)(ADC_InitStruct->ADC_NbrOfConversion - (uint8_t)1); + tmpreg1 |= ((uint32_t)tmpreg2 << 20); + + /* Write to ADCx SQR1 */ + ADCx->SQR1 = tmpreg1; +} + +/** + * @brief Fills each ADC_InitStruct member with its default value. + * @note This function is used to initialize the global features of the ADC ( + * Resolution and Data Alignment), however, the rest of the configuration + * parameters are specific to the regular channels group (scan mode + * activation, continuous mode activation, External trigger source and + * edge, number of conversion in the regular channels group sequencer). + * @param ADC_InitStruct: pointer to an ADC_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct) +{ + /* Initialize the ADC_Mode member */ + ADC_InitStruct->ADC_Resolution = ADC_Resolution_12b; + + /* initialize the ADC_ScanConvMode member */ + ADC_InitStruct->ADC_ScanConvMode = DISABLE; + + /* Initialize the ADC_ContinuousConvMode member */ + ADC_InitStruct->ADC_ContinuousConvMode = DISABLE; + + /* Initialize the ADC_ExternalTrigConvEdge member */ + ADC_InitStruct->ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None; + + /* Initialize the ADC_ExternalTrigConv member */ + ADC_InitStruct->ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1; + + /* Initialize the ADC_DataAlign member */ + ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right; + + /* Initialize the ADC_NbrOfConversion member */ + ADC_InitStruct->ADC_NbrOfConversion = 1; +} + +/** + * @brief Initializes the ADCs peripherals according to the specified parameters + * in the ADC_CommonInitStruct. + * @param ADC_CommonInitStruct: pointer to an ADC_CommonInitTypeDef structure + * that contains the configuration information for All ADCs peripherals. + * @retval None + */ +void ADC_CommonInit(ADC_CommonInitTypeDef* ADC_CommonInitStruct) +{ + uint32_t tmpreg1 = 0; + /* Check the parameters */ + assert_param(IS_ADC_MODE(ADC_CommonInitStruct->ADC_Mode)); + assert_param(IS_ADC_PRESCALER(ADC_CommonInitStruct->ADC_Prescaler)); + assert_param(IS_ADC_DMA_ACCESS_MODE(ADC_CommonInitStruct->ADC_DMAAccessMode)); + assert_param(IS_ADC_SAMPLING_DELAY(ADC_CommonInitStruct->ADC_TwoSamplingDelay)); + /*---------------------------- ADC CCR Configuration -----------------*/ + /* Get the ADC CCR value */ + tmpreg1 = ADC->CCR; + + /* Clear MULTI, DELAY, DMA and ADCPRE bits */ + tmpreg1 &= CR_CLEAR_MASK; + + /* Configure ADCx: Multi mode, Delay between two sampling time, ADC prescaler, + and DMA access mode for multimode */ + /* Set MULTI bits according to ADC_Mode value */ + /* Set ADCPRE bits according to ADC_Prescaler value */ + /* Set DMA bits according to ADC_DMAAccessMode value */ + /* Set DELAY bits according to ADC_TwoSamplingDelay value */ + tmpreg1 |= (uint32_t)(ADC_CommonInitStruct->ADC_Mode | + ADC_CommonInitStruct->ADC_Prescaler | + ADC_CommonInitStruct->ADC_DMAAccessMode | + ADC_CommonInitStruct->ADC_TwoSamplingDelay); + + /* Write to ADC CCR */ + ADC->CCR = tmpreg1; +} + +/** + * @brief Fills each ADC_CommonInitStruct member with its default value. + * @param ADC_CommonInitStruct: pointer to an ADC_CommonInitTypeDef structure + * which will be initialized. + * @retval None + */ +void ADC_CommonStructInit(ADC_CommonInitTypeDef* ADC_CommonInitStruct) +{ + /* Initialize the ADC_Mode member */ + ADC_CommonInitStruct->ADC_Mode = ADC_Mode_Independent; + + /* initialize the ADC_Prescaler member */ + ADC_CommonInitStruct->ADC_Prescaler = ADC_Prescaler_Div2; + + /* Initialize the ADC_DMAAccessMode member */ + ADC_CommonInitStruct->ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled; + + /* Initialize the ADC_TwoSamplingDelay member */ + ADC_CommonInitStruct->ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles; +} + +/** + * @brief Enables or disables the specified ADC peripheral. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the ADCx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the ADON bit to wake up the ADC from power down mode */ + ADCx->CR2 |= (uint32_t)ADC_CR2_ADON; + } + else + { + /* Disable the selected ADC peripheral */ + ADCx->CR2 &= (uint32_t)(~ADC_CR2_ADON); + } +} +/** + * @} + */ + +/** @defgroup ADC_Group2 Analog Watchdog configuration functions + * @brief Analog Watchdog configuration functions + * +@verbatim + =============================================================================== + Analog Watchdog configuration functions + =============================================================================== + + This section provides functions allowing to configure the Analog Watchdog + (AWD) feature in the ADC. + + A typical configuration Analog Watchdog is done following these steps : + 1. the ADC guarded channel(s) is (are) selected using the + ADC_AnalogWatchdogSingleChannelConfig() function. + 2. The Analog watchdog lower and higher threshold are configured using the + ADC_AnalogWatchdogThresholdsConfig() function. + 3. The Analog watchdog is enabled and configured to enable the check, on one + or more channels, using the ADC_AnalogWatchdogCmd() function. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the analog watchdog on single/all regular or + * injected channels + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_AnalogWatchdog: the ADC analog watchdog configuration. + * This parameter can be one of the following values: + * @arg ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on a single regular channel + * @arg ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on a single injected channel + * @arg ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog watchdog on a single regular or injected channel + * @arg ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on all regular channel + * @arg ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on all injected channel + * @arg ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog on all regular and injected channels + * @arg ADC_AnalogWatchdog_None: No channel guarded by the analog watchdog + * @retval None + */ +void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog)); + + /* Get the old register value */ + tmpreg = ADCx->CR1; + + /* Clear AWDEN, JAWDEN and AWDSGL bits */ + tmpreg &= CR1_AWDMode_RESET; + + /* Set the analog watchdog enable mode */ + tmpreg |= ADC_AnalogWatchdog; + + /* Store the new register value */ + ADCx->CR1 = tmpreg; +} + +/** + * @brief Configures the high and low thresholds of the analog watchdog. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param HighThreshold: the ADC analog watchdog High threshold value. + * This parameter must be a 12-bit value. + * @param LowThreshold: the ADC analog watchdog Low threshold value. + * This parameter must be a 12-bit value. + * @retval None + */ +void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, + uint16_t LowThreshold) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_THRESHOLD(HighThreshold)); + assert_param(IS_ADC_THRESHOLD(LowThreshold)); + + /* Set the ADCx high threshold */ + ADCx->HTR = HighThreshold; + + /* Set the ADCx low threshold */ + ADCx->LTR = LowThreshold; +} + +/** + * @brief Configures the analog watchdog guarded single channel + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure for the analog watchdog. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @retval None + */ +void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + + /* Get the old register value */ + tmpreg = ADCx->CR1; + + /* Clear the Analog watchdog channel select bits */ + tmpreg &= CR1_AWDCH_RESET; + + /* Set the Analog watchdog channel */ + tmpreg |= ADC_Channel; + + /* Store the new register value */ + ADCx->CR1 = tmpreg; +} +/** + * @} + */ + +/** @defgroup ADC_Group3 Temperature Sensor, Vrefint (Voltage Reference internal) + * and VBAT (Voltage BATtery) management functions + * @brief Temperature Sensor, Vrefint and VBAT management functions + * +@verbatim + =============================================================================== + Temperature Sensor, Vrefint and VBAT management functions + =============================================================================== + + This section provides functions allowing to enable/ disable the internal + connections between the ADC and the Temperature Sensor, the Vrefint and the + Vbat sources. + + A typical configuration to get the Temperature sensor and Vrefint channels + voltages is done following these steps : + 1. Enable the internal connection of Temperature sensor and Vrefint sources + with the ADC channels using ADC_TempSensorVrefintCmd() function. + 2. Select the ADC_Channel_TempSensor and/or ADC_Channel_Vrefint using + ADC_RegularChannelConfig() or ADC_InjectedChannelConfig() functions + 3. Get the voltage values, using ADC_GetConversionValue() or + ADC_GetInjectedConversionValue(). + + A typical configuration to get the VBAT channel voltage is done following + these steps : + 1. Enable the internal connection of VBAT source with the ADC channel using + ADC_VBATCmd() function. + 2. Select the ADC_Channel_Vbat using ADC_RegularChannelConfig() or + ADC_InjectedChannelConfig() functions + 3. Get the voltage value, using ADC_GetConversionValue() or + ADC_GetInjectedConversionValue(). + +@endverbatim + * @{ + */ + + +/** + * @brief Enables or disables the temperature sensor and Vrefint channels. + * @param NewState: new state of the temperature sensor and Vrefint channels. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_TempSensorVrefintCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the temperature sensor and Vrefint channel*/ + ADC->CCR |= (uint32_t)ADC_CCR_TSVREFE; + } + else + { + /* Disable the temperature sensor and Vrefint channel*/ + ADC->CCR &= (uint32_t)(~ADC_CCR_TSVREFE); + } +} + +/** + * @brief Enables or disables the VBAT (Voltage Battery) channel. + * @param NewState: new state of the VBAT channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_VBATCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the VBAT channel*/ + ADC->CCR |= (uint32_t)ADC_CCR_VBATE; + } + else + { + /* Disable the VBAT channel*/ + ADC->CCR &= (uint32_t)(~ADC_CCR_VBATE); + } +} + +/** + * @} + */ + +/** @defgroup ADC_Group4 Regular Channels Configuration functions + * @brief Regular Channels Configuration functions + * +@verbatim + =============================================================================== + Regular Channels Configuration functions + =============================================================================== + + This section provides functions allowing to manage the ADC's regular channels, + it is composed of 2 sub sections : + + 1. Configuration and management functions for regular channels: This subsection + provides functions allowing to configure the ADC regular channels : + - Configure the rank in the regular group sequencer for each channel + - Configure the sampling time for each channel + - select the conversion Trigger for regular channels + - select the desired EOC event behavior configuration + - Activate the continuous Mode (*) + - Activate the Discontinuous Mode + Please Note that the following features for regular channels are configurated + using the ADC_Init() function : + - scan mode activation + - continuous mode activation (**) + - External trigger source + - External trigger edge + - number of conversion in the regular channels group sequencer. + + @note (*) and (**) are performing the same configuration + + 2. Get the conversion data: This subsection provides an important function in + the ADC peripheral since it returns the converted data of the current + regular channel. When the Conversion value is read, the EOC Flag is + automatically cleared. + + @note For multi ADC mode, the last ADC1, ADC2 and ADC3 regular conversions + results data (in the selected multi mode) can be returned in the same + time using ADC_GetMultiModeConversionValue() function. + + +@endverbatim + * @{ + */ +/** + * @brief Configures for the selected ADC regular channel its corresponding + * rank in the sequencer and its sample time. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @param Rank: The rank in the regular group sequencer. + * This parameter must be between 1 to 16. + * @param ADC_SampleTime: The sample time value to be set for the selected channel. + * This parameter can be one of the following values: + * @arg ADC_SampleTime_3Cycles: Sample time equal to 3 cycles + * @arg ADC_SampleTime_15Cycles: Sample time equal to 15 cycles + * @arg ADC_SampleTime_28Cycles: Sample time equal to 28 cycles + * @arg ADC_SampleTime_56Cycles: Sample time equal to 56 cycles + * @arg ADC_SampleTime_84Cycles: Sample time equal to 84 cycles + * @arg ADC_SampleTime_112Cycles: Sample time equal to 112 cycles + * @arg ADC_SampleTime_144Cycles: Sample time equal to 144 cycles + * @arg ADC_SampleTime_480Cycles: Sample time equal to 480 cycles + * @retval None + */ +void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_REGULAR_RANK(Rank)); + assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + + /* if ADC_Channel_10 ... ADC_Channel_18 is selected */ + if (ADC_Channel > ADC_Channel_9) + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR1; + + /* Calculate the mask to clear */ + tmpreg2 = SMPR1_SMP_SET << (3 * (ADC_Channel - 10)); + + /* Clear the old sample time */ + tmpreg1 &= ~tmpreg2; + + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10)); + + /* Set the new sample time */ + tmpreg1 |= tmpreg2; + + /* Store the new register value */ + ADCx->SMPR1 = tmpreg1; + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR2; + + /* Calculate the mask to clear */ + tmpreg2 = SMPR2_SMP_SET << (3 * ADC_Channel); + + /* Clear the old sample time */ + tmpreg1 &= ~tmpreg2; + + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); + + /* Set the new sample time */ + tmpreg1 |= tmpreg2; + + /* Store the new register value */ + ADCx->SMPR2 = tmpreg1; + } + /* For Rank 1 to 6 */ + if (Rank < 7) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR3; + + /* Calculate the mask to clear */ + tmpreg2 = SQR3_SQ_SET << (5 * (Rank - 1)); + + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 1)); + + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + + /* Store the new register value */ + ADCx->SQR3 = tmpreg1; + } + /* For Rank 7 to 12 */ + else if (Rank < 13) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR2; + + /* Calculate the mask to clear */ + tmpreg2 = SQR2_SQ_SET << (5 * (Rank - 7)); + + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 7)); + + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + + /* Store the new register value */ + ADCx->SQR2 = tmpreg1; + } + /* For Rank 13 to 16 */ + else + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR1; + + /* Calculate the mask to clear */ + tmpreg2 = SQR1_SQ_SET << (5 * (Rank - 13)); + + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 13)); + + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + + /* Store the new register value */ + ADCx->SQR1 = tmpreg1; + } +} + +/** + * @brief Enables the selected ADC software start conversion of the regular channels. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_SoftwareStartConv(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Enable the selected ADC conversion for regular group */ + ADCx->CR2 |= (uint32_t)ADC_CR2_SWSTART; +} + +/** + * @brief Gets the selected ADC Software start regular conversion Status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC software start conversion (SET or RESET). + */ +FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Check the status of SWSTART bit */ + if ((ADCx->CR2 & ADC_CR2_JSWSTART) != (uint32_t)RESET) + { + /* SWSTART bit is set */ + bitstatus = SET; + } + else + { + /* SWSTART bit is reset */ + bitstatus = RESET; + } + + /* Return the SWSTART bit status */ + return bitstatus; +} + + +/** + * @brief Enables or disables the EOC on each regular channel conversion + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC EOC flag rising + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_EOCOnEachRegularChannelCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected ADC EOC rising on each regular channel conversion */ + ADCx->CR2 |= (uint32_t)ADC_CR2_EOCS; + } + else + { + /* Disable the selected ADC EOC rising on each regular channel conversion */ + ADCx->CR2 &= (uint32_t)(~ADC_CR2_EOCS); + } +} + +/** + * @brief Enables or disables the ADC continuous conversion mode + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC continuous conversion mode + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ContinuousModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected ADC continuous conversion mode */ + ADCx->CR2 |= (uint32_t)ADC_CR2_CONT; + } + else + { + /* Disable the selected ADC continuous conversion mode */ + ADCx->CR2 &= (uint32_t)(~ADC_CR2_CONT); + } +} + +/** + * @brief Configures the discontinuous mode for the selected ADC regular group + * channel. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param Number: specifies the discontinuous mode regular channel count value. + * This number must be between 1 and 8. + * @retval None + */ +void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number)); + + /* Get the old register value */ + tmpreg1 = ADCx->CR1; + + /* Clear the old discontinuous mode channel count */ + tmpreg1 &= CR1_DISCNUM_RESET; + + /* Set the discontinuous mode channel count */ + tmpreg2 = Number - 1; + tmpreg1 |= tmpreg2 << 13; + + /* Store the new register value */ + ADCx->CR1 = tmpreg1; +} + +/** + * @brief Enables or disables the discontinuous mode on regular group channel + * for the specified ADC + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC discontinuous mode on + * regular group channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected ADC regular discontinuous mode */ + ADCx->CR1 |= (uint32_t)ADC_CR1_DISCEN; + } + else + { + /* Disable the selected ADC regular discontinuous mode */ + ADCx->CR1 &= (uint32_t)(~ADC_CR1_DISCEN); + } +} + +/** + * @brief Returns the last ADCx conversion result data for regular channel. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The Data conversion value. + */ +uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Return the selected ADC conversion value */ + return (uint16_t) ADCx->DR; +} + +/** + * @brief Returns the last ADC1, ADC2 and ADC3 regular conversions results + * data in the selected multi mode. + * @param None + * @retval The Data conversion value. + * @note In dual mode, the value returned by this function is as following + * Data[15:0] : these bits contain the regular data of ADC1. + * Data[31:16]: these bits contain the regular data of ADC2. + * @note In triple mode, the value returned by this function is as following + * Data[15:0] : these bits contain alternatively the regular data of ADC1, ADC3 and ADC2. + * Data[31:16]: these bits contain alternatively the regular data of ADC2, ADC1 and ADC3. + */ +uint32_t ADC_GetMultiModeConversionValue(void) +{ + /* Return the multi mode conversion value */ + return (*(__IO uint32_t *) CDR_ADDRESS); +} +/** + * @} + */ + +/** @defgroup ADC_Group5 Regular Channels DMA Configuration functions + * @brief Regular Channels DMA Configuration functions + * +@verbatim + =============================================================================== + Regular Channels DMA Configuration functions + =============================================================================== + + This section provides functions allowing to configure the DMA for ADC regular + channels. + Since converted regular channel values are stored into a unique data register, + it is useful to use DMA for conversion of more than one regular channel. This + avoids the loss of the data already stored in the ADC Data register. + + When the DMA mode is enabled (using the ADC_DMACmd() function), after each + conversion of a regular channel, a DMA request is generated. + + Depending on the "DMA disable selection for Independent ADC mode" + configuration (using the ADC_DMARequestAfterLastTransferCmd() function), + at the end of the last DMA transfer, two possibilities are allowed: + - No new DMA request is issued to the DMA controller (feature DISABLED) + - Requests can continue to be generated (feature ENABLED). + + Depending on the "DMA disable selection for multi ADC mode" configuration + (using the void ADC_MultiModeDMARequestAfterLastTransferCmd() function), + at the end of the last DMA transfer, two possibilities are allowed: + - No new DMA request is issued to the DMA controller (feature DISABLED) + - Requests can continue to be generated (feature ENABLED). + +@endverbatim + * @{ + */ + + /** + * @brief Enables or disables the specified ADC DMA request. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC DMA transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC DMA request */ + ADCx->CR2 |= (uint32_t)ADC_CR2_DMA; + } + else + { + /* Disable the selected ADC DMA request */ + ADCx->CR2 &= (uint32_t)(~ADC_CR2_DMA); + } +} + +/** + * @brief Enables or disables the ADC DMA request after last transfer (Single-ADC mode) + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC DMA request after last transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DMARequestAfterLastTransferCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC DMA request after last transfer */ + ADCx->CR2 |= (uint32_t)ADC_CR2_DDS; + } + else + { + /* Disable the selected ADC DMA request after last transfer */ + ADCx->CR2 &= (uint32_t)(~ADC_CR2_DDS); + } +} + +/** + * @brief Enables or disables the ADC DMA request after last transfer in multi ADC mode + * @param NewState: new state of the selected ADC DMA request after last transfer. + * This parameter can be: ENABLE or DISABLE. + * @note if Enabled, DMA requests are issued as long as data are converted and + * DMA mode for multi ADC mode (selected using ADC_CommonInit() function + * by ADC_CommonInitStruct.ADC_DMAAccessMode structure member) is + * ADC_DMAAccessMode_1, ADC_DMAAccessMode_2 or ADC_DMAAccessMode_3. + * @retval None + */ +void ADC_MultiModeDMARequestAfterLastTransferCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC DMA request after last transfer */ + ADC->CCR |= (uint32_t)ADC_CCR_DDS; + } + else + { + /* Disable the selected ADC DMA request after last transfer */ + ADC->CCR &= (uint32_t)(~ADC_CCR_DDS); + } +} +/** + * @} + */ + +/** @defgroup ADC_Group6 Injected channels Configuration functions + * @brief Injected channels Configuration functions + * +@verbatim + =============================================================================== + Injected channels Configuration functions + =============================================================================== + + This section provide functions allowing to configure the ADC Injected channels, + it is composed of 2 sub sections : + + 1. Configuration functions for Injected channels: This subsection provides + functions allowing to configure the ADC injected channels : + - Configure the rank in the injected group sequencer for each channel + - Configure the sampling time for each channel + - Activate the Auto injected Mode + - Activate the Discontinuous Mode + - scan mode activation + - External/software trigger source + - External trigger edge + - injected channels sequencer. + + 2. Get the Specified Injected channel conversion data: This subsection + provides an important function in the ADC peripheral since it returns the + converted data of the specific injected channel. + +@endverbatim + * @{ + */ +/** + * @brief Configures for the selected ADC injected channel its corresponding + * rank in the sequencer and its sample time. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @param Rank: The rank in the injected group sequencer. + * This parameter must be between 1 to 4. + * @param ADC_SampleTime: The sample time value to be set for the selected channel. + * This parameter can be one of the following values: + * @arg ADC_SampleTime_3Cycles: Sample time equal to 3 cycles + * @arg ADC_SampleTime_15Cycles: Sample time equal to 15 cycles + * @arg ADC_SampleTime_28Cycles: Sample time equal to 28 cycles + * @arg ADC_SampleTime_56Cycles: Sample time equal to 56 cycles + * @arg ADC_SampleTime_84Cycles: Sample time equal to 84 cycles + * @arg ADC_SampleTime_112Cycles: Sample time equal to 112 cycles + * @arg ADC_SampleTime_144Cycles: Sample time equal to 144 cycles + * @arg ADC_SampleTime_480Cycles: Sample time equal to 480 cycles + * @retval None + */ +void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_INJECTED_RANK(Rank)); + assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + /* if ADC_Channel_10 ... ADC_Channel_18 is selected */ + if (ADC_Channel > ADC_Channel_9) + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR1; + /* Calculate the mask to clear */ + tmpreg2 = SMPR1_SMP_SET << (3*(ADC_Channel - 10)); + /* Clear the old sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3*(ADC_Channel - 10)); + /* Set the new sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR1 = tmpreg1; + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR2; + /* Calculate the mask to clear */ + tmpreg2 = SMPR2_SMP_SET << (3 * ADC_Channel); + /* Clear the old sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); + /* Set the new sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR2 = tmpreg1; + } + /* Rank configuration */ + /* Get the old register value */ + tmpreg1 = ADCx->JSQR; + /* Get JL value: Number = JL+1 */ + tmpreg3 = (tmpreg1 & JSQR_JL_SET)>> 20; + /* Calculate the mask to clear: ((Rank-1)+(4-JL-1)) */ + tmpreg2 = JSQR_JSQ_SET << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1))); + /* Clear the old JSQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set: ((Rank-1)+(4-JL-1)) */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1))); + /* Set the JSQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->JSQR = tmpreg1; +} + +/** + * @brief Configures the sequencer length for injected channels + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param Length: The sequencer length. + * This parameter must be a number between 1 to 4. + * @retval None + */ +void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_LENGTH(Length)); + + /* Get the old register value */ + tmpreg1 = ADCx->JSQR; + + /* Clear the old injected sequence length JL bits */ + tmpreg1 &= JSQR_JL_RESET; + + /* Set the injected sequence length JL bits */ + tmpreg2 = Length - 1; + tmpreg1 |= tmpreg2 << 20; + + /* Store the new register value */ + ADCx->JSQR = tmpreg1; +} + +/** + * @brief Set the injected channels conversion value offset + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InjectedChannel: the ADC injected channel to set its offset. + * This parameter can be one of the following values: + * @arg ADC_InjectedChannel_1: Injected Channel1 selected + * @arg ADC_InjectedChannel_2: Injected Channel2 selected + * @arg ADC_InjectedChannel_3: Injected Channel3 selected + * @arg ADC_InjectedChannel_4: Injected Channel4 selected + * @param Offset: the offset value for the selected ADC injected channel + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset) +{ + __IO uint32_t tmp = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); + assert_param(IS_ADC_OFFSET(Offset)); + + tmp = (uint32_t)ADCx; + tmp += ADC_InjectedChannel; + + /* Set the selected injected channel data offset */ + *(__IO uint32_t *) tmp = (uint32_t)Offset; +} + + /** + * @brief Configures the ADCx external trigger for injected channels conversion. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_ExternalTrigInjecConv: specifies the ADC trigger to start injected conversion. + * This parameter can be one of the following values: + * @arg ADC_ExternalTrigInjecConv_T1_CC4: Timer1 capture compare4 selected + * @arg ADC_ExternalTrigInjecConv_T1_TRGO: Timer1 TRGO event selected + * @arg ADC_ExternalTrigInjecConv_T2_CC1: Timer2 capture compare1 selected + * @arg ADC_ExternalTrigInjecConv_T2_TRGO: Timer2 TRGO event selected + * @arg ADC_ExternalTrigInjecConv_T3_CC2: Timer3 capture compare2 selected + * @arg ADC_ExternalTrigInjecConv_T3_CC4: Timer3 capture compare4 selected + * @arg ADC_ExternalTrigInjecConv_T4_CC1: Timer4 capture compare1 selected + * @arg ADC_ExternalTrigInjecConv_T4_CC2: Timer4 capture compare2 selected + * @arg ADC_ExternalTrigInjecConv_T4_CC3: Timer4 capture compare3 selected + * @arg ADC_ExternalTrigInjecConv_T4_TRGO: Timer4 TRGO event selected + * @arg ADC_ExternalTrigInjecConv_T5_CC4: Timer5 capture compare4 selected + * @arg ADC_ExternalTrigInjecConv_T5_TRGO: Timer5 TRGO event selected + * @arg ADC_ExternalTrigInjecConv_T8_CC2: Timer8 capture compare2 selected + * @arg ADC_ExternalTrigInjecConv_T8_CC3: Timer8 capture compare3 selected + * @arg ADC_ExternalTrigInjecConv_T8_CC4: Timer8 capture compare4 selected + * @arg ADC_ExternalTrigInjecConv_Ext_IT15: External interrupt line 15 event selected + * @retval None + */ +void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_ExternalTrigInjecConv)); + + /* Get the old register value */ + tmpreg = ADCx->CR2; + + /* Clear the old external event selection for injected group */ + tmpreg &= CR2_JEXTSEL_RESET; + + /* Set the external event selection for injected group */ + tmpreg |= ADC_ExternalTrigInjecConv; + + /* Store the new register value */ + ADCx->CR2 = tmpreg; +} + +/** + * @brief Configures the ADCx external trigger edge for injected channels conversion. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_ExternalTrigInjecConvEdge: specifies the ADC external trigger edge + * to start injected conversion. + * This parameter can be one of the following values: + * @arg ADC_ExternalTrigInjecConvEdge_None: external trigger disabled for + * injected conversion + * @arg ADC_ExternalTrigInjecConvEdge_Rising: detection on rising edge + * @arg ADC_ExternalTrigInjecConvEdge_Falling: detection on falling edge + * @arg ADC_ExternalTrigInjecConvEdge_RisingFalling: detection on both rising + * and falling edge + * @retval None + */ +void ADC_ExternalTrigInjectedConvEdgeConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConvEdge) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_EXT_INJEC_TRIG_EDGE(ADC_ExternalTrigInjecConvEdge)); + /* Get the old register value */ + tmpreg = ADCx->CR2; + /* Clear the old external trigger edge for injected group */ + tmpreg &= CR2_JEXTEN_RESET; + /* Set the new external trigger edge for injected group */ + tmpreg |= ADC_ExternalTrigInjecConvEdge; + /* Store the new register value */ + ADCx->CR2 = tmpreg; +} + +/** + * @brief Enables the selected ADC software start conversion of the injected channels. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_SoftwareStartInjectedConv(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Enable the selected ADC conversion for injected group */ + ADCx->CR2 |= (uint32_t)ADC_CR2_JSWSTART; +} + +/** + * @brief Gets the selected ADC Software start injected conversion Status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC software start injected conversion (SET or RESET). + */ +FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Check the status of JSWSTART bit */ + if ((ADCx->CR2 & ADC_CR2_JSWSTART) != (uint32_t)RESET) + { + /* JSWSTART bit is set */ + bitstatus = SET; + } + else + { + /* JSWSTART bit is reset */ + bitstatus = RESET; + } + /* Return the JSWSTART bit status */ + return bitstatus; +} + +/** + * @brief Enables or disables the selected ADC automatic injected group + * conversion after regular one. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC auto injected conversion + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC automatic injected group conversion */ + ADCx->CR1 |= (uint32_t)ADC_CR1_JAUTO; + } + else + { + /* Disable the selected ADC automatic injected group conversion */ + ADCx->CR1 &= (uint32_t)(~ADC_CR1_JAUTO); + } +} + +/** + * @brief Enables or disables the discontinuous mode for injected group + * channel for the specified ADC + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC discontinuous mode on injected + * group channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC injected discontinuous mode */ + ADCx->CR1 |= (uint32_t)ADC_CR1_JDISCEN; + } + else + { + /* Disable the selected ADC injected discontinuous mode */ + ADCx->CR1 &= (uint32_t)(~ADC_CR1_JDISCEN); + } +} + +/** + * @brief Returns the ADC injected channel conversion result + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InjectedChannel: the converted ADC injected channel. + * This parameter can be one of the following values: + * @arg ADC_InjectedChannel_1: Injected Channel1 selected + * @arg ADC_InjectedChannel_2: Injected Channel2 selected + * @arg ADC_InjectedChannel_3: Injected Channel3 selected + * @arg ADC_InjectedChannel_4: Injected Channel4 selected + * @retval The Data conversion value. + */ +uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); + + tmp = (uint32_t)ADCx; + tmp += ADC_InjectedChannel + JDR_OFFSET; + + /* Returns the selected injected channel conversion data value */ + return (uint16_t) (*(__IO uint32_t*) tmp); +} +/** + * @} + */ + +/** @defgroup ADC_Group7 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + + This section provides functions allowing to configure the ADC Interrupts and + to get the status and clear flags and Interrupts pending bits. + + Each ADC provides 4 Interrupts sources and 6 Flags which can be divided into + 3 groups: + + I. Flags and Interrupts for ADC regular channels + ================================================= + Flags : + ---------- + 1. ADC_FLAG_OVR : Overrun detection when regular converted data are lost + + 2. ADC_FLAG_EOC : Regular channel end of conversion ==> to indicate (depending + on EOCS bit, managed by ADC_EOCOnEachRegularChannelCmd() ) the end of: + ==> a regular CHANNEL conversion + ==> sequence of regular GROUP conversions . + + 3. ADC_FLAG_STRT: Regular channel start ==> to indicate when regular CHANNEL + conversion starts. + + Interrupts : + ------------ + 1. ADC_IT_OVR : specifies the interrupt source for Overrun detection event. + 2. ADC_IT_EOC : specifies the interrupt source for Regular channel end of + conversion event. + + + II. Flags and Interrupts for ADC Injected channels + ================================================= + Flags : + ---------- + 1. ADC_FLAG_JEOC : Injected channel end of conversion ==> to indicate at + the end of injected GROUP conversion + + 2. ADC_FLAG_JSTRT: Injected channel start ==> to indicate hardware when + injected GROUP conversion starts. + + Interrupts : + ------------ + 1. ADC_IT_JEOC : specifies the interrupt source for Injected channel end of + conversion event. + + III. General Flags and Interrupts for the ADC + ================================================= + Flags : + ---------- + 1. ADC_FLAG_AWD: Analog watchdog ==> to indicate if the converted voltage + crosses the programmed thresholds values. + + Interrupts : + ------------ + 1. ADC_IT_AWD : specifies the interrupt source for Analog watchdog event. + + + The user should identify which mode will be used in his application to manage + the ADC controller events: Polling mode or Interrupt mode. + + In the Polling Mode it is advised to use the following functions: + - ADC_GetFlagStatus() : to check if flags events occur. + - ADC_ClearFlag() : to clear the flags events. + + In the Interrupt Mode it is advised to use the following functions: + - ADC_ITConfig() : to enable or disable the interrupt source. + - ADC_GetITStatus() : to check if Interrupt occurs. + - ADC_ClearITPendingBit() : to clear the Interrupt pending Bit + (corresponding Flag). +@endverbatim + * @{ + */ +/** + * @brief Enables or disables the specified ADC interrupts. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt sources to be enabled or disabled. + * This parameter can be one of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @arg ADC_IT_OVR: Overrun interrupt enable + * @param NewState: new state of the specified ADC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState) +{ + uint32_t itmask = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_ADC_IT(ADC_IT)); + + /* Get the ADC IT index */ + itmask = (uint8_t)ADC_IT; + itmask = (uint32_t)0x01 << itmask; + + if (NewState != DISABLE) + { + /* Enable the selected ADC interrupts */ + ADCx->CR1 |= itmask; + } + else + { + /* Disable the selected ADC interrupts */ + ADCx->CR1 &= (~(uint32_t)itmask); + } +} + +/** + * @brief Checks whether the specified ADC flag is set or not. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg ADC_FLAG_AWD: Analog watchdog flag + * @arg ADC_FLAG_EOC: End of conversion flag + * @arg ADC_FLAG_JEOC: End of injected group conversion flag + * @arg ADC_FLAG_JSTRT: Start of injected group conversion flag + * @arg ADC_FLAG_STRT: Start of regular group conversion flag + * @arg ADC_FLAG_OVR: Overrun flag + * @retval The new state of ADC_FLAG (SET or RESET). + */ +FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_GET_FLAG(ADC_FLAG)); + + /* Check the status of the specified ADC flag */ + if ((ADCx->SR & ADC_FLAG) != (uint8_t)RESET) + { + /* ADC_FLAG is set */ + bitstatus = SET; + } + else + { + /* ADC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the ADC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the ADCx's pending flags. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg ADC_FLAG_AWD: Analog watchdog flag + * @arg ADC_FLAG_EOC: End of conversion flag + * @arg ADC_FLAG_JEOC: End of injected group conversion flag + * @arg ADC_FLAG_JSTRT: Start of injected group conversion flag + * @arg ADC_FLAG_STRT: Start of regular group conversion flag + * @arg ADC_FLAG_OVR: Overrun flag + * @retval None + */ +void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG)); + + /* Clear the selected ADC flags */ + ADCx->SR = ~(uint32_t)ADC_FLAG; +} + +/** + * @brief Checks whether the specified ADC interrupt has occurred or not. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt source to check. + * This parameter can be one of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @arg ADC_IT_OVR: Overrun interrupt mask + * @retval The new state of ADC_IT (SET or RESET). + */ +ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t itmask = 0, enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_IT(ADC_IT)); + + /* Get the ADC IT index */ + itmask = ADC_IT >> 8; + + /* Get the ADC_IT enable bit status */ + enablestatus = (ADCx->CR1 & ((uint32_t)0x01 << (uint8_t)ADC_IT)) ; + + /* Check the status of the specified ADC interrupt */ + if (((ADCx->SR & itmask) != (uint32_t)RESET) && enablestatus) + { + /* ADC_IT is set */ + bitstatus = SET; + } + else + { + /* ADC_IT is reset */ + bitstatus = RESET; + } + /* Return the ADC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the ADCx's interrupt pending bits. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt pending bit to clear. + * This parameter can be one of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @arg ADC_IT_OVR: Overrun interrupt mask + * @retval None + */ +void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT) +{ + uint8_t itmask = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_IT(ADC_IT)); + /* Get the ADC IT index */ + itmask = (uint8_t)(ADC_IT >> 8); + /* Clear the selected ADC interrupt pending bits */ + ADCx->SR = ~(uint32_t)itmask; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_can.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_can.c new file mode 100644 index 000000000..8543ab8b5 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_can.c @@ -0,0 +1,1698 @@ +/** + ****************************************************************************** + * @file stm32f4xx_can.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Controller area network (CAN) peripheral: + * - Initialization and Configuration + * - CAN Frames Transmission + * - CAN Frames Reception + * - Operation modes switch + * - Error management + * - Interrupts and flags + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + + * 1. Enable the CAN controller interface clock using + * RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1, ENABLE); for CAN1 + * and RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN2, ENABLE); for CAN2 + * @note In case you are using CAN2 only, you have to enable the CAN1 clock. + * + * 2. CAN pins configuration + * - Enable the clock for the CAN GPIOs using the following function: + * RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE); + * - Connect the involved CAN pins to AF9 using the following function + * GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_CANx); + * - Configure these CAN pins in alternate function mode by calling + * the function GPIO_Init(); + * + * 3. Initialise and configure the CAN using CAN_Init() and + * CAN_FilterInit() functions. + * + * 4. Transmit the desired CAN frame using CAN_Transmit() function. + * + * 5. Check the transmission of a CAN frame using CAN_TransmitStatus() + * function. + * + * 6. Cancel the transmission of a CAN frame using CAN_CancelTransmit() + * function. + * + * 7. Receive a CAN frame using CAN_Recieve() function. + * + * 8. Release the receive FIFOs using CAN_FIFORelease() function. + * + * 9. Return the number of pending received frames using + * CAN_MessagePending() function. + * + * 10. To control CAN events you can use one of the following two methods: + * - Check on CAN flags using the CAN_GetFlagStatus() function. + * - Use CAN interrupts through the function CAN_ITConfig() at + * initialization phase and CAN_GetITStatus() function into + * interrupt routines to check if the event has occurred or not. + * After checking on a flag you should clear it using CAN_ClearFlag() + * function. And after checking on an interrupt event you should + * clear it using CAN_ClearITPendingBit() function. + * + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_can.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup CAN + * @brief CAN driver modules + * @{ + */ +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* CAN Master Control Register bits */ +#define MCR_DBF ((uint32_t)0x00010000) /* software master reset */ + +/* CAN Mailbox Transmit Request */ +#define TMIDxR_TXRQ ((uint32_t)0x00000001) /* Transmit mailbox request */ + +/* CAN Filter Master Register bits */ +#define FMR_FINIT ((uint32_t)0x00000001) /* Filter init mode */ + +/* Time out for INAK bit */ +#define INAK_TIMEOUT ((uint32_t)0x0000FFFF) +/* Time out for SLAK bit */ +#define SLAK_TIMEOUT ((uint32_t)0x0000FFFF) + +/* Flags in TSR register */ +#define CAN_FLAGS_TSR ((uint32_t)0x08000000) +/* Flags in RF1R register */ +#define CAN_FLAGS_RF1R ((uint32_t)0x04000000) +/* Flags in RF0R register */ +#define CAN_FLAGS_RF0R ((uint32_t)0x02000000) +/* Flags in MSR register */ +#define CAN_FLAGS_MSR ((uint32_t)0x01000000) +/* Flags in ESR register */ +#define CAN_FLAGS_ESR ((uint32_t)0x00F00000) + +/* Mailboxes definition */ +#define CAN_TXMAILBOX_0 ((uint8_t)0x00) +#define CAN_TXMAILBOX_1 ((uint8_t)0x01) +#define CAN_TXMAILBOX_2 ((uint8_t)0x02) + +#define CAN_MODE_MASK ((uint32_t) 0x00000003) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit); + +/** @defgroup CAN_Private_Functions + * @{ + */ + +/** @defgroup CAN_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + This section provides functions allowing to + - Initialize the CAN peripherals : Prescaler, operating mode, the maximum number + of time quanta to perform resynchronization, the number of time quanta in + Bit Segment 1 and 2 and many other modes. + Refer to @ref CAN_InitTypeDef for more details. + - Configures the CAN reception filter. + - Select the start bank filter for slave CAN. + - Enables or disables the Debug Freeze mode for CAN + - Enables or disables the CAN Time Trigger Operation communication mode + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the CAN peripheral registers to their default reset values. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @retval None. + */ +void CAN_DeInit(CAN_TypeDef* CANx) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + if (CANx == CAN1) + { + /* Enable CAN1 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, ENABLE); + /* Release CAN1 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, DISABLE); + } + else + { + /* Enable CAN2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, ENABLE); + /* Release CAN2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, DISABLE); + } +} + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_InitStruct. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure that contains + * the configuration information for the CAN peripheral. + * @retval Constant indicates initialization succeed which will be + * CAN_InitStatus_Failed or CAN_InitStatus_Success. + */ +uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct) +{ + uint8_t InitStatus = CAN_InitStatus_Failed; + uint32_t wait_ack = 0x00000000; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TTCM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_ABOM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_AWUM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_NART)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_RFLM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TXFP)); + assert_param(IS_CAN_MODE(CAN_InitStruct->CAN_Mode)); + assert_param(IS_CAN_SJW(CAN_InitStruct->CAN_SJW)); + assert_param(IS_CAN_BS1(CAN_InitStruct->CAN_BS1)); + assert_param(IS_CAN_BS2(CAN_InitStruct->CAN_BS2)); + assert_param(IS_CAN_PRESCALER(CAN_InitStruct->CAN_Prescaler)); + + /* Exit from sleep mode */ + CANx->MCR &= (~(uint32_t)CAN_MCR_SLEEP); + + /* Request initialisation */ + CANx->MCR |= CAN_MCR_INRQ ; + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) + { + wait_ack++; + } + + /* Check acknowledge */ + if ((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) + { + InitStatus = CAN_InitStatus_Failed; + } + else + { + /* Set the time triggered communication mode */ + if (CAN_InitStruct->CAN_TTCM == ENABLE) + { + CANx->MCR |= CAN_MCR_TTCM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_TTCM; + } + + /* Set the automatic bus-off management */ + if (CAN_InitStruct->CAN_ABOM == ENABLE) + { + CANx->MCR |= CAN_MCR_ABOM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_ABOM; + } + + /* Set the automatic wake-up mode */ + if (CAN_InitStruct->CAN_AWUM == ENABLE) + { + CANx->MCR |= CAN_MCR_AWUM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_AWUM; + } + + /* Set the no automatic retransmission */ + if (CAN_InitStruct->CAN_NART == ENABLE) + { + CANx->MCR |= CAN_MCR_NART; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_NART; + } + + /* Set the receive FIFO locked mode */ + if (CAN_InitStruct->CAN_RFLM == ENABLE) + { + CANx->MCR |= CAN_MCR_RFLM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_RFLM; + } + + /* Set the transmit FIFO priority */ + if (CAN_InitStruct->CAN_TXFP == ENABLE) + { + CANx->MCR |= CAN_MCR_TXFP; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_TXFP; + } + + /* Set the bit timing register */ + CANx->BTR = (uint32_t)((uint32_t)CAN_InitStruct->CAN_Mode << 30) | \ + ((uint32_t)CAN_InitStruct->CAN_SJW << 24) | \ + ((uint32_t)CAN_InitStruct->CAN_BS1 << 16) | \ + ((uint32_t)CAN_InitStruct->CAN_BS2 << 20) | \ + ((uint32_t)CAN_InitStruct->CAN_Prescaler - 1); + + /* Request leave initialisation */ + CANx->MCR &= ~(uint32_t)CAN_MCR_INRQ; + + /* Wait the acknowledge */ + wait_ack = 0; + + while (((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) + { + wait_ack++; + } + + /* ...and check acknowledged */ + if ((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) + { + InitStatus = CAN_InitStatus_Failed; + } + else + { + InitStatus = CAN_InitStatus_Success ; + } + } + + /* At this step, return the status of initialization */ + return InitStatus; +} + +/** + * @brief Configures the CAN reception filter according to the specified + * parameters in the CAN_FilterInitStruct. + * @param CAN_FilterInitStruct: pointer to a CAN_FilterInitTypeDef structure that + * contains the configuration information. + * @retval None + */ +void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct) +{ + uint32_t filter_number_bit_pos = 0; + /* Check the parameters */ + assert_param(IS_CAN_FILTER_NUMBER(CAN_FilterInitStruct->CAN_FilterNumber)); + assert_param(IS_CAN_FILTER_MODE(CAN_FilterInitStruct->CAN_FilterMode)); + assert_param(IS_CAN_FILTER_SCALE(CAN_FilterInitStruct->CAN_FilterScale)); + assert_param(IS_CAN_FILTER_FIFO(CAN_FilterInitStruct->CAN_FilterFIFOAssignment)); + assert_param(IS_FUNCTIONAL_STATE(CAN_FilterInitStruct->CAN_FilterActivation)); + + filter_number_bit_pos = ((uint32_t)1) << CAN_FilterInitStruct->CAN_FilterNumber; + + /* Initialisation mode for the filter */ + CAN1->FMR |= FMR_FINIT; + + /* Filter Deactivation */ + CAN1->FA1R &= ~(uint32_t)filter_number_bit_pos; + + /* Filter Scale */ + if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_16bit) + { + /* 16-bit scale for the filter */ + CAN1->FS1R &= ~(uint32_t)filter_number_bit_pos; + + /* First 16-bit identifier and First 16-bit mask */ + /* Or First 16-bit identifier and Second 16-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); + + /* Second 16-bit identifier and Second 16-bit mask */ + /* Or Third 16-bit identifier and Fourth 16-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh); + } + + if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_32bit) + { + /* 32-bit scale for the filter */ + CAN1->FS1R |= filter_number_bit_pos; + /* 32-bit identifier or First 32-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); + /* 32-bit mask or Second 32-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow); + } + + /* Filter Mode */ + if (CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdMask) + { + /*Id/Mask mode for the filter*/ + CAN1->FM1R &= ~(uint32_t)filter_number_bit_pos; + } + else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ + { + /*Identifier list mode for the filter*/ + CAN1->FM1R |= (uint32_t)filter_number_bit_pos; + } + + /* Filter FIFO assignment */ + if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_Filter_FIFO0) + { + /* FIFO 0 assignation for the filter */ + CAN1->FFA1R &= ~(uint32_t)filter_number_bit_pos; + } + + if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_Filter_FIFO1) + { + /* FIFO 1 assignation for the filter */ + CAN1->FFA1R |= (uint32_t)filter_number_bit_pos; + } + + /* Filter activation */ + if (CAN_FilterInitStruct->CAN_FilterActivation == ENABLE) + { + CAN1->FA1R |= filter_number_bit_pos; + } + + /* Leave the initialisation mode for the filter */ + CAN1->FMR &= ~FMR_FINIT; +} + +/** + * @brief Fills each CAN_InitStruct member with its default value. + * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure which ill be initialized. + * @retval None + */ +void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct) +{ + /* Reset CAN init structure parameters values */ + + /* Initialize the time triggered communication mode */ + CAN_InitStruct->CAN_TTCM = DISABLE; + + /* Initialize the automatic bus-off management */ + CAN_InitStruct->CAN_ABOM = DISABLE; + + /* Initialize the automatic wake-up mode */ + CAN_InitStruct->CAN_AWUM = DISABLE; + + /* Initialize the no automatic retransmission */ + CAN_InitStruct->CAN_NART = DISABLE; + + /* Initialize the receive FIFO locked mode */ + CAN_InitStruct->CAN_RFLM = DISABLE; + + /* Initialize the transmit FIFO priority */ + CAN_InitStruct->CAN_TXFP = DISABLE; + + /* Initialize the CAN_Mode member */ + CAN_InitStruct->CAN_Mode = CAN_Mode_Normal; + + /* Initialize the CAN_SJW member */ + CAN_InitStruct->CAN_SJW = CAN_SJW_1tq; + + /* Initialize the CAN_BS1 member */ + CAN_InitStruct->CAN_BS1 = CAN_BS1_4tq; + + /* Initialize the CAN_BS2 member */ + CAN_InitStruct->CAN_BS2 = CAN_BS2_3tq; + + /* Initialize the CAN_Prescaler member */ + CAN_InitStruct->CAN_Prescaler = 1; +} + +/** + * @brief Select the start bank filter for slave CAN. + * @param CAN_BankNumber: Select the start slave bank filter from 1..27. + * @retval None + */ +void CAN_SlaveStartBank(uint8_t CAN_BankNumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_BANKNUMBER(CAN_BankNumber)); + + /* Enter Initialisation mode for the filter */ + CAN1->FMR |= FMR_FINIT; + + /* Select the start slave bank */ + CAN1->FMR &= (uint32_t)0xFFFFC0F1 ; + CAN1->FMR |= (uint32_t)(CAN_BankNumber)<<8; + + /* Leave Initialisation mode for the filter */ + CAN1->FMR &= ~FMR_FINIT; +} + +/** + * @brief Enables or disables the DBG Freeze for CAN. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param NewState: new state of the CAN peripheral. + * This parameter can be: ENABLE (CAN reception/transmission is frozen + * during debug. Reception FIFOs can still be accessed/controlled normally) + * or DISABLE (CAN is working during debug). + * @retval None + */ +void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable Debug Freeze */ + CANx->MCR |= MCR_DBF; + } + else + { + /* Disable Debug Freeze */ + CANx->MCR &= ~MCR_DBF; + } +} + + +/** + * @brief Enables or disables the CAN Time TriggerOperation communication mode. + * @note DLC must be programmed as 8 in order Time Stamp (2 bytes) to be + * sent over the CAN bus. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param NewState: Mode new state. This parameter can be: ENABLE or DISABLE. + * When enabled, Time stamp (TIME[15:0]) value is sent in the last two + * data bytes of the 8-byte message: TIME[7:0] in data byte 6 and TIME[15:8] + * in data byte 7. + * @retval None + */ +void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the TTCM mode */ + CANx->MCR |= CAN_MCR_TTCM; + + /* Set TGT bits */ + CANx->sTxMailBox[0].TDTR |= ((uint32_t)CAN_TDT0R_TGT); + CANx->sTxMailBox[1].TDTR |= ((uint32_t)CAN_TDT1R_TGT); + CANx->sTxMailBox[2].TDTR |= ((uint32_t)CAN_TDT2R_TGT); + } + else + { + /* Disable the TTCM mode */ + CANx->MCR &= (uint32_t)(~(uint32_t)CAN_MCR_TTCM); + + /* Reset TGT bits */ + CANx->sTxMailBox[0].TDTR &= ((uint32_t)~CAN_TDT0R_TGT); + CANx->sTxMailBox[1].TDTR &= ((uint32_t)~CAN_TDT1R_TGT); + CANx->sTxMailBox[2].TDTR &= ((uint32_t)~CAN_TDT2R_TGT); + } +} +/** + * @} + */ + + +/** @defgroup CAN_Group2 CAN Frames Transmission functions + * @brief CAN Frames Transmission functions + * +@verbatim + =============================================================================== + CAN Frames Transmission functions + =============================================================================== + This section provides functions allowing to + - Initiate and transmit a CAN frame message (if there is an empty mailbox). + - Check the transmission status of a CAN Frame + - Cancel a transmit request + +@endverbatim + * @{ + */ + +/** + * @brief Initiates and transmits a CAN frame message. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param TxMessage: pointer to a structure which contains CAN Id, CAN DLC and CAN data. + * @retval The number of the mailbox that is used for transmission or + * CAN_TxStatus_NoMailBox if there is no empty mailbox. + */ +uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage) +{ + uint8_t transmit_mailbox = 0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IDTYPE(TxMessage->IDE)); + assert_param(IS_CAN_RTR(TxMessage->RTR)); + assert_param(IS_CAN_DLC(TxMessage->DLC)); + + /* Select one empty transmit mailbox */ + if ((CANx->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) + { + transmit_mailbox = 0; + } + else if ((CANx->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) + { + transmit_mailbox = 1; + } + else if ((CANx->TSR&CAN_TSR_TME2) == CAN_TSR_TME2) + { + transmit_mailbox = 2; + } + else + { + transmit_mailbox = CAN_TxStatus_NoMailBox; + } + + if (transmit_mailbox != CAN_TxStatus_NoMailBox) + { + /* Set up the Id */ + CANx->sTxMailBox[transmit_mailbox].TIR &= TMIDxR_TXRQ; + if (TxMessage->IDE == CAN_Id_Standard) + { + assert_param(IS_CAN_STDID(TxMessage->StdId)); + CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->StdId << 21) | \ + TxMessage->RTR); + } + else + { + assert_param(IS_CAN_EXTID(TxMessage->ExtId)); + CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->ExtId << 3) | \ + TxMessage->IDE | \ + TxMessage->RTR); + } + + /* Set up the DLC */ + TxMessage->DLC &= (uint8_t)0x0000000F; + CANx->sTxMailBox[transmit_mailbox].TDTR &= (uint32_t)0xFFFFFFF0; + CANx->sTxMailBox[transmit_mailbox].TDTR |= TxMessage->DLC; + + /* Set up the data field */ + CANx->sTxMailBox[transmit_mailbox].TDLR = (((uint32_t)TxMessage->Data[3] << 24) | + ((uint32_t)TxMessage->Data[2] << 16) | + ((uint32_t)TxMessage->Data[1] << 8) | + ((uint32_t)TxMessage->Data[0])); + CANx->sTxMailBox[transmit_mailbox].TDHR = (((uint32_t)TxMessage->Data[7] << 24) | + ((uint32_t)TxMessage->Data[6] << 16) | + ((uint32_t)TxMessage->Data[5] << 8) | + ((uint32_t)TxMessage->Data[4])); + /* Request transmission */ + CANx->sTxMailBox[transmit_mailbox].TIR |= TMIDxR_TXRQ; + } + return transmit_mailbox; +} + +/** + * @brief Checks the transmission status of a CAN Frame. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @param TransmitMailbox: the number of the mailbox that is used for transmission. + * @retval CAN_TxStatus_Ok if the CAN driver transmits the message, + * CAN_TxStatus_Failed in an other case. + */ +uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox) +{ + uint32_t state = 0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_TRANSMITMAILBOX(TransmitMailbox)); + + switch (TransmitMailbox) + { + case (CAN_TXMAILBOX_0): + state = CANx->TSR & (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0); + break; + case (CAN_TXMAILBOX_1): + state = CANx->TSR & (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1); + break; + case (CAN_TXMAILBOX_2): + state = CANx->TSR & (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2); + break; + default: + state = CAN_TxStatus_Failed; + break; + } + switch (state) + { + /* transmit pending */ + case (0x0): state = CAN_TxStatus_Pending; + break; + /* transmit failed */ + case (CAN_TSR_RQCP0 | CAN_TSR_TME0): state = CAN_TxStatus_Failed; + break; + case (CAN_TSR_RQCP1 | CAN_TSR_TME1): state = CAN_TxStatus_Failed; + break; + case (CAN_TSR_RQCP2 | CAN_TSR_TME2): state = CAN_TxStatus_Failed; + break; + /* transmit succeeded */ + case (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0):state = CAN_TxStatus_Ok; + break; + case (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1):state = CAN_TxStatus_Ok; + break; + case (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2):state = CAN_TxStatus_Ok; + break; + default: state = CAN_TxStatus_Failed; + break; + } + return (uint8_t) state; +} + +/** + * @brief Cancels a transmit request. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @param Mailbox: Mailbox number. + * @retval None + */ +void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_TRANSMITMAILBOX(Mailbox)); + /* abort transmission */ + switch (Mailbox) + { + case (CAN_TXMAILBOX_0): CANx->TSR |= CAN_TSR_ABRQ0; + break; + case (CAN_TXMAILBOX_1): CANx->TSR |= CAN_TSR_ABRQ1; + break; + case (CAN_TXMAILBOX_2): CANx->TSR |= CAN_TSR_ABRQ2; + break; + default: + break; + } +} +/** + * @} + */ + + +/** @defgroup CAN_Group3 CAN Frames Reception functions + * @brief CAN Frames Reception functions + * +@verbatim + =============================================================================== + CAN Frames Reception functions + =============================================================================== + This section provides functions allowing to + - Receive a correct CAN frame + - Release a specified receive FIFO (2 FIFOs are available) + - Return the number of the pending received CAN frames + +@endverbatim + * @{ + */ + +/** + * @brief Receives a correct CAN frame. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. + * @param RxMessage: pointer to a structure receive frame which contains CAN Id, + * CAN DLC, CAN data and FMI number. + * @retval None + */ +void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + /* Get the Id */ + RxMessage->IDE = (uint8_t)0x04 & CANx->sFIFOMailBox[FIFONumber].RIR; + if (RxMessage->IDE == CAN_Id_Standard) + { + RxMessage->StdId = (uint32_t)0x000007FF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 21); + } + else + { + RxMessage->ExtId = (uint32_t)0x1FFFFFFF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 3); + } + + RxMessage->RTR = (uint8_t)0x02 & CANx->sFIFOMailBox[FIFONumber].RIR; + /* Get the DLC */ + RxMessage->DLC = (uint8_t)0x0F & CANx->sFIFOMailBox[FIFONumber].RDTR; + /* Get the FMI */ + RxMessage->FMI = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDTR >> 8); + /* Get the data field */ + RxMessage->Data[0] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDLR; + RxMessage->Data[1] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 8); + RxMessage->Data[2] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 16); + RxMessage->Data[3] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 24); + RxMessage->Data[4] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDHR; + RxMessage->Data[5] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 8); + RxMessage->Data[6] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 16); + RxMessage->Data[7] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 24); + /* Release the FIFO */ + /* Release FIFO0 */ + if (FIFONumber == CAN_FIFO0) + { + CANx->RF0R |= CAN_RF0R_RFOM0; + } + /* Release FIFO1 */ + else /* FIFONumber == CAN_FIFO1 */ + { + CANx->RF1R |= CAN_RF1R_RFOM1; + } +} + +/** + * @brief Releases the specified receive FIFO. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @param FIFONumber: FIFO to release, CAN_FIFO0 or CAN_FIFO1. + * @retval None + */ +void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + /* Release FIFO0 */ + if (FIFONumber == CAN_FIFO0) + { + CANx->RF0R |= CAN_RF0R_RFOM0; + } + /* Release FIFO1 */ + else /* FIFONumber == CAN_FIFO1 */ + { + CANx->RF1R |= CAN_RF1R_RFOM1; + } +} + +/** + * @brief Returns the number of pending received messages. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. + * @retval NbMessage : which is the number of pending message. + */ +uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber) +{ + uint8_t message_pending=0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + if (FIFONumber == CAN_FIFO0) + { + message_pending = (uint8_t)(CANx->RF0R&(uint32_t)0x03); + } + else if (FIFONumber == CAN_FIFO1) + { + message_pending = (uint8_t)(CANx->RF1R&(uint32_t)0x03); + } + else + { + message_pending = 0; + } + return message_pending; +} +/** + * @} + */ + + +/** @defgroup CAN_Group4 CAN Operation modes functions + * @brief CAN Operation modes functions + * +@verbatim + =============================================================================== + CAN Operation modes functions + =============================================================================== + This section provides functions allowing to select the CAN Operation modes + - sleep mode + - normal mode + - initialization mode + +@endverbatim + * @{ + */ + + +/** + * @brief Selects the CAN Operation mode. + * @param CAN_OperatingMode: CAN Operating Mode. + * This parameter can be one of @ref CAN_OperatingMode_TypeDef enumeration. + * @retval status of the requested mode which can be + * - CAN_ModeStatus_Failed: CAN failed entering the specific mode + * - CAN_ModeStatus_Success: CAN Succeed entering the specific mode + */ +uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode) +{ + uint8_t status = CAN_ModeStatus_Failed; + + /* Timeout for INAK or also for SLAK bits*/ + uint32_t timeout = INAK_TIMEOUT; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_OPERATING_MODE(CAN_OperatingMode)); + + if (CAN_OperatingMode == CAN_OperatingMode_Initialization) + { + /* Request initialisation */ + CANx->MCR = (uint32_t)((CANx->MCR & (uint32_t)(~(uint32_t)CAN_MCR_SLEEP)) | CAN_MCR_INRQ); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_INAK) && (timeout != 0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_INAK) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else if (CAN_OperatingMode == CAN_OperatingMode_Normal) + { + /* Request leave initialisation and sleep mode and enter Normal mode */ + CANx->MCR &= (uint32_t)(~(CAN_MCR_SLEEP|CAN_MCR_INRQ)); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != 0) && (timeout!=0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != 0) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else if (CAN_OperatingMode == CAN_OperatingMode_Sleep) + { + /* Request Sleep mode */ + CANx->MCR = (uint32_t)((CANx->MCR & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_SLAK) && (timeout!=0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_SLAK) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else + { + status = CAN_ModeStatus_Failed; + } + + return (uint8_t) status; +} + +/** + * @brief Enters the Sleep (low power) mode. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @retval CAN_Sleep_Ok if sleep entered, CAN_Sleep_Failed otherwise. + */ +uint8_t CAN_Sleep(CAN_TypeDef* CANx) +{ + uint8_t sleepstatus = CAN_Sleep_Failed; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Request Sleep mode */ + CANx->MCR = (((CANx->MCR) & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); + + /* Sleep mode status */ + if ((CANx->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) == CAN_MSR_SLAK) + { + /* Sleep mode not entered */ + sleepstatus = CAN_Sleep_Ok; + } + /* return sleep mode status */ + return (uint8_t)sleepstatus; +} + +/** + * @brief Wakes up the CAN peripheral from sleep mode . + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @retval CAN_WakeUp_Ok if sleep mode left, CAN_WakeUp_Failed otherwise. + */ +uint8_t CAN_WakeUp(CAN_TypeDef* CANx) +{ + uint32_t wait_slak = SLAK_TIMEOUT; + uint8_t wakeupstatus = CAN_WakeUp_Failed; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Wake up request */ + CANx->MCR &= ~(uint32_t)CAN_MCR_SLEEP; + + /* Sleep mode status */ + while(((CANx->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK)&&(wait_slak!=0x00)) + { + wait_slak--; + } + if((CANx->MSR & CAN_MSR_SLAK) != CAN_MSR_SLAK) + { + /* wake up done : Sleep mode exited */ + wakeupstatus = CAN_WakeUp_Ok; + } + /* return wakeup status */ + return (uint8_t)wakeupstatus; +} +/** + * @} + */ + + +/** @defgroup CAN_Group5 CAN Bus Error management functions + * @brief CAN Bus Error management functions + * +@verbatim + =============================================================================== + CAN Bus Error management functions + =============================================================================== + This section provides functions allowing to + - Return the CANx's last error code (LEC) + - Return the CANx Receive Error Counter (REC) + - Return the LSB of the 9-bit CANx Transmit Error Counter(TEC). + + @note If TEC is greater than 255, The CAN is in bus-off state. + @note if REC or TEC are greater than 96, an Error warning flag occurs. + @note if REC or TEC are greater than 127, an Error Passive Flag occurs. + +@endverbatim + * @{ + */ + +/** + * @brief Returns the CANx's last error code (LEC). + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @retval Error code: + * - CAN_ERRORCODE_NoErr: No Error + * - CAN_ERRORCODE_StuffErr: Stuff Error + * - CAN_ERRORCODE_FormErr: Form Error + * - CAN_ERRORCODE_ACKErr : Acknowledgment Error + * - CAN_ERRORCODE_BitRecessiveErr: Bit Recessive Error + * - CAN_ERRORCODE_BitDominantErr: Bit Dominant Error + * - CAN_ERRORCODE_CRCErr: CRC Error + * - CAN_ERRORCODE_SoftwareSetErr: Software Set Error + */ +uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx) +{ + uint8_t errorcode=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the error code*/ + errorcode = (((uint8_t)CANx->ESR) & (uint8_t)CAN_ESR_LEC); + + /* Return the error code*/ + return errorcode; +} + +/** + * @brief Returns the CANx Receive Error Counter (REC). + * @note In case of an error during reception, this counter is incremented + * by 1 or by 8 depending on the error condition as defined by the CAN + * standard. After every successful reception, the counter is + * decremented by 1 or reset to 120 if its value was higher than 128. + * When the counter value exceeds 127, the CAN controller enters the + * error passive state. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval CAN Receive Error Counter. + */ +uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx) +{ + uint8_t counter=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the Receive Error Counter*/ + counter = (uint8_t)((CANx->ESR & CAN_ESR_REC)>> 24); + + /* Return the Receive Error Counter*/ + return counter; +} + + +/** + * @brief Returns the LSB of the 9-bit CANx Transmit Error Counter(TEC). + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval LSB of the 9-bit CAN Transmit Error Counter. + */ +uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx) +{ + uint8_t counter=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the LSB of the 9-bit CANx Transmit Error Counter(TEC) */ + counter = (uint8_t)((CANx->ESR & CAN_ESR_TEC)>> 16); + + /* Return the LSB of the 9-bit CANx Transmit Error Counter(TEC) */ + return counter; +} +/** + * @} + */ + +/** @defgroup CAN_Group6 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + + This section provides functions allowing to configure the CAN Interrupts and + to get the status and clear flags and Interrupts pending bits. + + The CAN provides 14 Interrupts sources and 15 Flags: + + =============== + Flags : + =============== + The 15 flags can be divided on 4 groups: + + A. Transmit Flags + ----------------------- + CAN_FLAG_RQCP0, + CAN_FLAG_RQCP1, + CAN_FLAG_RQCP2 : Request completed MailBoxes 0, 1 and 2 Flags + Set when when the last request (transmit or abort) has + been performed. + + B. Receive Flags + ----------------------- + + CAN_FLAG_FMP0, + CAN_FLAG_FMP1 : FIFO 0 and 1 Message Pending Flags + set to signal that messages are pending in the receive + FIFO. + These Flags are cleared only by hardware. + + CAN_FLAG_FF0, + CAN_FLAG_FF1 : FIFO 0 and 1 Full Flags + set when three messages are stored in the selected + FIFO. + + CAN_FLAG_FOV0 + CAN_FLAG_FOV1 : FIFO 0 and 1 Overrun Flags + set when a new message has been received and passed + the filter while the FIFO was full. + + C. Operating Mode Flags + ----------------------- + CAN_FLAG_WKU : Wake up Flag + set to signal that a SOF bit has been detected while + the CAN hardware was in Sleep mode. + + CAN_FLAG_SLAK : Sleep acknowledge Flag + Set to signal that the CAN has entered Sleep Mode. + + D. Error Flags + ----------------------- + CAN_FLAG_EWG : Error Warning Flag + Set when the warning limit has been reached (Receive + Error Counter or Transmit Error Counter greater than 96). + This Flag is cleared only by hardware. + + CAN_FLAG_EPV : Error Passive Flag + Set when the Error Passive limit has been reached + (Receive Error Counter or Transmit Error Counter + greater than 127). + This Flag is cleared only by hardware. + + CAN_FLAG_BOF : Bus-Off Flag + set when CAN enters the bus-off state. The bus-off + state is entered on TEC overflow, greater than 255. + This Flag is cleared only by hardware. + + CAN_FLAG_LEC : Last error code Flag + set If a message has been transferred (reception or + transmission) with error, and the error code is hold. + + =============== + Interrupts : + =============== + The 14 interrupts can be divided on 4 groups: + + A. Transmit interrupt + ----------------------- + CAN_IT_TME : Transmit mailbox empty Interrupt + if enabled, this interrupt source is pending when + no transmit request are pending for Tx mailboxes. + + B. Receive Interrupts + ----------------------- + CAN_IT_FMP0, + CAN_IT_FMP1 : FIFO 0 and FIFO1 message pending Interrupts + if enabled, these interrupt sources are pending when + messages are pending in the receive FIFO. + The corresponding interrupt pending bits are cleared + only by hardware. + + CAN_IT_FF0, + CAN_IT_FF1 : FIFO 0 and FIFO1 full Interrupts + if enabled, these interrupt sources are pending when + three messages are stored in the selected FIFO. + + CAN_IT_FOV0, + CAN_IT_FOV1 : FIFO 0 and FIFO1 overrun Interrupts + if enabled, these interrupt sources are pending when + a new message has been received and passed the filter + while the FIFO was full. + + C. Operating Mode Interrupts + ------------------------------- + CAN_IT_WKU : Wake-up Interrupt + if enabled, this interrupt source is pending when + a SOF bit has been detected while the CAN hardware was + in Sleep mode. + + CAN_IT_SLK : Sleep acknowledge Interrupt + if enabled, this interrupt source is pending when + the CAN has entered Sleep Mode. + + D. Error Interrupts + ----------------------- + CAN_IT_EWG : Error warning Interrupt + if enabled, this interrupt source is pending when + the warning limit has been reached (Receive Error + Counter or Transmit Error Counter=96). + + CAN_IT_EPV : Error passive Interrupt + if enabled, this interrupt source is pending when + the Error Passive limit has been reached (Receive + Error Counter or Transmit Error Counter>127). + + CAN_IT_BOF : Bus-off Interrupt + if enabled, this interrupt source is pending when + CAN enters the bus-off state. The bus-off state is + entered on TEC overflow, greater than 255. + This Flag is cleared only by hardware. + + CAN_IT_LEC : Last error code Interrupt + if enabled, this interrupt source is pending when + a message has been transferred (reception or + transmission) with error, and the error code is hold. + + CAN_IT_ERR : Error Interrupt + if enabled, this interrupt source is pending when + an error condition is pending. + + + Managing the CAN controller events : + ------------------------------------ + The user should identify which mode will be used in his application to manage + the CAN controller events: Polling mode or Interrupt mode. + + 1. In the Polling Mode it is advised to use the following functions: + - CAN_GetFlagStatus() : to check if flags events occur. + - CAN_ClearFlag() : to clear the flags events. + + + + 2. In the Interrupt Mode it is advised to use the following functions: + - CAN_ITConfig() : to enable or disable the interrupt source. + - CAN_GetITStatus() : to check if Interrupt occurs. + - CAN_ClearITPendingBit() : to clear the Interrupt pending Bit (corresponding Flag). + @note This function has no impact on CAN_IT_FMP0 and CAN_IT_FMP1 Interrupts + pending bits since there are cleared only by hardware. + +@endverbatim + * @{ + */ +/** + * @brief Enables or disables the specified CANx interrupts. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the CAN interrupt sources to be enabled or disabled. + * This parameter can be: + * @arg CAN_IT_TME: Transmit mailbox empty Interrupt + * @arg CAN_IT_FMP0: FIFO 0 message pending Interrupt + * @arg CAN_IT_FF0: FIFO 0 full Interrupt + * @arg CAN_IT_FOV0: FIFO 0 overrun Interrupt + * @arg CAN_IT_FMP1: FIFO 1 message pending Interrupt + * @arg CAN_IT_FF1: FIFO 1 full Interrupt + * @arg CAN_IT_FOV1: FIFO 1 overrun Interrupt + * @arg CAN_IT_WKU: Wake-up Interrupt + * @arg CAN_IT_SLK: Sleep acknowledge Interrupt + * @arg CAN_IT_EWG: Error warning Interrupt + * @arg CAN_IT_EPV: Error passive Interrupt + * @arg CAN_IT_BOF: Bus-off Interrupt + * @arg CAN_IT_LEC: Last error code Interrupt + * @arg CAN_IT_ERR: Error Interrupt + * @param NewState: new state of the CAN interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IT(CAN_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected CANx interrupt */ + CANx->IER |= CAN_IT; + } + else + { + /* Disable the selected CANx interrupt */ + CANx->IER &= ~CAN_IT; + } +} +/** + * @brief Checks whether the specified CAN flag is set or not. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg CAN_FLAG_RQCP0: Request MailBox0 Flag + * @arg CAN_FLAG_RQCP1: Request MailBox1 Flag + * @arg CAN_FLAG_RQCP2: Request MailBox2 Flag + * @arg CAN_FLAG_FMP0: FIFO 0 Message Pending Flag + * @arg CAN_FLAG_FF0: FIFO 0 Full Flag + * @arg CAN_FLAG_FOV0: FIFO 0 Overrun Flag + * @arg CAN_FLAG_FMP1: FIFO 1 Message Pending Flag + * @arg CAN_FLAG_FF1: FIFO 1 Full Flag + * @arg CAN_FLAG_FOV1: FIFO 1 Overrun Flag + * @arg CAN_FLAG_WKU: Wake up Flag + * @arg CAN_FLAG_SLAK: Sleep acknowledge Flag + * @arg CAN_FLAG_EWG: Error Warning Flag + * @arg CAN_FLAG_EPV: Error Passive Flag + * @arg CAN_FLAG_BOF: Bus-Off Flag + * @arg CAN_FLAG_LEC: Last error code Flag + * @retval The new state of CAN_FLAG (SET or RESET). + */ +FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_GET_FLAG(CAN_FLAG)); + + + if((CAN_FLAG & CAN_FLAGS_ESR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->ESR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_MSR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->MSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_TSR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->TSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_RF0R) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->RF0R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else /* If(CAN_FLAG & CAN_FLAGS_RF1R != (uint32_t)RESET) */ + { + /* Check the status of the specified CAN flag */ + if ((uint32_t)(CANx->RF1R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + /* Return the CAN_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the CAN's pending flags. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_FLAG: specifies the flag to clear. + * This parameter can be one of the following values: + * @arg CAN_FLAG_RQCP0: Request MailBox0 Flag + * @arg CAN_FLAG_RQCP1: Request MailBox1 Flag + * @arg CAN_FLAG_RQCP2: Request MailBox2 Flag + * @arg CAN_FLAG_FF0: FIFO 0 Full Flag + * @arg CAN_FLAG_FOV0: FIFO 0 Overrun Flag + * @arg CAN_FLAG_FF1: FIFO 1 Full Flag + * @arg CAN_FLAG_FOV1: FIFO 1 Overrun Flag + * @arg CAN_FLAG_WKU: Wake up Flag + * @arg CAN_FLAG_SLAK: Sleep acknowledge Flag + * @arg CAN_FLAG_LEC: Last error code Flag + * @retval None + */ +void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG) +{ + uint32_t flagtmp=0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_CLEAR_FLAG(CAN_FLAG)); + + if (CAN_FLAG == CAN_FLAG_LEC) /* ESR register */ + { + /* Clear the selected CAN flags */ + CANx->ESR = (uint32_t)RESET; + } + else /* MSR or TSR or RF0R or RF1R */ + { + flagtmp = CAN_FLAG & 0x000FFFFF; + + if ((CAN_FLAG & CAN_FLAGS_RF0R)!=(uint32_t)RESET) + { + /* Receive Flags */ + CANx->RF0R = (uint32_t)(flagtmp); + } + else if ((CAN_FLAG & CAN_FLAGS_RF1R)!=(uint32_t)RESET) + { + /* Receive Flags */ + CANx->RF1R = (uint32_t)(flagtmp); + } + else if ((CAN_FLAG & CAN_FLAGS_TSR)!=(uint32_t)RESET) + { + /* Transmit Flags */ + CANx->TSR = (uint32_t)(flagtmp); + } + else /* If((CAN_FLAG & CAN_FLAGS_MSR)!=(uint32_t)RESET) */ + { + /* Operating mode Flags */ + CANx->MSR = (uint32_t)(flagtmp); + } + } +} + +/** + * @brief Checks whether the specified CANx interrupt has occurred or not. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the CAN interrupt source to check. + * This parameter can be one of the following values: + * @arg CAN_IT_TME: Transmit mailbox empty Interrupt + * @arg CAN_IT_FMP0: FIFO 0 message pending Interrupt + * @arg CAN_IT_FF0: FIFO 0 full Interrupt + * @arg CAN_IT_FOV0: FIFO 0 overrun Interrupt + * @arg CAN_IT_FMP1: FIFO 1 message pending Interrupt + * @arg CAN_IT_FF1: FIFO 1 full Interrupt + * @arg CAN_IT_FOV1: FIFO 1 overrun Interrupt + * @arg CAN_IT_WKU: Wake-up Interrupt + * @arg CAN_IT_SLK: Sleep acknowledge Interrupt + * @arg CAN_IT_EWG: Error warning Interrupt + * @arg CAN_IT_EPV: Error passive Interrupt + * @arg CAN_IT_BOF: Bus-off Interrupt + * @arg CAN_IT_LEC: Last error code Interrupt + * @arg CAN_IT_ERR: Error Interrupt + * @retval The current state of CAN_IT (SET or RESET). + */ +ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT) +{ + ITStatus itstatus = RESET; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IT(CAN_IT)); + + /* check the interrupt enable bit */ + if((CANx->IER & CAN_IT) != RESET) + { + /* in case the Interrupt is enabled, .... */ + switch (CAN_IT) + { + case CAN_IT_TME: + /* Check CAN_TSR_RQCPx bits */ + itstatus = CheckITStatus(CANx->TSR, CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2); + break; + case CAN_IT_FMP0: + /* Check CAN_RF0R_FMP0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FMP0); + break; + case CAN_IT_FF0: + /* Check CAN_RF0R_FULL0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FULL0); + break; + case CAN_IT_FOV0: + /* Check CAN_RF0R_FOVR0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FOVR0); + break; + case CAN_IT_FMP1: + /* Check CAN_RF1R_FMP1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FMP1); + break; + case CAN_IT_FF1: + /* Check CAN_RF1R_FULL1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FULL1); + break; + case CAN_IT_FOV1: + /* Check CAN_RF1R_FOVR1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FOVR1); + break; + case CAN_IT_WKU: + /* Check CAN_MSR_WKUI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_WKUI); + break; + case CAN_IT_SLK: + /* Check CAN_MSR_SLAKI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_SLAKI); + break; + case CAN_IT_EWG: + /* Check CAN_ESR_EWGF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EWGF); + break; + case CAN_IT_EPV: + /* Check CAN_ESR_EPVF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EPVF); + break; + case CAN_IT_BOF: + /* Check CAN_ESR_BOFF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_BOFF); + break; + case CAN_IT_LEC: + /* Check CAN_ESR_LEC bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_LEC); + break; + case CAN_IT_ERR: + /* Check CAN_MSR_ERRI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_ERRI); + break; + default: + /* in case of error, return RESET */ + itstatus = RESET; + break; + } + } + else + { + /* in case the Interrupt is not enabled, return RESET */ + itstatus = RESET; + } + + /* Return the CAN_IT status */ + return itstatus; +} + +/** + * @brief Clears the CANx's interrupt pending bits. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the interrupt pending bit to clear. + * This parameter can be one of the following values: + * @arg CAN_IT_TME: Transmit mailbox empty Interrupt + * @arg CAN_IT_FF0: FIFO 0 full Interrupt + * @arg CAN_IT_FOV0: FIFO 0 overrun Interrupt + * @arg CAN_IT_FF1: FIFO 1 full Interrupt + * @arg CAN_IT_FOV1: FIFO 1 overrun Interrupt + * @arg CAN_IT_WKU: Wake-up Interrupt + * @arg CAN_IT_SLK: Sleep acknowledge Interrupt + * @arg CAN_IT_EWG: Error warning Interrupt + * @arg CAN_IT_EPV: Error passive Interrupt + * @arg CAN_IT_BOF: Bus-off Interrupt + * @arg CAN_IT_LEC: Last error code Interrupt + * @arg CAN_IT_ERR: Error Interrupt + * @retval None + */ +void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_CLEAR_IT(CAN_IT)); + + switch (CAN_IT) + { + case CAN_IT_TME: + /* Clear CAN_TSR_RQCPx (rc_w1)*/ + CANx->TSR = CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2; + break; + case CAN_IT_FF0: + /* Clear CAN_RF0R_FULL0 (rc_w1)*/ + CANx->RF0R = CAN_RF0R_FULL0; + break; + case CAN_IT_FOV0: + /* Clear CAN_RF0R_FOVR0 (rc_w1)*/ + CANx->RF0R = CAN_RF0R_FOVR0; + break; + case CAN_IT_FF1: + /* Clear CAN_RF1R_FULL1 (rc_w1)*/ + CANx->RF1R = CAN_RF1R_FULL1; + break; + case CAN_IT_FOV1: + /* Clear CAN_RF1R_FOVR1 (rc_w1)*/ + CANx->RF1R = CAN_RF1R_FOVR1; + break; + case CAN_IT_WKU: + /* Clear CAN_MSR_WKUI (rc_w1)*/ + CANx->MSR = CAN_MSR_WKUI; + break; + case CAN_IT_SLK: + /* Clear CAN_MSR_SLAKI (rc_w1)*/ + CANx->MSR = CAN_MSR_SLAKI; + break; + case CAN_IT_EWG: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* @note the corresponding Flag is cleared by hardware depending on the CAN Bus status*/ + break; + case CAN_IT_EPV: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* @note the corresponding Flag is cleared by hardware depending on the CAN Bus status*/ + break; + case CAN_IT_BOF: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* @note the corresponding Flag is cleared by hardware depending on the CAN Bus status*/ + break; + case CAN_IT_LEC: + /* Clear LEC bits */ + CANx->ESR = RESET; + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + break; + case CAN_IT_ERR: + /*Clear LEC bits */ + CANx->ESR = RESET; + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* @note BOFF, EPVF and EWGF Flags are cleared by hardware depending on the CAN Bus status*/ + break; + default: + break; + } +} + /** + * @} + */ + +/** + * @brief Checks whether the CAN interrupt has occurred or not. + * @param CAN_Reg: specifies the CAN interrupt register to check. + * @param It_Bit: specifies the interrupt source bit to check. + * @retval The new state of the CAN Interrupt (SET or RESET). + */ +static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit) +{ + ITStatus pendingbitstatus = RESET; + + if ((CAN_Reg & It_Bit) != (uint32_t)RESET) + { + /* CAN_IT is set */ + pendingbitstatus = SET; + } + else + { + /* CAN_IT is reset */ + pendingbitstatus = RESET; + } + return pendingbitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_crc.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_crc.c new file mode 100644 index 000000000..c2c6bbb3c --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_crc.c @@ -0,0 +1,127 @@ +/** + ****************************************************************************** + * @file stm32f4xx_crc.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides all the CRC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_crc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup CRC + * @brief CRC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup CRC_Private_Functions + * @{ + */ + +/** + * @brief Resets the CRC Data register (DR). + * @param None + * @retval None + */ +void CRC_ResetDR(void) +{ + /* Reset CRC generator */ + CRC->CR = CRC_CR_RESET; +} + +/** + * @brief Computes the 32-bit CRC of a given data word(32-bit). + * @param Data: data word(32-bit) to compute its CRC + * @retval 32-bit CRC + */ +uint32_t CRC_CalcCRC(uint32_t Data) +{ + CRC->DR = Data; + + return (CRC->DR); +} + +/** + * @brief Computes the 32-bit CRC of a given buffer of data word(32-bit). + * @param pBuffer: pointer to the buffer containing the data to be computed + * @param BufferLength: length of the buffer to be computed + * @retval 32-bit CRC + */ +uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength) +{ + uint32_t index = 0; + + for(index = 0; index < BufferLength; index++) + { + CRC->DR = pBuffer[index]; + } + return (CRC->DR); +} + +/** + * @brief Returns the current CRC value. + * @param None + * @retval 32-bit CRC + */ +uint32_t CRC_GetCRC(void) +{ + return (CRC->DR); +} + +/** + * @brief Stores a 8-bit data in the Independent Data(ID) register. + * @param IDValue: 8-bit value to be stored in the ID register + * @retval None + */ +void CRC_SetIDRegister(uint8_t IDValue) +{ + CRC->IDR = IDValue; +} + +/** + * @brief Returns the 8-bit data stored in the Independent Data(ID) register + * @param None + * @retval 8-bit value of the ID register + */ +uint8_t CRC_GetIDRegister(void) +{ + return (CRC->IDR); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp.c new file mode 100644 index 000000000..dcdbef8f5 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp.c @@ -0,0 +1,850 @@ +/** + ****************************************************************************** + * @file stm32f4xx_cryp.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Cryptographic processor (CRYP) peripheral: + * - Initialization and Configuration functions + * - Data treatment functions + * - Context swapping functions + * - DMA interface function + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * 1. Enable the CRYP controller clock using + * RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_CRYP, ENABLE); function. + * + * 2. Initialise the CRYP using CRYP_Init(), CRYP_KeyInit() and if + * needed CRYP_IVInit(). + * + * 3. Flush the IN and OUT FIFOs by using CRYP_FIFOFlush() function. + * + * 4. Enable the CRYP controller using the CRYP_Cmd() function. + * + * 5. If using DMA for Data input and output transfer, + * Activate the needed DMA Requests using CRYP_DMACmd() function + + * 6. If DMA is not used for data transfer, use CRYP_DataIn() and + * CRYP_DataOut() functions to enter data to IN FIFO and get result + * from OUT FIFO. + * + * 7. To control CRYP events you can use one of the following + * two methods: + * - Check on CRYP flags using the CRYP_GetFlagStatus() function. + * - Use CRYP interrupts through the function CRYP_ITConfig() at + * initialization phase and CRYP_GetITStatus() function into + * interrupt routines in processing phase. + * + * 8. Save and restore Cryptographic processor context using + * CRYP_SaveContext() and CRYP_RestoreContext() functions. + * + * + * =================================================================== + * Procedure to perform an encryption or a decryption + * =================================================================== + * + * Initialization + * =============== + * 1. Initialize the peripheral using CRYP_Init(), CRYP_KeyInit() and + * CRYP_IVInit functions: + * - Configure the key size (128-, 192- or 256-bit, in the AES only) + * - Enter the symmetric key + * - Configure the data type + * - In case of decryption in AES-ECB or AES-CBC, you must prepare + * the key: configure the key preparation mode. Then Enable the CRYP + * peripheral using CRYP_Cmd() function: the BUSY flag is set. + * Wait until BUSY flag is reset : the key is prepared for decryption + * - Configure the algorithm and chaining (the DES/TDES in ECB/CBC, the + * AES in ECB/CBC/CTR) + * - Configure the direction (encryption/decryption). + * - Write the initialization vectors (in CBC or CTR modes only) + * + * 2. Flush the IN and OUT FIFOs using the CRYP_FIFOFlush() function + * + * + * Basic Processing mode (polling mode) + * ==================================== + * 1. Enable the cryptographic processor using CRYP_Cmd() function. + * + * 2. Write the first blocks in the input FIFO (2 to 8 words) using + * CRYP_DataIn() function. + * + * 3. Repeat the following sequence until the complete message has been + * processed: + * + * a) Wait for flag CRYP_FLAG_OFNE occurs (using CRYP_GetFlagStatus() + * function), then read the OUT-FIFO using CRYP_DataOut() function + * (1 block or until the FIFO is empty) + * + * b) Wait for flag CRYP_FLAG_IFNF occurs, (using CRYP_GetFlagStatus() + * function then write the IN FIFO using CRYP_DataIn() function + * (1 block or until the FIFO is full) + * + * 4. At the end of the processing, CRYP_FLAG_BUSY flag will be reset and + * both FIFOs are empty (CRYP_FLAG_IFEM is set and CRYP_FLAG_OFNE is + * reset). You can disable the peripheral using CRYP_Cmd() function. + * + * Interrupts Processing mode + * =========================== + * In this mode, Processing is done when the data are transferred by the + * CPU during interrupts. + * + * 1. Enable the interrupts CRYP_IT_INI and CRYP_IT_OUTI using + * CRYP_ITConfig() function. + * + * 2. Enable the cryptographic processor using CRYP_Cmd() function. + * + * 3. In the CRYP_IT_INI interrupt handler : load the input message into the + * IN FIFO using CRYP_DataIn() function . You can load 2 or 4 words at a + * time, or load data until the IN FIFO is full. When the last word of + * the message has been entered into the IN FIFO, disable the CRYP_IT_INI + * interrupt (using CRYP_ITConfig() function). + * + * 4. In the CRYP_IT_OUTI interrupt handler : read the output message from + * the OUT FIFO using CRYP_DataOut() function. You can read 1 block (2 or + * 4 words) at a time or read data until the FIFO is empty. + * When the last word has been read, INIM=0, BUSY=0 and both FIFOs are + * empty (CRYP_FLAG_IFEM is set and CRYP_FLAG_OFNE is reset). + * You can disable the CRYP_IT_OUTI interrupt (using CRYP_ITConfig() + * function) and you can disable the peripheral using CRYP_Cmd() function. + * + * DMA Processing mode + * ==================== + * In this mode, Processing is done when the DMA is used to transfer the + * data from/to the memory. + * + * 1. Configure the DMA controller to transfer the input data from the + * memory using DMA_Init() function. + * The transfer length is the length of the message. + * As message padding is not managed by the peripheral, the message + * length must be an entire number of blocks. The data are transferred + * in burst mode. The burst length is 4 words in the AES and 2 or 4 + * words in the DES/TDES. The DMA should be configured to set an + * interrupt on transfer completion of the output data to indicate that + * the processing is finished. + * Refer to DMA peripheral driver for more details. + * + * 2. Enable the cryptographic processor using CRYP_Cmd() function. + * Enable the DMA requests CRYP_DMAReq_DataIN and CRYP_DMAReq_DataOUT + * using CRYP_DMACmd() function. + * + * 3. All the transfers and processing are managed by the DMA and the + * cryptographic processor. The DMA transfer complete interrupt indicates + * that the processing is complete. Both FIFOs are normally empty and + * CRYP_FLAG_BUSY flag is reset. + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_cryp.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup CRYP + * @brief CRYP driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define FLAG_MASK ((uint8_t)0x20) +#define MAX_TIMEOUT ((uint16_t)0xFFFF) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup CRYP_Private_Functions + * @{ + */ + +/** @defgroup CRYP_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + This section provides functions allowing to + - Initialize the cryptographic Processor using CRYP_Init() function + - Encrypt or Decrypt + - mode : TDES-ECB, TDES-CBC, + DES-ECB, DES-CBC, + AES-ECB, AES-CBC, AES-CTR, AES-Key + - DataType : 32-bit data, 16-bit data, bit data or bit-string + - Key Size (only in AES modes) + - Configure the Encrypt or Decrypt Key using CRYP_KeyInit() function + - Configure the Initialization Vectors(IV) for CBC and CTR modes using + CRYP_IVInit() function. + - Flushes the IN and OUT FIFOs : using CRYP_FIFOFlush() function. + - Enable or disable the CRYP Processor using CRYP_Cmd() function + + +@endverbatim + * @{ + */ +/** + * @brief Deinitializes the CRYP peripheral registers to their default reset values + * @param None + * @retval None + */ +void CRYP_DeInit(void) +{ + /* Enable CRYP reset state */ + RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_CRYP, ENABLE); + + /* Release CRYP from reset state */ + RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_CRYP, DISABLE); +} + +/** + * @brief Initializes the CRYP peripheral according to the specified parameters + * in the CRYP_InitStruct. + * @param CRYP_InitStruct: pointer to a CRYP_InitTypeDef structure that contains + * the configuration information for the CRYP peripheral. + * @retval None + */ +void CRYP_Init(CRYP_InitTypeDef* CRYP_InitStruct) +{ + /* Check the parameters */ + assert_param(IS_CRYP_ALGOMODE(CRYP_InitStruct->CRYP_AlgoMode)); + assert_param(IS_CRYP_DATATYPE(CRYP_InitStruct->CRYP_DataType)); + assert_param(IS_CRYP_ALGODIR(CRYP_InitStruct->CRYP_AlgoDir)); + + /* Select Algorithm mode*/ + CRYP->CR &= ~CRYP_CR_ALGOMODE; + CRYP->CR |= CRYP_InitStruct->CRYP_AlgoMode; + + /* Select dataType */ + CRYP->CR &= ~CRYP_CR_DATATYPE; + CRYP->CR |= CRYP_InitStruct->CRYP_DataType; + + /* select Key size (used only with AES algorithm) */ + if ((CRYP_InitStruct->CRYP_AlgoMode == CRYP_AlgoMode_AES_ECB) || + (CRYP_InitStruct->CRYP_AlgoMode == CRYP_AlgoMode_AES_CBC) || + (CRYP_InitStruct->CRYP_AlgoMode == CRYP_AlgoMode_AES_CTR) || + (CRYP_InitStruct->CRYP_AlgoMode == CRYP_AlgoMode_AES_Key)) + { + assert_param(IS_CRYP_KEYSIZE(CRYP_InitStruct->CRYP_KeySize)); + CRYP->CR &= ~CRYP_CR_KEYSIZE; + CRYP->CR |= CRYP_InitStruct->CRYP_KeySize; /* Key size and value must be + configured once the key has + been prepared */ + } + + /* Select data Direction */ + CRYP->CR &= ~CRYP_CR_ALGODIR; + CRYP->CR |= CRYP_InitStruct->CRYP_AlgoDir; +} + +/** + * @brief Fills each CRYP_InitStruct member with its default value. + * @param CRYP_InitStruct: pointer to a CRYP_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void CRYP_StructInit(CRYP_InitTypeDef* CRYP_InitStruct) +{ + /* Initialize the CRYP_AlgoDir member */ + CRYP_InitStruct->CRYP_AlgoDir = CRYP_AlgoDir_Encrypt; + + /* initialize the CRYP_AlgoMode member */ + CRYP_InitStruct->CRYP_AlgoMode = CRYP_AlgoMode_TDES_ECB; + + /* initialize the CRYP_DataType member */ + CRYP_InitStruct->CRYP_DataType = CRYP_DataType_32b; + + /* Initialize the CRYP_KeySize member */ + CRYP_InitStruct->CRYP_KeySize = CRYP_KeySize_128b; +} + +/** + * @brief Initializes the CRYP Keys according to the specified parameters in + * the CRYP_KeyInitStruct. + * @param CRYP_KeyInitStruct: pointer to a CRYP_KeyInitTypeDef structure that + * contains the configuration information for the CRYP Keys. + * @retval None + */ +void CRYP_KeyInit(CRYP_KeyInitTypeDef* CRYP_KeyInitStruct) +{ + /* Key Initialisation */ + CRYP->K0LR = CRYP_KeyInitStruct->CRYP_Key0Left; + CRYP->K0RR = CRYP_KeyInitStruct->CRYP_Key0Right; + CRYP->K1LR = CRYP_KeyInitStruct->CRYP_Key1Left; + CRYP->K1RR = CRYP_KeyInitStruct->CRYP_Key1Right; + CRYP->K2LR = CRYP_KeyInitStruct->CRYP_Key2Left; + CRYP->K2RR = CRYP_KeyInitStruct->CRYP_Key2Right; + CRYP->K3LR = CRYP_KeyInitStruct->CRYP_Key3Left; + CRYP->K3RR = CRYP_KeyInitStruct->CRYP_Key3Right; +} + +/** + * @brief Fills each CRYP_KeyInitStruct member with its default value. + * @param CRYP_KeyInitStruct: pointer to a CRYP_KeyInitTypeDef structure + * which will be initialized. + * @retval None + */ +void CRYP_KeyStructInit(CRYP_KeyInitTypeDef* CRYP_KeyInitStruct) +{ + CRYP_KeyInitStruct->CRYP_Key0Left = 0; + CRYP_KeyInitStruct->CRYP_Key0Right = 0; + CRYP_KeyInitStruct->CRYP_Key1Left = 0; + CRYP_KeyInitStruct->CRYP_Key1Right = 0; + CRYP_KeyInitStruct->CRYP_Key2Left = 0; + CRYP_KeyInitStruct->CRYP_Key2Right = 0; + CRYP_KeyInitStruct->CRYP_Key3Left = 0; + CRYP_KeyInitStruct->CRYP_Key3Right = 0; +} +/** + * @brief Initializes the CRYP Initialization Vectors(IV) according to the + * specified parameters in the CRYP_IVInitStruct. + * @param CRYP_IVInitStruct: pointer to a CRYP_IVInitTypeDef structure that contains + * the configuration information for the CRYP Initialization Vectors(IV). + * @retval None + */ +void CRYP_IVInit(CRYP_IVInitTypeDef* CRYP_IVInitStruct) +{ + CRYP->IV0LR = CRYP_IVInitStruct->CRYP_IV0Left; + CRYP->IV0RR = CRYP_IVInitStruct->CRYP_IV0Right; + CRYP->IV1LR = CRYP_IVInitStruct->CRYP_IV1Left; + CRYP->IV1RR = CRYP_IVInitStruct->CRYP_IV1Right; +} + +/** + * @brief Fills each CRYP_IVInitStruct member with its default value. + * @param CRYP_IVInitStruct: pointer to a CRYP_IVInitTypeDef Initialization + * Vectors(IV) structure which will be initialized. + * @retval None + */ +void CRYP_IVStructInit(CRYP_IVInitTypeDef* CRYP_IVInitStruct) +{ + CRYP_IVInitStruct->CRYP_IV0Left = 0; + CRYP_IVInitStruct->CRYP_IV0Right = 0; + CRYP_IVInitStruct->CRYP_IV1Left = 0; + CRYP_IVInitStruct->CRYP_IV1Right = 0; +} + +/** + * @brief Flushes the IN and OUT FIFOs (that is read and write pointers of the + * FIFOs are reset) + * @note The FIFOs must be flushed only when BUSY flag is reset. + * @param None + * @retval None + */ +void CRYP_FIFOFlush(void) +{ + /* Reset the read and write pointers of the FIFOs */ + CRYP->CR |= CRYP_CR_FFLUSH; +} + +/** + * @brief Enables or disables the CRYP peripheral. + * @param NewState: new state of the CRYP peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CRYP_Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Cryptographic processor */ + CRYP->CR |= CRYP_CR_CRYPEN; + } + else + { + /* Disable the Cryptographic processor */ + CRYP->CR &= ~CRYP_CR_CRYPEN; + } +} +/** + * @} + */ + +/** @defgroup CRYP_Group2 CRYP Data processing functions + * @brief CRYP Data processing functions + * +@verbatim + =============================================================================== + CRYP Data processing functions + =============================================================================== + This section provides functions allowing the encryption and decryption + operations: + - Enter data to be treated in the IN FIFO : using CRYP_DataIn() function. + - Get the data result from the OUT FIFO : using CRYP_DataOut() function. + +@endverbatim + * @{ + */ + +/** + * @brief Writes data in the Data Input register (DIN). + * @note After the DIN register has been read once or several times, + * the FIFO must be flushed (using CRYP_FIFOFlush() function). + * @param Data: data to write in Data Input register + * @retval None + */ +void CRYP_DataIn(uint32_t Data) +{ + CRYP->DR = Data; +} + +/** + * @brief Returns the last data entered into the output FIFO. + * @param None + * @retval Last data entered into the output FIFO. + */ +uint32_t CRYP_DataOut(void) +{ + return CRYP->DOUT; +} +/** + * @} + */ + +/** @defgroup CRYP_Group3 Context swapping functions + * @brief Context swapping functions + * +@verbatim + =============================================================================== + Context swapping functions + =============================================================================== + + This section provides functions allowing to save and store CRYP Context + + It is possible to interrupt an encryption/ decryption/ key generation process + to perform another processing with a higher priority, and to complete the + interrupted process later on, when the higher-priority task is complete. To do + so, the context of the interrupted task must be saved from the CRYP registers + to memory, and then be restored from memory to the CRYP registers. + + 1. To save the current context, use CRYP_SaveContext() function + 2. To restore the saved context, use CRYP_RestoreContext() function + + +@endverbatim + * @{ + */ + +/** + * @brief Saves the CRYP peripheral Context. + * @note This function stops DMA transfer before to save the context. After + * restoring the context, you have to enable the DMA again (if the DMA + * was previously used). + * @param CRYP_ContextSave: pointer to a CRYP_Context structure that contains + * the repository for current context. + * @param CRYP_KeyInitStruct: pointer to a CRYP_KeyInitTypeDef structure that + * contains the configuration information for the CRYP Keys. + * @retval None + */ +ErrorStatus CRYP_SaveContext(CRYP_Context* CRYP_ContextSave, + CRYP_KeyInitTypeDef* CRYP_KeyInitStruct) +{ + __IO uint32_t timeout = 0; + uint32_t ckeckmask = 0, bitstatus; + ErrorStatus status = ERROR; + + /* Stop DMA transfers on the IN FIFO by clearing the DIEN bit in the CRYP_DMACR */ + CRYP->DMACR &= ~(uint32_t)CRYP_DMACR_DIEN; + + /* Wait until both the IN and OUT FIFOs are empty + (IFEM=1 and OFNE=0 in the CRYP_SR register) and the + BUSY bit is cleared. */ + + if ((CRYP->CR & (uint32_t)(CRYP_CR_ALGOMODE_TDES_ECB | CRYP_CR_ALGOMODE_TDES_CBC)) != (uint32_t)0 )/* TDES */ + { + ckeckmask = CRYP_SR_IFEM | CRYP_SR_BUSY ; + } + else /* AES or DES */ + { + ckeckmask = CRYP_SR_IFEM | CRYP_SR_BUSY | CRYP_SR_OFNE; + } + + do + { + bitstatus = CRYP->SR & ckeckmask; + timeout++; + } + while ((timeout != MAX_TIMEOUT) && (bitstatus != CRYP_SR_IFEM)); + + if ((CRYP->SR & ckeckmask) != CRYP_SR_IFEM) + { + status = ERROR; + } + else + { + /* Stop DMA transfers on the OUT FIFO by + - writing the DOEN bit to 0 in the CRYP_DMACR register + - and clear the CRYPEN bit. */ + + CRYP->DMACR &= ~(uint32_t)CRYP_DMACR_DOEN; + CRYP->CR &= ~(uint32_t)CRYP_CR_CRYPEN; + + /* Save the current configuration (bits [9:2] in the CRYP_CR register) */ + CRYP_ContextSave->CR_bits9to2 = CRYP->CR & (CRYP_CR_KEYSIZE | + CRYP_CR_DATATYPE | + CRYP_CR_ALGOMODE | + CRYP_CR_ALGODIR); + + /* and, if not in ECB mode, the initialization vectors. */ + CRYP_ContextSave->CRYP_IV0LR = CRYP->IV0LR; + CRYP_ContextSave->CRYP_IV0RR = CRYP->IV0RR; + CRYP_ContextSave->CRYP_IV1LR = CRYP->IV1LR; + CRYP_ContextSave->CRYP_IV1RR = CRYP->IV1RR; + + /* save The key value */ + CRYP_ContextSave->CRYP_K0LR = CRYP_KeyInitStruct->CRYP_Key0Left; + CRYP_ContextSave->CRYP_K0RR = CRYP_KeyInitStruct->CRYP_Key0Right; + CRYP_ContextSave->CRYP_K1LR = CRYP_KeyInitStruct->CRYP_Key1Left; + CRYP_ContextSave->CRYP_K1RR = CRYP_KeyInitStruct->CRYP_Key1Right; + CRYP_ContextSave->CRYP_K2LR = CRYP_KeyInitStruct->CRYP_Key2Left; + CRYP_ContextSave->CRYP_K2RR = CRYP_KeyInitStruct->CRYP_Key2Right; + CRYP_ContextSave->CRYP_K3LR = CRYP_KeyInitStruct->CRYP_Key3Left; + CRYP_ContextSave->CRYP_K3RR = CRYP_KeyInitStruct->CRYP_Key3Right; + + /* When needed, save the DMA status (pointers for IN and OUT messages, + number of remaining bytes, etc.) */ + + status = SUCCESS; + } + + return status; +} + +/** + * @brief Restores the CRYP peripheral Context. + * @note Since teh DMA transfer is stopped in CRYP_SaveContext() function, + * after restoring the context, you have to enable the DMA again (if the + * DMA was previously used). + * @param CRYP_ContextRestore: pointer to a CRYP_Context structure that contains + * the repository for saved context. + * @note The data that were saved during context saving must be rewrited into + * the IN FIFO. + * @retval None + */ +void CRYP_RestoreContext(CRYP_Context* CRYP_ContextRestore) +{ + + /* Configure the processor with the saved configuration */ + CRYP->CR = CRYP_ContextRestore->CR_bits9to2; + + /* restore The key value */ + CRYP->K0LR = CRYP_ContextRestore->CRYP_K0LR; + CRYP->K0RR = CRYP_ContextRestore->CRYP_K0RR; + CRYP->K1LR = CRYP_ContextRestore->CRYP_K1LR; + CRYP->K1RR = CRYP_ContextRestore->CRYP_K1RR; + CRYP->K2LR = CRYP_ContextRestore->CRYP_K2LR; + CRYP->K2RR = CRYP_ContextRestore->CRYP_K2RR; + CRYP->K3LR = CRYP_ContextRestore->CRYP_K3LR; + CRYP->K3RR = CRYP_ContextRestore->CRYP_K3RR; + + /* and the initialization vectors. */ + CRYP->IV0LR = CRYP_ContextRestore->CRYP_IV0LR; + CRYP->IV0RR = CRYP_ContextRestore->CRYP_IV0RR; + CRYP->IV1LR = CRYP_ContextRestore->CRYP_IV1LR; + CRYP->IV1RR = CRYP_ContextRestore->CRYP_IV1RR; + + /* Enable the cryptographic processor */ + CRYP->CR |= CRYP_CR_CRYPEN; +} +/** + * @} + */ + +/** @defgroup CRYP_Group4 CRYP's DMA interface Configuration function + * @brief CRYP's DMA interface Configuration function + * +@verbatim + =============================================================================== + CRYP's DMA interface Configuration function + =============================================================================== + + This section provides functions allowing to configure the DMA interface for + CRYP data input and output transfer. + + When the DMA mode is enabled (using the CRYP_DMACmd() function), data can be + transferred: + - From memory to the CRYP IN FIFO using the DMA peripheral by enabling + the CRYP_DMAReq_DataIN request. + - From the CRYP OUT FIFO to the memory using the DMA peripheral by enabling + the CRYP_DMAReq_DataOUT request. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the CRYP DMA interface. + * @param CRYP_DMAReq: specifies the CRYP DMA transfer request to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg CRYP_DMAReq_DataOUT: DMA for outgoing(Tx) data transfer + * @arg CRYP_DMAReq_DataIN: DMA for incoming(Rx) data transfer + * @param NewState: new state of the selected CRYP DMA transfer request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CRYP_DMACmd(uint8_t CRYP_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CRYP_DMAREQ(CRYP_DMAReq)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected CRYP DMA request */ + CRYP->DMACR |= CRYP_DMAReq; + } + else + { + /* Disable the selected CRYP DMA request */ + CRYP->DMACR &= (uint8_t)~CRYP_DMAReq; + } +} +/** + * @} + */ + +/** @defgroup CRYP_Group5 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + + This section provides functions allowing to configure the CRYP Interrupts and + to get the status and Interrupts pending bits. + + The CRYP provides 2 Interrupts sources and 7 Flags: + + Flags : + ------- + + 1. CRYP_FLAG_IFEM : Set when Input FIFO is empty. + This Flag is cleared only by hardware. + + 2. CRYP_FLAG_IFNF : Set when Input FIFO is not full. + This Flag is cleared only by hardware. + + + 3. CRYP_FLAG_INRIS : Set when Input FIFO Raw interrupt is pending + it gives the raw interrupt state prior to masking + of the input FIFO service interrupt. + This Flag is cleared only by hardware. + + 4. CRYP_FLAG_OFNE : Set when Output FIFO not empty. + This Flag is cleared only by hardware. + + 5. CRYP_FLAG_OFFU : Set when Output FIFO is full. + This Flag is cleared only by hardware. + + 6. CRYP_FLAG_OUTRIS : Set when Output FIFO Raw interrupt is pending + it gives the raw interrupt state prior to masking + of the output FIFO service interrupt. + This Flag is cleared only by hardware. + + 7. CRYP_FLAG_BUSY : Set when the CRYP core is currently processing a + block of data or a key preparation (for AES + decryption). + This Flag is cleared only by hardware. + To clear it, the CRYP core must be disabled and the + last processing has completed. + + Interrupts : + ------------ + + 1. CRYP_IT_INI : The input FIFO service interrupt is asserted when there + are less than 4 words in the input FIFO. + This interrupt is associated to CRYP_FLAG_INRIS flag. + + @note This interrupt is cleared by performing write operations + to the input FIFO until it holds 4 or more words. The + input FIFO service interrupt INMIS is enabled with the + CRYP enable bit. Consequently, when CRYP is disabled, the + INMIS signal is low even if the input FIFO is empty. + + + + 2. CRYP_IT_OUTI : The output FIFO service interrupt is asserted when there + is one or more (32-bit word) data items in the output FIFO. + This interrupt is associated to CRYP_FLAG_OUTRIS flag. + + @note This interrupt is cleared by reading data from the output + FIFO until there is no valid (32-bit) word left (that is, + the interrupt follows the state of the OFNE (output FIFO + not empty) flag). + + + Managing the CRYP controller events : + ------------------------------------ + The user should identify which mode will be used in his application to manage + the CRYP controller events: Polling mode or Interrupt mode. + + 1. In the Polling Mode it is advised to use the following functions: + - CRYP_GetFlagStatus() : to check if flags events occur. + + @note The CRYPT flags do not need to be cleared since they are cleared as + soon as the associated event are reset. + + + 2. In the Interrupt Mode it is advised to use the following functions: + - CRYP_ITConfig() : to enable or disable the interrupt source. + - CRYP_GetITStatus() : to check if Interrupt occurs. + + @note The CRYPT interrupts have no pending bits, the interrupt is cleared as + soon as the associated event is reset. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified CRYP interrupts. + * @param CRYP_IT: specifies the CRYP interrupt source to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg CRYP_IT_INI: Input FIFO interrupt + * @arg CRYP_IT_OUTI: Output FIFO interrupt + * @param NewState: new state of the specified CRYP interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CRYP_ITConfig(uint8_t CRYP_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CRYP_CONFIG_IT(CRYP_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected CRYP interrupt */ + CRYP->IMSCR |= CRYP_IT; + } + else + { + /* Disable the selected CRYP interrupt */ + CRYP->IMSCR &= (uint8_t)~CRYP_IT; + } +} + +/** + * @brief Checks whether the specified CRYP interrupt has occurred or not. + * @note This function checks the status of the masked interrupt (i.e the + * interrupt should be previously enabled). + * @param CRYP_IT: specifies the CRYP (masked) interrupt source to check. + * This parameter can be one of the following values: + * @arg CRYP_IT_INI: Input FIFO interrupt + * @arg CRYP_IT_OUTI: Output FIFO interrupt + * @retval The new state of CRYP_IT (SET or RESET). + */ +ITStatus CRYP_GetITStatus(uint8_t CRYP_IT) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_CRYP_GET_IT(CRYP_IT)); + + /* Check the status of the specified CRYP interrupt */ + if ((CRYP->MISR & CRYP_IT) != (uint8_t)RESET) + { + /* CRYP_IT is set */ + bitstatus = SET; + } + else + { + /* CRYP_IT is reset */ + bitstatus = RESET; + } + /* Return the CRYP_IT status */ + return bitstatus; +} + +/** + * @brief Checks whether the specified CRYP flag is set or not. + * @param CRYP_FLAG: specifies the CRYP flag to check. + * This parameter can be one of the following values: + * @arg CRYP_FLAG_IFEM: Input FIFO Empty flag. + * @arg CRYP_FLAG_IFNF: Input FIFO Not Full flag. + * @arg CRYP_FLAG_OFNE: Output FIFO Not Empty flag. + * @arg CRYP_FLAG_OFFU: Output FIFO Full flag. + * @arg CRYP_FLAG_BUSY: Busy flag. + * @arg CRYP_FLAG_OUTRIS: Output FIFO raw interrupt flag. + * @arg CRYP_FLAG_INRIS: Input FIFO raw interrupt flag. + * @retval The new state of CRYP_FLAG (SET or RESET). + */ +FlagStatus CRYP_GetFlagStatus(uint8_t CRYP_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tempreg = 0; + + /* Check the parameters */ + assert_param(IS_CRYP_GET_FLAG(CRYP_FLAG)); + + /* check if the FLAG is in RISR register */ + if ((CRYP_FLAG & FLAG_MASK) != 0x00) + { + tempreg = CRYP->RISR; + } + else /* The FLAG is in SR register */ + { + tempreg = CRYP->SR; + } + + + /* Check the status of the specified CRYP flag */ + if ((tempreg & CRYP_FLAG ) != (uint8_t)RESET) + { + /* CRYP_FLAG is set */ + bitstatus = SET; + } + else + { + /* CRYP_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the CRYP_FLAG status */ + return bitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_aes.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_aes.c new file mode 100644 index 000000000..286680979 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_aes.c @@ -0,0 +1,638 @@ +/** + ****************************************************************************** + * @file stm32f4xx_cryp_aes.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides high level functions to encrypt and decrypt an + * input message using AES in ECB/CBC/CTR modes. + * It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP + * peripheral. + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * 1. Enable The CRYP controller clock using + * RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_CRYP, ENABLE); function. + * + * 2. Encrypt and decrypt using AES in ECB Mode using CRYP_AES_ECB() + * function. + * + * 3. Encrypt and decrypt using AES in CBC Mode using CRYP_AES_CBC() + * function. + * + * 4. Encrypt and decrypt using AES in CTR Mode using CRYP_AES_CTR() + * function. + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_cryp.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup CRYP + * @brief CRYP driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define AESBUSY_TIMEOUT ((uint32_t) 0x00010000) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup CRYP_Private_Functions + * @{ + */ + +/** @defgroup CRYP_Group6 High Level AES functions + * @brief High Level AES functions + * +@verbatim + =============================================================================== + High Level AES functions + =============================================================================== + + +@endverbatim + * @{ + */ + +/** + * @brief Encrypt and decrypt using AES in ECB Mode + * @param Mode: encryption or decryption Mode. + * This parameter can be one of the following values: + * @arg MODE_ENCRYPT: Encryption + * @arg MODE_DECRYPT: Decryption + * @param Key: Key used for AES algorithm. + * @param Keysize: length of the Key, must be a 128, 192 or 256. + * @param Input: pointer to the Input buffer. + * @param Ilength: length of the Input buffer, must be a multiple of 16. + * @param Output: pointer to the returned buffer. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: Operation done + * - ERROR: Operation failed + */ +ErrorStatus CRYP_AES_ECB(uint8_t Mode, uint8_t* Key, uint16_t Keysize, + uint8_t* Input, uint32_t Ilength, uint8_t* Output) +{ + CRYP_InitTypeDef AES_CRYP_InitStructure; + CRYP_KeyInitTypeDef AES_CRYP_KeyInitStructure; + __IO uint32_t counter = 0; + uint32_t busystatus = 0; + ErrorStatus status = SUCCESS; + uint32_t keyaddr = (uint32_t)Key; + uint32_t inputaddr = (uint32_t)Input; + uint32_t outputaddr = (uint32_t)Output; + uint32_t i = 0; + + /* Crypto structures initialisation*/ + CRYP_KeyStructInit(&AES_CRYP_KeyInitStructure); + + switch(Keysize) + { + case 128: + AES_CRYP_InitStructure.CRYP_KeySize = CRYP_KeySize_128b; + AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr)); + break; + case 192: + AES_CRYP_InitStructure.CRYP_KeySize = CRYP_KeySize_192b; + AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr)); + break; + case 256: + AES_CRYP_InitStructure.CRYP_KeySize = CRYP_KeySize_256b; + AES_CRYP_KeyInitStructure.CRYP_Key0Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key0Right= __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr)); + break; + default: + break; + } + + /*------------------ AES Decryption ------------------*/ + if(Mode == MODE_DECRYPT) /* AES decryption */ + { + /* Flush IN/OUT FIFOs */ + CRYP_FIFOFlush(); + + /* Crypto Init for Key preparation for decryption process */ + AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt; + AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_Key; + AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_32b; + CRYP_Init(&AES_CRYP_InitStructure); + + /* Key Initialisation */ + CRYP_KeyInit(&AES_CRYP_KeyInitStructure); + + /* Enable Crypto processor */ + CRYP_Cmd(ENABLE); + + /* wait until the Busy flag is RESET */ + do + { + busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY); + counter++; + }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET)); + + if (busystatus != RESET) + { + status = ERROR; + } + else + { + /* Crypto Init for decryption process */ + AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt; + } + } + /*------------------ AES Encryption ------------------*/ + else /* AES encryption */ + { + + CRYP_KeyInit(&AES_CRYP_KeyInitStructure); + + /* Crypto Init for Encryption process */ + AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt; + } + + AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_ECB; + AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b; + CRYP_Init(&AES_CRYP_InitStructure); + + /* Flush IN/OUT FIFOs */ + CRYP_FIFOFlush(); + + /* Enable Crypto processor */ + CRYP_Cmd(ENABLE); + + for(i=0; ((i
© COPYRIGHT 2011 STMicroelectronics
+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_cryp.h" + + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup CRYP + * @brief CRYP driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define DESBUSY_TIMEOUT ((uint32_t) 0x00010000) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + + +/** @defgroup CRYP_Private_Functions + * @{ + */ + +/** @defgroup CRYP_Group8 High Level DES functions + * @brief High Level DES functions + * +@verbatim + =============================================================================== + High Level DES functions + =============================================================================== +@endverbatim + * @{ + */ + +/** + * @brief Encrypt and decrypt using DES in ECB Mode + * @param Mode: encryption or decryption Mode. + * This parameter can be one of the following values: + * @arg MODE_ENCRYPT: Encryption + * @arg MODE_DECRYPT: Decryption + * @param Key: Key used for DES algorithm. + * @param Ilength: length of the Input buffer, must be a multiple of 8. + * @param Input: pointer to the Input buffer. + * @param Output: pointer to the returned buffer. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: Operation done + * - ERROR: Operation failed + */ +ErrorStatus CRYP_DES_ECB(uint8_t Mode, uint8_t Key[8], uint8_t *Input, + uint32_t Ilength, uint8_t *Output) +{ + CRYP_InitTypeDef DES_CRYP_InitStructure; + CRYP_KeyInitTypeDef DES_CRYP_KeyInitStructure; + __IO uint32_t counter = 0; + uint32_t busystatus = 0; + ErrorStatus status = SUCCESS; + uint32_t keyaddr = (uint32_t)Key; + uint32_t inputaddr = (uint32_t)Input; + uint32_t outputaddr = (uint32_t)Output; + uint32_t i = 0; + + /* Crypto structures initialisation*/ + CRYP_KeyStructInit(&DES_CRYP_KeyInitStructure); + + /* Crypto Init for Encryption process */ + if( Mode == MODE_ENCRYPT ) /* DES encryption */ + { + DES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt; + } + else/* if( Mode == MODE_DECRYPT )*/ /* DES decryption */ + { + DES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt; + } + + DES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_DES_ECB; + DES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b; + CRYP_Init(&DES_CRYP_InitStructure); + + /* Key Initialisation */ + DES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + DES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr)); + CRYP_KeyInit(& DES_CRYP_KeyInitStructure); + + /* Flush IN/OUT FIFO */ + CRYP_FIFOFlush(); + + /* Enable Crypto processor */ + CRYP_Cmd(ENABLE); + + for(i=0; ((i
© COPYRIGHT 2011 STMicroelectronics
+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_cryp.h" + + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup CRYP + * @brief CRYP driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define TDESBUSY_TIMEOUT ((uint32_t) 0x00010000) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + + +/** @defgroup CRYP_Private_Functions + * @{ + */ + +/** @defgroup CRYP_Group7 High Level TDES functions + * @brief High Level TDES functions + * +@verbatim + =============================================================================== + High Level TDES functions + =============================================================================== + + +@endverbatim + * @{ + */ + +/** + * @brief Encrypt and decrypt using TDES in ECB Mode + * @param Mode: encryption or decryption Mode. + * This parameter can be one of the following values: + * @arg MODE_ENCRYPT: Encryption + * @arg MODE_DECRYPT: Decryption + * @param Key: Key used for TDES algorithm. + * @param Ilength: length of the Input buffer, must be a multiple of 8. + * @param Input: pointer to the Input buffer. + * @param Output: pointer to the returned buffer. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: Operation done + * - ERROR: Operation failed + */ +ErrorStatus CRYP_TDES_ECB(uint8_t Mode, uint8_t Key[24], uint8_t *Input, + uint32_t Ilength, uint8_t *Output) +{ + CRYP_InitTypeDef TDES_CRYP_InitStructure; + CRYP_KeyInitTypeDef TDES_CRYP_KeyInitStructure; + __IO uint32_t counter = 0; + uint32_t busystatus = 0; + ErrorStatus status = SUCCESS; + uint32_t keyaddr = (uint32_t)Key; + uint32_t inputaddr = (uint32_t)Input; + uint32_t outputaddr = (uint32_t)Output; + uint32_t i = 0; + + /* Crypto structures initialisation*/ + CRYP_KeyStructInit(&TDES_CRYP_KeyInitStructure); + + /* Crypto Init for Encryption process */ + if(Mode == MODE_ENCRYPT) /* TDES encryption */ + { + TDES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt; + } + else /*if(Mode == MODE_DECRYPT)*/ /* TDES decryption */ + { + TDES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt; + } + + TDES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_TDES_ECB; + TDES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b; + CRYP_Init(&TDES_CRYP_InitStructure); + + /* Key Initialisation */ + TDES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + TDES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + TDES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + TDES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + TDES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr)); + keyaddr+=4; + TDES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr)); + CRYP_KeyInit(& TDES_CRYP_KeyInitStructure); + + /* Flush IN/OUT FIFO */ + CRYP_FIFOFlush(); + + /* Enable Crypto processor */ + CRYP_Cmd(ENABLE); + + for(i=0; ((i
© COPYRIGHT 2011 STMicroelectronics
+ ****************************************************************************** + */ + + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_dac.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup DAC + * @brief DAC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* CR register Mask */ +#define CR_CLEAR_MASK ((uint32_t)0x00000FFE) + +/* DAC Dual Channels SWTRIG masks */ +#define DUAL_SWTRIG_SET ((uint32_t)0x00000003) +#define DUAL_SWTRIG_RESET ((uint32_t)0xFFFFFFFC) + +/* DHR registers offsets */ +#define DHR12R1_OFFSET ((uint32_t)0x00000008) +#define DHR12R2_OFFSET ((uint32_t)0x00000014) +#define DHR12RD_OFFSET ((uint32_t)0x00000020) + +/* DOR register offset */ +#define DOR_OFFSET ((uint32_t)0x0000002C) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup DAC_Private_Functions + * @{ + */ + +/** @defgroup DAC_Group1 DAC channels configuration + * @brief DAC channels configuration: trigger, output buffer, data format + * +@verbatim + =============================================================================== + DAC channels configuration: trigger, output buffer, data format + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the DAC peripheral registers to their default reset values. + * @param None + * @retval None + */ +void DAC_DeInit(void) +{ + /* Enable DAC reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE); + /* Release DAC from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE); +} + +/** + * @brief Initializes the DAC peripheral according to the specified parameters + * in the DAC_InitStruct. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure that contains + * the configuration information for the specified DAC channel. + * @retval None + */ +void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0; + + /* Check the DAC parameters */ + assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger)); + assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration)); + assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude)); + assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer)); + +/*---------------------------- DAC CR Configuration --------------------------*/ + /* Get the DAC CR value */ + tmpreg1 = DAC->CR; + /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */ + tmpreg1 &= ~(CR_CLEAR_MASK << DAC_Channel); + /* Configure for the selected DAC channel: buffer output, trigger, + wave generation, mask/amplitude for wave generation */ + /* Set TSELx and TENx bits according to DAC_Trigger value */ + /* Set WAVEx bits according to DAC_WaveGeneration value */ + /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */ + /* Set BOFFx bit according to DAC_OutputBuffer value */ + tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration | + DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | \ + DAC_InitStruct->DAC_OutputBuffer); + /* Calculate CR register value depending on DAC_Channel */ + tmpreg1 |= tmpreg2 << DAC_Channel; + /* Write to DAC CR */ + DAC->CR = tmpreg1; +} + +/** + * @brief Fills each DAC_InitStruct member with its default value. + * @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct) +{ +/*--------------- Reset DAC init structure parameters values -----------------*/ + /* Initialize the DAC_Trigger member */ + DAC_InitStruct->DAC_Trigger = DAC_Trigger_None; + /* Initialize the DAC_WaveGeneration member */ + DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None; + /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */ + DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0; + /* Initialize the DAC_OutputBuffer member */ + DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable; +} + +/** + * @brief Enables or disables the specified DAC channel. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the DAC channel. + * This parameter can be: ENABLE or DISABLE. + * @note When the DAC channel is enabled the trigger source can no more be modified. + * @retval None + */ +void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected DAC channel */ + DAC->CR |= (DAC_CR_EN1 << DAC_Channel); + } + else + { + /* Disable the selected DAC channel */ + DAC->CR &= (~(DAC_CR_EN1 << DAC_Channel)); + } +} + +/** + * @brief Enables or disables the selected DAC channel software trigger. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the selected DAC channel software trigger. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable software trigger for the selected DAC channel */ + DAC->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4); + } + else + { + /* Disable software trigger for the selected DAC channel */ + DAC->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4)); + } +} + +/** + * @brief Enables or disables simultaneously the two DAC channels software triggers. + * @param NewState: new state of the DAC channels software triggers. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_DualSoftwareTriggerCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable software trigger for both DAC channels */ + DAC->SWTRIGR |= DUAL_SWTRIG_SET; + } + else + { + /* Disable software trigger for both DAC channels */ + DAC->SWTRIGR &= DUAL_SWTRIG_RESET; + } +} + +/** + * @brief Enables or disables the selected DAC channel wave generation. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_Wave: specifies the wave type to enable or disable. + * This parameter can be one of the following values: + * @arg DAC_Wave_Noise: noise wave generation + * @arg DAC_Wave_Triangle: triangle wave generation + * @param NewState: new state of the selected DAC channel wave generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_WAVE(DAC_Wave)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected wave generation for the selected DAC channel */ + DAC->CR |= DAC_Wave << DAC_Channel; + } + else + { + /* Disable the selected wave generation for the selected DAC channel */ + DAC->CR &= ~(DAC_Wave << DAC_Channel); + } +} + +/** + * @brief Set the specified data holding register value for DAC channel1. + * @param DAC_Align: Specifies the data alignment for DAC channel1. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data: Data to be loaded in the selected data holding register. + * @retval None + */ +void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12R1_OFFSET + DAC_Align; + + /* Set the DAC channel1 selected data holding register */ + *(__IO uint32_t *) tmp = Data; +} + +/** + * @brief Set the specified data holding register value for DAC channel2. + * @param DAC_Align: Specifies the data alignment for DAC channel2. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data: Data to be loaded in the selected data holding register. + * @retval None + */ +void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12R2_OFFSET + DAC_Align; + + /* Set the DAC channel2 selected data holding register */ + *(__IO uint32_t *)tmp = Data; +} + +/** + * @brief Set the specified data holding register value for dual channel DAC. + * @param DAC_Align: Specifies the data alignment for dual channel DAC. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data2: Data for DAC Channel2 to be loaded in the selected data holding register. + * @param Data1: Data for DAC Channel1 to be loaded in the selected data holding register. + * @note In dual mode, a unique register access is required to write in both + * DAC channels at the same time. + * @retval None + */ +void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1) +{ + uint32_t data = 0, tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data1)); + assert_param(IS_DAC_DATA(Data2)); + + /* Calculate and set dual DAC data holding register value */ + if (DAC_Align == DAC_Align_8b_R) + { + data = ((uint32_t)Data2 << 8) | Data1; + } + else + { + data = ((uint32_t)Data2 << 16) | Data1; + } + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12RD_OFFSET + DAC_Align; + + /* Set the dual DAC selected data holding register */ + *(__IO uint32_t *)tmp = data; +} + +/** + * @brief Returns the last data output value of the selected DAC channel. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @retval The selected DAC channel data output value. + */ +uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + + tmp = (uint32_t) DAC_BASE ; + tmp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2); + + /* Returns the DAC channel data output register value */ + return (uint16_t) (*(__IO uint32_t*) tmp); +} +/** + * @} + */ + +/** @defgroup DAC_Group2 DMA management functions + * @brief DMA management functions + * +@verbatim + =============================================================================== + DMA management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified DAC channel DMA request. + * @note When enabled DMA1 is generated when an external trigger (EXTI Line9, + * TIM2, TIM4, TIM5, TIM6, TIM7 or TIM8 but not a software trigger) occurs. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the selected DAC channel DMA request. + * This parameter can be: ENABLE or DISABLE. + * @note The DAC channel1 is mapped on DMA1 Stream 5 channel7 which must be + * already configured. + * @note The DAC channel2 is mapped on DMA1 Stream 6 channel7 which must be + * already configured. + * @retval None + */ +void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected DAC channel DMA request */ + DAC->CR |= (DAC_CR_DMAEN1 << DAC_Channel); + } + else + { + /* Disable the selected DAC channel DMA request */ + DAC->CR &= (~(DAC_CR_DMAEN1 << DAC_Channel)); + } +} +/** + * @} + */ + +/** @defgroup DAC_Group3 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified DAC interrupts. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt sources to be enabled or disabled. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @note The DMA underrun occurs when a second external trigger arrives before the + * acknowledgement for the first external trigger is received (first request). + * @param NewState: new state of the specified DAC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_DAC_IT(DAC_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected DAC interrupts */ + DAC->CR |= (DAC_IT << DAC_Channel); + } + else + { + /* Disable the selected DAC interrupts */ + DAC->CR &= (~(uint32_t)(DAC_IT << DAC_Channel)); + } +} + +/** + * @brief Checks whether the specified DAC flag is set or not. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_FLAG: specifies the flag to check. + * This parameter can be only of the following value: + * @arg DAC_FLAG_DMAUDR: DMA underrun flag + * @note The DMA underrun occurs when a second external trigger arrives before the + * acknowledgement for the first external trigger is received (first request). + * @retval The new state of DAC_FLAG (SET or RESET). + */ +FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_FLAG(DAC_FLAG)); + + /* Check the status of the specified DAC flag */ + if ((DAC->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)RESET) + { + /* DAC_FLAG is set */ + bitstatus = SET; + } + else + { + /* DAC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the DAC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DAC channel's pending flags. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_FLAG: specifies the flag to clear. + * This parameter can be of the following value: + * @arg DAC_FLAG_DMAUDR: DMA underrun flag + * @note The DMA underrun occurs when a second external trigger arrives before the + * acknowledgement for the first external trigger is received (first request). + * @retval None + */ +void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_FLAG(DAC_FLAG)); + + /* Clear the selected DAC flags */ + DAC->SR = (DAC_FLAG << DAC_Channel); +} + +/** + * @brief Checks whether the specified DAC interrupt has occurred or not. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt source to check. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @note The DMA underrun occurs when a second external trigger arrives before the + * acknowledgement for the first external trigger is received (first request). + * @retval The new state of DAC_IT (SET or RESET). + */ +ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_IT(DAC_IT)); + + /* Get the DAC_IT enable bit status */ + enablestatus = (DAC->CR & (DAC_IT << DAC_Channel)) ; + + /* Check the status of the specified DAC interrupt */ + if (((DAC->SR & (DAC_IT << DAC_Channel)) != (uint32_t)RESET) && enablestatus) + { + /* DAC_IT is set */ + bitstatus = SET; + } + else + { + /* DAC_IT is reset */ + bitstatus = RESET; + } + /* Return the DAC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the DAC channel's interrupt pending bits. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt pending bit to clear. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @note The DMA underrun occurs when a second external trigger arrives before the + * acknowledgement for the first external trigger is received (first request). + * @retval None + */ +void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_IT(DAC_IT)); + + /* Clear the selected DAC interrupt pending bits */ + DAC->SR = (DAC_IT << DAC_Channel); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dbgmcu.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dbgmcu.c new file mode 100644 index 000000000..b81dff46c --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dbgmcu.c @@ -0,0 +1,174 @@ +/** + ****************************************************************************** + * @file stm32f4xx_dbgmcu.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides all the DBGMCU firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_dbgmcu.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup DBGMCU + * @brief DBGMCU driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define IDCODE_DEVID_MASK ((uint32_t)0x00000FFF) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup DBGMCU_Private_Functions + * @{ + */ + +/** + * @brief Returns the device revision identifier. + * @param None + * @retval Device revision identifier + */ +uint32_t DBGMCU_GetREVID(void) +{ + return(DBGMCU->IDCODE >> 16); +} + +/** + * @brief Returns the device identifier. + * @param None + * @retval Device identifier + */ +uint32_t DBGMCU_GetDEVID(void) +{ + return(DBGMCU->IDCODE & IDCODE_DEVID_MASK); +} + +/** + * @brief Configures low power mode behavior when the MCU is in Debug mode. + * @param DBGMCU_Periph: specifies the low power mode. + * This parameter can be any combination of the following values: + * @arg DBGMCU_SLEEP: Keep debugger connection during SLEEP mode + * @arg DBGMCU_STOP: Keep debugger connection during STOP mode + * @arg DBGMCU_STANDBY: Keep debugger connection during STANDBY mode + * @param NewState: new state of the specified low power mode in Debug mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + DBGMCU->CR |= DBGMCU_Periph; + } + else + { + DBGMCU->CR &= ~DBGMCU_Periph; + } +} + +/** + * @brief Configures APB1 peripheral behavior when the MCU is in Debug mode. + * @param DBGMCU_Periph: specifies the APB1 peripheral. + * This parameter can be any combination of the following values: + * @arg DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted + * @arg DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted + * @arg DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted + * @arg DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted + * @arg DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted + * @arg DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted + * @arg DBGMCU_TIM12_STOP: TIM12 counter stopped when Core is halted + * @arg DBGMCU_TIM13_STOP: TIM13 counter stopped when Core is halted + * @arg DBGMCU_TIM14_STOP: TIM14 counter stopped when Core is halted + * @arg DBGMCU_RTC_STOP: RTC Calendar and Wakeup counter stopped when Core is halted. + * @arg DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted + * @arg DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted + * @arg DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped when Core is halted + * @arg DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped when Core is halted + * @arg DBGMCU_I2C3_SMBUS_TIMEOUT: I2C3 SMBUS timeout mode stopped when Core is halted + * @arg DBGMCU_CAN2_STOP: Debug CAN1 stopped when Core is halted + * @arg DBGMCU_CAN1_STOP: Debug CAN2 stopped when Core is halted + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DBGMCU_APB1PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DBGMCU_APB1PERIPH(DBGMCU_Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + DBGMCU->APB1FZ |= DBGMCU_Periph; + } + else + { + DBGMCU->APB1FZ &= ~DBGMCU_Periph; + } +} + +/** + * @brief Configures APB2 peripheral behavior when the MCU is in Debug mode. + * @param DBGMCU_Periph: specifies the APB2 peripheral. + * This parameter can be any combination of the following values: + * @arg DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted + * @arg DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted + * @arg DBGMCU_TIM9_STOP: TIM9 counter stopped when Core is halted + * @arg DBGMCU_TIM10_STOP: TIM10 counter stopped when Core is halted + * @arg DBGMCU_TIM11_STOP: TIM11 counter stopped when Core is halted + * @param NewState: new state of the specified peripheral in Debug mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DBGMCU_APB2PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DBGMCU_APB2PERIPH(DBGMCU_Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + DBGMCU->APB2FZ |= DBGMCU_Periph; + } + else + { + DBGMCU->APB2FZ &= ~DBGMCU_Periph; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c new file mode 100644 index 000000000..3ffc36d7c --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c @@ -0,0 +1,534 @@ +/** + ****************************************************************************** + * @file stm32f4xx_dcmi.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the DCMI peripheral: + * - Initialization and Configuration + * - Image capture functions + * - Interrupts and flags management + * + * @verbatim + * + * + * =================================================================== + * How to use this driver + * =================================================================== + * + * The sequence below describes how to use this driver to capture image + * from a camera module connected to the DCMI Interface. + * This sequence does not take into account the configuration of the + * camera module, which should be made before to configure and enable + * the DCMI to capture images. + * + * 1. Enable the clock for the DCMI and associated GPIOs using the following functions: + * RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_DCMI, ENABLE); + * RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE); + * + * 2. DCMI pins configuration + * - Connect the involved DCMI pins to AF13 using the following function + * GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_DCMI); + * - Configure these DCMI pins in alternate function mode by calling the function + * GPIO_Init(); + * + * 3. Declare a DCMI_InitTypeDef structure, for example: + * DCMI_InitTypeDef DCMI_InitStructure; + * and fill the DCMI_InitStructure variable with the allowed values + * of the structure member. + * + * 4. Initialize the DCMI interface by calling the function + * DCMI_Init(&DCMI_InitStructure); + * + * 5. Configure the DMA2_Stream1 channel1 to transfer Data from DCMI DR + * register to the destination memory buffer. + * + * 6. Enable DCMI interface using the function + * DCMI_Cmd(ENABLE); + * + * 7. Start the image capture using the function + * DCMI_CaptureCmd(ENABLE); + * + * 8. At this stage the DCMI interface waits for the first start of frame, + * then a DMA request is generated continuously/once (depending on the + * mode used, Continuous/Snapshot) to transfer the received data into + * the destination memory. + * + * @note If you need to capture only a rectangular window from the received + * image, you have to use the DCMI_CROPConfig() function to configure + * the coordinates and size of the window to be captured, then enable + * the Crop feature using DCMI_CROPCmd(ENABLE); + * In this case, the Crop configuration should be made before to enable + * and start the DCMI interface. + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_dcmi.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup DCMI + * @brief DCMI driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup DCMI_Private_Functions + * @{ + */ + +/** @defgroup DCMI_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the DCMI registers to their default reset values. + * @param None + * @retval None + */ +void DCMI_DeInit(void) +{ + DCMI->CR = 0x0; + DCMI->IER = 0x0; + DCMI->ICR = 0x1F; + DCMI->ESCR = 0x0; + DCMI->ESUR = 0x0; + DCMI->CWSTRTR = 0x0; + DCMI->CWSIZER = 0x0; +} + +/** + * @brief Initializes the DCMI according to the specified parameters in the DCMI_InitStruct. + * @param DCMI_InitStruct: pointer to a DCMI_InitTypeDef structure that contains + * the configuration information for the DCMI. + * @retval None + */ +void DCMI_Init(DCMI_InitTypeDef* DCMI_InitStruct) +{ + uint32_t temp = 0x0; + + /* Check the parameters */ + assert_param(IS_DCMI_CAPTURE_MODE(DCMI_InitStruct->DCMI_CaptureMode)); + assert_param(IS_DCMI_SYNCHRO(DCMI_InitStruct->DCMI_SynchroMode)); + assert_param(IS_DCMI_PCKPOLARITY(DCMI_InitStruct->DCMI_PCKPolarity)); + assert_param(IS_DCMI_VSPOLARITY(DCMI_InitStruct->DCMI_VSPolarity)); + assert_param(IS_DCMI_HSPOLARITY(DCMI_InitStruct->DCMI_HSPolarity)); + assert_param(IS_DCMI_CAPTURE_RATE(DCMI_InitStruct->DCMI_CaptureRate)); + assert_param(IS_DCMI_EXTENDED_DATA(DCMI_InitStruct->DCMI_ExtendedDataMode)); + + /* The DCMI configuration registers should be programmed correctly before + enabling the CR_ENABLE Bit and the CR_CAPTURE Bit */ + DCMI->CR &= ~(DCMI_CR_ENABLE | DCMI_CR_CAPTURE); + + /* Reset the old DCMI configuration */ + temp = DCMI->CR; + + temp &= ~((uint32_t)DCMI_CR_CM | DCMI_CR_ESS | DCMI_CR_PCKPOL | + DCMI_CR_HSPOL | DCMI_CR_VSPOL | DCMI_CR_FCRC_0 | + DCMI_CR_FCRC_1 | DCMI_CR_EDM_0 | DCMI_CR_EDM_1); + + /* Sets the new configuration of the DCMI peripheral */ + temp |= ((uint32_t)DCMI_InitStruct->DCMI_CaptureMode | + DCMI_InitStruct->DCMI_SynchroMode | + DCMI_InitStruct->DCMI_PCKPolarity | + DCMI_InitStruct->DCMI_VSPolarity | + DCMI_InitStruct->DCMI_HSPolarity | + DCMI_InitStruct->DCMI_CaptureRate | + DCMI_InitStruct->DCMI_ExtendedDataMode); + + DCMI->CR = temp; +} + +/** + * @brief Fills each DCMI_InitStruct member with its default value. + * @param DCMI_InitStruct : pointer to a DCMI_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DCMI_StructInit(DCMI_InitTypeDef* DCMI_InitStruct) +{ + /* Set the default configuration */ + DCMI_InitStruct->DCMI_CaptureMode = DCMI_CaptureMode_Continuous; + DCMI_InitStruct->DCMI_SynchroMode = DCMI_SynchroMode_Hardware; + DCMI_InitStruct->DCMI_PCKPolarity = DCMI_PCKPolarity_Falling; + DCMI_InitStruct->DCMI_VSPolarity = DCMI_VSPolarity_Low; + DCMI_InitStruct->DCMI_HSPolarity = DCMI_HSPolarity_Low; + DCMI_InitStruct->DCMI_CaptureRate = DCMI_CaptureRate_All_Frame; + DCMI_InitStruct->DCMI_ExtendedDataMode = DCMI_ExtendedDataMode_8b; +} + +/** + * @brief Initializes the DCMI peripheral CROP mode according to the specified + * parameters in the DCMI_CROPInitStruct. + * @note This function should be called before to enable and start the DCMI interface. + * @param DCMI_CROPInitStruct: pointer to a DCMI_CROPInitTypeDef structure that + * contains the configuration information for the DCMI peripheral CROP mode. + * @retval None + */ +void DCMI_CROPConfig(DCMI_CROPInitTypeDef* DCMI_CROPInitStruct) +{ + /* Sets the CROP window coordinates */ + DCMI->CWSTRTR = (uint32_t)((uint32_t)DCMI_CROPInitStruct->DCMI_HorizontalOffsetCount | + ((uint32_t)DCMI_CROPInitStruct->DCMI_VerticalStartLine << 16)); + + /* Sets the CROP window size */ + DCMI->CWSIZER = (uint32_t)(DCMI_CROPInitStruct->DCMI_CaptureCount | + ((uint32_t)DCMI_CROPInitStruct->DCMI_VerticalLineCount << 16)); +} + +/** + * @brief Enables or disables the DCMI Crop feature. + * @note This function should be called before to enable and start the DCMI interface. + * @param NewState: new state of the DCMI Crop feature. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DCMI_CROPCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DCMI Crop feature */ + DCMI->CR |= (uint32_t)DCMI_CR_CROP; + } + else + { + /* Disable the DCMI Crop feature */ + DCMI->CR &= ~(uint32_t)DCMI_CR_CROP; + } +} + +/** + * @brief Sets the embedded synchronization codes + * @param DCMI_CodesInitTypeDef: pointer to a DCMI_CodesInitTypeDef structure that + * contains the embedded synchronization codes for the DCMI peripheral. + * @retval None + */ +void DCMI_SetEmbeddedSynchroCodes(DCMI_CodesInitTypeDef* DCMI_CodesInitStruct) +{ + DCMI->ESCR = (uint32_t)(DCMI_CodesInitStruct->DCMI_FrameStartCode | + ((uint32_t)DCMI_CodesInitStruct->DCMI_LineStartCode << 8)| + ((uint32_t)DCMI_CodesInitStruct->DCMI_LineEndCode << 16)| + ((uint32_t)DCMI_CodesInitStruct->DCMI_FrameEndCode << 24)); +} + +/** + * @brief Enables or disables the DCMI JPEG format. + * @note The Crop and Embedded Synchronization features cannot be used in this mode. + * @param NewState: new state of the DCMI JPEG format. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DCMI_JPEGCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DCMI JPEG format */ + DCMI->CR |= (uint32_t)DCMI_CR_JPEG; + } + else + { + /* Disable the DCMI JPEG format */ + DCMI->CR &= ~(uint32_t)DCMI_CR_JPEG; + } +} +/** + * @} + */ + +/** @defgroup DCMI_Group2 Image capture functions + * @brief Image capture functions + * +@verbatim + =============================================================================== + Image capture functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the DCMI interface. + * @param NewState: new state of the DCMI interface. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DCMI_Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DCMI by setting ENABLE bit */ + DCMI->CR |= (uint32_t)DCMI_CR_ENABLE; + } + else + { + /* Disable the DCMI by clearing ENABLE bit */ + DCMI->CR &= ~(uint32_t)DCMI_CR_ENABLE; + } +} + +/** + * @brief Enables or disables the DCMI Capture. + * @param NewState: new state of the DCMI capture. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DCMI_CaptureCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DCMI Capture */ + DCMI->CR |= (uint32_t)DCMI_CR_CAPTURE; + } + else + { + /* Disable the DCMI Capture */ + DCMI->CR &= ~(uint32_t)DCMI_CR_CAPTURE; + } +} + +/** + * @brief Reads the data stored in the DR register. + * @param None + * @retval Data register value + */ +uint32_t DCMI_ReadData(void) +{ + return DCMI->DR; +} +/** + * @} + */ + +/** @defgroup DCMI_Group3 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the DCMI interface interrupts. + * @param DCMI_IT: specifies the DCMI interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg DCMI_IT_FRAME: Frame capture complete interrupt mask + * @arg DCMI_IT_OVF: Overflow interrupt mask + * @arg DCMI_IT_ERR: Synchronization error interrupt mask + * @arg DCMI_IT_VSYNC: VSYNC interrupt mask + * @arg DCMI_IT_LINE: Line interrupt mask + * @param NewState: new state of the specified DCMI interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DCMI_ITConfig(uint16_t DCMI_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DCMI_CONFIG_IT(DCMI_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Interrupt sources */ + DCMI->IER |= DCMI_IT; + } + else + { + /* Disable the Interrupt sources */ + DCMI->IER &= (uint16_t)(~DCMI_IT); + } +} + +/** + * @brief Checks whether the DCMI interface flag is set or not. + * @param DCMI_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg DCMI_FLAG_FRAMERI: Frame capture complete Raw flag mask + * @arg DCMI_FLAG_OVFRI: Overflow Raw flag mask + * @arg DCMI_FLAG_ERRRI: Synchronization error Raw flag mask + * @arg DCMI_FLAG_VSYNCRI: VSYNC Raw flag mask + * @arg DCMI_FLAG_LINERI: Line Raw flag mask + * @arg DCMI_FLAG_FRAMEMI: Frame capture complete Masked flag mask + * @arg DCMI_FLAG_OVFMI: Overflow Masked flag mask + * @arg DCMI_FLAG_ERRMI: Synchronization error Masked flag mask + * @arg DCMI_FLAG_VSYNCMI: VSYNC Masked flag mask + * @arg DCMI_FLAG_LINEMI: Line Masked flag mask + * @arg DCMI_FLAG_HSYNC: HSYNC flag mask + * @arg DCMI_FLAG_VSYNC: VSYNC flag mask + * @arg DCMI_FLAG_FNE: Fifo not empty flag mask + * @retval The new state of DCMI_FLAG (SET or RESET). + */ +FlagStatus DCMI_GetFlagStatus(uint16_t DCMI_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t dcmireg, tempreg = 0; + + /* Check the parameters */ + assert_param(IS_DCMI_GET_FLAG(DCMI_FLAG)); + + /* Get the DCMI register index */ + dcmireg = (((uint16_t)DCMI_FLAG) >> 12); + + if (dcmireg == 0x01) /* The FLAG is in RISR register */ + { + tempreg= DCMI->RISR; + } + else if (dcmireg == 0x02) /* The FLAG is in SR register */ + { + tempreg = DCMI->SR; + } + else /* The FLAG is in MISR register */ + { + tempreg = DCMI->MISR; + } + + if ((tempreg & DCMI_FLAG) != (uint16_t)RESET ) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the DCMI_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DCMI's pending flags. + * @param DCMI_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg DCMI_FLAG_FRAMERI: Frame capture complete Raw flag mask + * @arg DCMI_FLAG_OVFRI: Overflow Raw flag mask + * @arg DCMI_FLAG_ERRRI: Synchronization error Raw flag mask + * @arg DCMI_FLAG_VSYNCRI: VSYNC Raw flag mask + * @arg DCMI_FLAG_LINERI: Line Raw flag mask + * @retval None + */ +void DCMI_ClearFlag(uint16_t DCMI_FLAG) +{ + /* Check the parameters */ + assert_param(IS_DCMI_CLEAR_FLAG(DCMI_FLAG)); + + /* Clear the flag by writing in the ICR register 1 in the corresponding + Flag position*/ + + DCMI->ICR = DCMI_FLAG; +} + +/** + * @brief Checks whether the DCMI interrupt has occurred or not. + * @param DCMI_IT: specifies the DCMI interrupt source to check. + * This parameter can be one of the following values: + * @arg DCMI_IT_FRAME: Frame capture complete interrupt mask + * @arg DCMI_IT_OVF: Overflow interrupt mask + * @arg DCMI_IT_ERR: Synchronization error interrupt mask + * @arg DCMI_IT_VSYNC: VSYNC interrupt mask + * @arg DCMI_IT_LINE: Line interrupt mask + * @retval The new state of DCMI_IT (SET or RESET). + */ +ITStatus DCMI_GetITStatus(uint16_t DCMI_IT) +{ + ITStatus bitstatus = RESET; + uint32_t itstatus = 0; + + /* Check the parameters */ + assert_param(IS_DCMI_GET_IT(DCMI_IT)); + + itstatus = DCMI->MISR & DCMI_IT; /* Only masked interrupts are checked */ + + if ((itstatus != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the DCMI's interrupt pending bits. + * @param DCMI_IT: specifies the DCMI interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg DCMI_IT_FRAME: Frame capture complete interrupt mask + * @arg DCMI_IT_OVF: Overflow interrupt mask + * @arg DCMI_IT_ERR: Synchronization error interrupt mask + * @arg DCMI_IT_VSYNC: VSYNC interrupt mask + * @arg DCMI_IT_LINE: Line interrupt mask + * @retval None + */ +void DCMI_ClearITPendingBit(uint16_t DCMI_IT) +{ + /* Clear the interrupt pending Bit by writing in the ICR register 1 in the + corresponding pending Bit position*/ + + DCMI->ICR = DCMI_IT; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c new file mode 100644 index 000000000..c2868cff2 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c @@ -0,0 +1,1283 @@ +/** + ****************************************************************************** + * @file stm32f4xx_dma.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Direct Memory Access controller (DMA): + * - Initialization and Configuration + * - Data Counter + * - Double Buffer mode configuration and command + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * 1. Enable The DMA controller clock using RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_DMA1, ENABLE) + * function for DMA1 or using RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_DMA2, ENABLE) + * function for DMA2. + * + * 2. Enable and configure the peripheral to be connected to the DMA Stream + * (except for internal SRAM / FLASH memories: no initialization is + * necessary). + * + * 3. For a given Stream, program the required configuration through following parameters: + * Source and Destination addresses, Transfer Direction, Transfer size, Source and Destination + * data formats, Circular or Normal mode, Stream Priority level, Source and Destination + * Incrementation mode, FIFO mode and its Threshold (if needed), Burst mode for Source and/or + * Destination (if needed) using the DMA_Init() function. + * To avoid filling un-nesecessary fields, you can call DMA_StructInit() function + * to initialize a given structure with default values (reset values), the modify + * only necessary fields (ie. Source and Destination addresses, Transfer size and Data Formats). + * + * 4. Enable the NVIC and the corresponding interrupt(s) using the function + * DMA_ITConfig() if you need to use DMA interrupts. + * + * 5. Optionally, if the Circular mode is enabled, you can use the Double buffer mode by configuring + * the second Memory address and the first Memory to be used through the function + * DMA_DoubleBufferModeConfig(). Then enable the Double buffer mode through the function + * DMA_DoubleBufferModeCmd(). These operations must be done before step 6. + * + * 6. Enable the DMA stream using the DMA_Cmd() function. + * + * 7. Activate the needed Stream Request using PPP_DMACmd() function for + * any PPP peripheral except internal SRAM and FLASH (ie. SPI, USART ...) + * The function allowing this operation is provided in each PPP peripheral + * driver (ie. SPI_DMACmd for SPI peripheral). + * Once the Stream is enabled, it is not possible to modify its configuration + * unless the stream is stopped and disabled. + * After enabling the Stream, it is advised to monitor the EN bit status using + * the function DMA_GetCmdStatus(). In case of configuration errors or bus errors + * this bit will remain reset and all transfers on this Stream will remain on hold. + * + * 8. Optionally, you can configure the number of data to be transferred + * when the Stream is disabled (ie. after each Transfer Complete event + * or when a Transfer Error occurs) using the function DMA_SetCurrDataCounter(). + * And you can get the number of remaining data to be transferred using + * the function DMA_GetCurrDataCounter() at run time (when the DMA Stream is + * enabled and running). + * + * 9. To control DMA events you can use one of the following + * two methods: + * a- Check on DMA Stream flags using the function DMA_GetFlagStatus(). + * b- Use DMA interrupts through the function DMA_ITConfig() at initialization + * phase and DMA_GetITStatus() function into interrupt routines in + * communication phase. + * After checking on a flag you should clear it using DMA_ClearFlag() + * function. And after checking on an interrupt event you should + * clear it using DMA_ClearITPendingBit() function. + * + * 10. Optionally, if Circular mode and Double Buffer mode are enabled, you can modify + * the Memory Addresses using the function DMA_MemoryTargetConfig(). Make sure that + * the Memory Address to be modified is not the one currently in use by DMA Stream. + * This condition can be monitored using the function DMA_GetCurrentMemoryTarget(). + * + * 11. Optionally, Pause-Resume operations may be performed: + * The DMA_Cmd() function may be used to perform Pause-Resume operation. When a + * transfer is ongoing, calling this function to disable the Stream will cause the + * transfer to be paused. All configuration registers and the number of remaining + * data will be preserved. When calling again this function to re-enable the Stream, + * the transfer will be resumed from the point where it was paused. + * + * @note Memory-to-Memory transfer is possible by setting the address of the memory into + * the Peripheral registers. In this mode, Circular mode and Double Buffer mode + * are not allowed. + * + * @note The FIFO is used mainly to reduce bus usage and to allow data packing/unpacking: it is + * possible to set different Data Sizes for the Peripheral and the Memory (ie. you can set + * Half-Word data size for the peripheral to access its data register and set Word data size + * for the Memory to gain in access time. Each two Half-words will be packed and written in + * a single access to a Word in the Memory). + * + * @note When FIFO is disabled, it is not allowed to configure different Data Sizes for Source + * and Destination. In this case the Peripheral Data Size will be applied to both Source + * and Destination. + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_dma.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup DMA + * @brief DMA driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* Masks Definition */ +#define TRANSFER_IT_ENABLE_MASK (uint32_t)(DMA_SxCR_TCIE | DMA_SxCR_HTIE | \ + DMA_SxCR_TEIE | DMA_SxCR_DMEIE) + +#define DMA_Stream0_IT_MASK (uint32_t)(DMA_LISR_FEIF0 | DMA_LISR_DMEIF0 | \ + DMA_LISR_TEIF0 | DMA_LISR_HTIF0 | \ + DMA_LISR_TCIF0) + +#define DMA_Stream1_IT_MASK (uint32_t)(DMA_Stream0_IT_MASK << 6) +#define DMA_Stream2_IT_MASK (uint32_t)(DMA_Stream0_IT_MASK << 16) +#define DMA_Stream3_IT_MASK (uint32_t)(DMA_Stream0_IT_MASK << 22) +#define DMA_Stream4_IT_MASK (uint32_t)(DMA_Stream0_IT_MASK | (uint32_t)0x20000000) +#define DMA_Stream5_IT_MASK (uint32_t)(DMA_Stream1_IT_MASK | (uint32_t)0x20000000) +#define DMA_Stream6_IT_MASK (uint32_t)(DMA_Stream2_IT_MASK | (uint32_t)0x20000000) +#define DMA_Stream7_IT_MASK (uint32_t)(DMA_Stream3_IT_MASK | (uint32_t)0x20000000) +#define TRANSFER_IT_MASK (uint32_t)0x0F3C0F3C +#define HIGH_ISR_MASK (uint32_t)0x20000000 +#define RESERVED_MASK (uint32_t)0x0F7D0F7D + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + + +/** @defgroup DMA_Private_Functions + * @{ + */ + +/** @defgroup DMA_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + + This subsection provides functions allowing to initialize the DMA Stream source + and destination addresses, incrementation and data sizes, transfer direction, + buffer size, circular/normal mode selection, memory-to-memory mode selection + and Stream priority value. + + The DMA_Init() function follows the DMA configuration procedures as described in + reference manual (RM0090) except the first point: waiting on EN bit to be reset. + This condition should be checked by user application using the function DMA_GetCmdStatus() + before calling the DMA_Init() function. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitialize the DMAy Streamx registers to their default reset values. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @retval None + */ +void DMA_DeInit(DMA_Stream_TypeDef* DMAy_Streamx) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + + /* Disable the selected DMAy Streamx */ + DMAy_Streamx->CR &= ~((uint32_t)DMA_SxCR_EN); + + /* Reset DMAy Streamx control register */ + DMAy_Streamx->CR = 0; + + /* Reset DMAy Streamx Number of Data to Transfer register */ + DMAy_Streamx->NDTR = 0; + + /* Reset DMAy Streamx peripheral address register */ + DMAy_Streamx->PAR = 0; + + /* Reset DMAy Streamx memory 0 address register */ + DMAy_Streamx->M0AR = 0; + + /* Reset DMAy Streamx memory 1 address register */ + DMAy_Streamx->M1AR = 0; + + /* Reset DMAy Streamx FIFO control register */ + DMAy_Streamx->FCR = (uint32_t)0x00000021; + + /* Reset interrupt pending bits for the selected stream */ + if (DMAy_Streamx == DMA1_Stream0) + { + /* Reset interrupt pending bits for DMA1 Stream0 */ + DMA1->LIFCR = DMA_Stream0_IT_MASK; + } + else if (DMAy_Streamx == DMA1_Stream1) + { + /* Reset interrupt pending bits for DMA1 Stream1 */ + DMA1->LIFCR = DMA_Stream1_IT_MASK; + } + else if (DMAy_Streamx == DMA1_Stream2) + { + /* Reset interrupt pending bits for DMA1 Stream2 */ + DMA1->LIFCR = DMA_Stream2_IT_MASK; + } + else if (DMAy_Streamx == DMA1_Stream3) + { + /* Reset interrupt pending bits for DMA1 Stream3 */ + DMA1->LIFCR = DMA_Stream3_IT_MASK; + } + else if (DMAy_Streamx == DMA1_Stream4) + { + /* Reset interrupt pending bits for DMA1 Stream4 */ + DMA1->HIFCR = DMA_Stream4_IT_MASK; + } + else if (DMAy_Streamx == DMA1_Stream5) + { + /* Reset interrupt pending bits for DMA1 Stream5 */ + DMA1->HIFCR = DMA_Stream5_IT_MASK; + } + else if (DMAy_Streamx == DMA1_Stream6) + { + /* Reset interrupt pending bits for DMA1 Stream6 */ + DMA1->HIFCR = (uint32_t)DMA_Stream6_IT_MASK; + } + else if (DMAy_Streamx == DMA1_Stream7) + { + /* Reset interrupt pending bits for DMA1 Stream7 */ + DMA1->HIFCR = DMA_Stream7_IT_MASK; + } + else if (DMAy_Streamx == DMA2_Stream0) + { + /* Reset interrupt pending bits for DMA2 Stream0 */ + DMA2->LIFCR = DMA_Stream0_IT_MASK; + } + else if (DMAy_Streamx == DMA2_Stream1) + { + /* Reset interrupt pending bits for DMA2 Stream1 */ + DMA2->LIFCR = DMA_Stream1_IT_MASK; + } + else if (DMAy_Streamx == DMA2_Stream2) + { + /* Reset interrupt pending bits for DMA2 Stream2 */ + DMA2->LIFCR = DMA_Stream2_IT_MASK; + } + else if (DMAy_Streamx == DMA2_Stream3) + { + /* Reset interrupt pending bits for DMA2 Stream3 */ + DMA2->LIFCR = DMA_Stream3_IT_MASK; + } + else if (DMAy_Streamx == DMA2_Stream4) + { + /* Reset interrupt pending bits for DMA2 Stream4 */ + DMA2->HIFCR = DMA_Stream4_IT_MASK; + } + else if (DMAy_Streamx == DMA2_Stream5) + { + /* Reset interrupt pending bits for DMA2 Stream5 */ + DMA2->HIFCR = DMA_Stream5_IT_MASK; + } + else if (DMAy_Streamx == DMA2_Stream6) + { + /* Reset interrupt pending bits for DMA2 Stream6 */ + DMA2->HIFCR = DMA_Stream6_IT_MASK; + } + else + { + if (DMAy_Streamx == DMA2_Stream7) + { + /* Reset interrupt pending bits for DMA2 Stream7 */ + DMA2->HIFCR = DMA_Stream7_IT_MASK; + } + } +} + +/** + * @brief Initializes the DMAy Streamx according to the specified parameters in + * the DMA_InitStruct structure. + * @note Before calling this function, it is recommended to check that the Stream + * is actually disabled using the function DMA_GetCmdStatus(). + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param DMA_InitStruct: pointer to a DMA_InitTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval None + */ +void DMA_Init(DMA_Stream_TypeDef* DMAy_Streamx, DMA_InitTypeDef* DMA_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_DMA_CHANNEL(DMA_InitStruct->DMA_Channel)); + assert_param(IS_DMA_DIRECTION(DMA_InitStruct->DMA_DIR)); + assert_param(IS_DMA_BUFFER_SIZE(DMA_InitStruct->DMA_BufferSize)); + assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc)); + assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc)); + assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize)); + assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize)); + assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode)); + assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority)); + assert_param(IS_DMA_FIFO_MODE_STATE(DMA_InitStruct->DMA_FIFOMode)); + assert_param(IS_DMA_FIFO_THRESHOLD(DMA_InitStruct->DMA_FIFOThreshold)); + assert_param(IS_DMA_MEMORY_BURST(DMA_InitStruct->DMA_MemoryBurst)); + assert_param(IS_DMA_PERIPHERAL_BURST(DMA_InitStruct->DMA_PeripheralBurst)); + + /*------------------------- DMAy Streamx CR Configuration ------------------*/ + /* Get the DMAy_Streamx CR value */ + tmpreg = DMAy_Streamx->CR; + + /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */ + tmpreg &= ((uint32_t)~(DMA_SxCR_CHSEL | DMA_SxCR_MBURST | DMA_SxCR_PBURST | \ + DMA_SxCR_PL | DMA_SxCR_MSIZE | DMA_SxCR_PSIZE | \ + DMA_SxCR_MINC | DMA_SxCR_PINC | DMA_SxCR_CIRC | \ + DMA_SxCR_DIR)); + + /* Configure DMAy Streamx: */ + /* Set CHSEL bits according to DMA_CHSEL value */ + /* Set DIR bits according to DMA_DIR value */ + /* Set PINC bit according to DMA_PeripheralInc value */ + /* Set MINC bit according to DMA_MemoryInc value */ + /* Set PSIZE bits according to DMA_PeripheralDataSize value */ + /* Set MSIZE bits according to DMA_MemoryDataSize value */ + /* Set CIRC bit according to DMA_Mode value */ + /* Set PL bits according to DMA_Priority value */ + /* Set MBURST bits according to DMA_MemoryBurst value */ + /* Set PBURST bits according to DMA_PeripheralBurst value */ + tmpreg |= DMA_InitStruct->DMA_Channel | DMA_InitStruct->DMA_DIR | + DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc | + DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize | + DMA_InitStruct->DMA_Mode | DMA_InitStruct->DMA_Priority | + DMA_InitStruct->DMA_MemoryBurst | DMA_InitStruct->DMA_PeripheralBurst; + + /* Write to DMAy Streamx CR register */ + DMAy_Streamx->CR = tmpreg; + + /*------------------------- DMAy Streamx FCR Configuration -----------------*/ + /* Get the DMAy_Streamx FCR value */ + tmpreg = DMAy_Streamx->FCR; + + /* Clear DMDIS and FTH bits */ + tmpreg &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH); + + /* Configure DMAy Streamx FIFO: + Set DMDIS bits according to DMA_FIFOMode value + Set FTH bits according to DMA_FIFOThreshold value */ + tmpreg |= DMA_InitStruct->DMA_FIFOMode | DMA_InitStruct->DMA_FIFOThreshold; + + /* Write to DMAy Streamx CR */ + DMAy_Streamx->FCR = tmpreg; + + /*------------------------- DMAy Streamx NDTR Configuration ----------------*/ + /* Write to DMAy Streamx NDTR register */ + DMAy_Streamx->NDTR = DMA_InitStruct->DMA_BufferSize; + + /*------------------------- DMAy Streamx PAR Configuration -----------------*/ + /* Write to DMAy Streamx PAR */ + DMAy_Streamx->PAR = DMA_InitStruct->DMA_PeripheralBaseAddr; + + /*------------------------- DMAy Streamx M0AR Configuration ----------------*/ + /* Write to DMAy Streamx M0AR */ + DMAy_Streamx->M0AR = DMA_InitStruct->DMA_Memory0BaseAddr; +} + +/** + * @brief Fills each DMA_InitStruct member with its default value. + * @param DMA_InitStruct : pointer to a DMA_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct) +{ + /*-------------- Reset DMA init structure parameters values ----------------*/ + /* Initialize the DMA_Channel member */ + DMA_InitStruct->DMA_Channel = 0; + + /* Initialize the DMA_PeripheralBaseAddr member */ + DMA_InitStruct->DMA_PeripheralBaseAddr = 0; + + /* Initialize the DMA_Memory0BaseAddr member */ + DMA_InitStruct->DMA_Memory0BaseAddr = 0; + + /* Initialize the DMA_DIR member */ + DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralToMemory; + + /* Initialize the DMA_BufferSize member */ + DMA_InitStruct->DMA_BufferSize = 0; + + /* Initialize the DMA_PeripheralInc member */ + DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable; + + /* Initialize the DMA_MemoryInc member */ + DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable; + + /* Initialize the DMA_PeripheralDataSize member */ + DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + + /* Initialize the DMA_MemoryDataSize member */ + DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + + /* Initialize the DMA_Mode member */ + DMA_InitStruct->DMA_Mode = DMA_Mode_Normal; + + /* Initialize the DMA_Priority member */ + DMA_InitStruct->DMA_Priority = DMA_Priority_Low; + + /* Initialize the DMA_FIFOMode member */ + DMA_InitStruct->DMA_FIFOMode = DMA_FIFOMode_Disable; + + /* Initialize the DMA_FIFOThreshold member */ + DMA_InitStruct->DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull; + + /* Initialize the DMA_MemoryBurst member */ + DMA_InitStruct->DMA_MemoryBurst = DMA_MemoryBurst_Single; + + /* Initialize the DMA_PeripheralBurst member */ + DMA_InitStruct->DMA_PeripheralBurst = DMA_PeripheralBurst_Single; +} + +/** + * @brief Enables or disables the specified DMAy Streamx. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param NewState: new state of the DMAy Streamx. + * This parameter can be: ENABLE or DISABLE. + * + * @note This function may be used to perform Pause-Resume operation. When a + * transfer is ongoing, calling this function to disable the Stream will + * cause the transfer to be paused. All configuration registers and the + * number of remaining data will be preserved. When calling again this + * function to re-enable the Stream, the transfer will be resumed from + * the point where it was paused. + * + * @note After configuring the DMA Stream (DMA_Init() function) and enabling the + * stream, it is recommended to check (or wait until) the DMA Stream is + * effectively enabled. A Stream may remain disabled if a configuration + * parameter is wrong. + * After disabling a DMA Stream, it is also recommended to check (or wait + * until) the DMA Stream is effectively disabled. If a Stream is disabled + * while a data transfer is ongoing, the current data will be transferred + * and the Stream will be effectively disabled only after the transfer of + * this single data is finished. + * + * @retval None + */ +void DMA_Cmd(DMA_Stream_TypeDef* DMAy_Streamx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected DMAy Streamx by setting EN bit */ + DMAy_Streamx->CR |= (uint32_t)DMA_SxCR_EN; + } + else + { + /* Disable the selected DMAy Streamx by clearing EN bit */ + DMAy_Streamx->CR &= ~(uint32_t)DMA_SxCR_EN; + } +} + +/** + * @brief Configures, when the PINC (Peripheral Increment address mode) bit is + * set, if the peripheral address should be incremented with the data + * size (configured with PSIZE bits) or by a fixed offset equal to 4 + * (32-bit aligned addresses). + * + * @note This function has no effect if the Peripheral Increment mode is disabled. + * + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param DMA_Pincos: specifies the Peripheral increment offset size. + * This parameter can be one of the following values: + * @arg DMA_PINCOS_Psize: Peripheral address increment is done + * accordingly to PSIZE parameter. + * @arg DMA_PINCOS_WordAligned: Peripheral address increment offset is + * fixed to 4 (32-bit aligned addresses). + * @retval None + */ +void DMA_PeriphIncOffsetSizeConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_Pincos) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_DMA_PINCOS_SIZE(DMA_Pincos)); + + /* Check the needed Peripheral increment offset */ + if(DMA_Pincos != DMA_PINCOS_Psize) + { + /* Configure DMA_SxCR_PINCOS bit with the input parameter */ + DMAy_Streamx->CR |= (uint32_t)DMA_SxCR_PINCOS; + } + else + { + /* Clear the PINCOS bit: Peripheral address incremented according to PSIZE */ + DMAy_Streamx->CR &= ~(uint32_t)DMA_SxCR_PINCOS; + } +} + +/** + * @brief Configures, when the DMAy Streamx is disabled, the flow controller for + * the next transactions (Peripheral or Memory). + * + * @note Before enabling this feature, check if the used peripheral supports + * the Flow Controller mode or not. + * + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param DMA_FlowCtrl: specifies the DMA flow controller. + * This parameter can be one of the following values: + * @arg DMA_FlowCtrl_Memory: DMAy_Streamx transactions flow controller is + * the DMA controller. + * @arg DMA_FlowCtrl_Peripheral: DMAy_Streamx transactions flow controller + * is the peripheral. + * @retval None + */ +void DMA_FlowControllerConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FlowCtrl) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_DMA_FLOW_CTRL(DMA_FlowCtrl)); + + /* Check the needed flow controller */ + if(DMA_FlowCtrl != DMA_FlowCtrl_Memory) + { + /* Configure DMA_SxCR_PFCTRL bit with the input parameter */ + DMAy_Streamx->CR |= (uint32_t)DMA_SxCR_PFCTRL; + } + else + { + /* Clear the PFCTRL bit: Memory is the flow controller */ + DMAy_Streamx->CR &= ~(uint32_t)DMA_SxCR_PFCTRL; + } +} +/** + * @} + */ + +/** @defgroup DMA_Group2 Data Counter functions + * @brief Data Counter functions + * +@verbatim + =============================================================================== + Data Counter functions + =============================================================================== + + This subsection provides function allowing to configure and read the buffer size + (number of data to be transferred). + + The DMA data counter can be written only when the DMA Stream is disabled + (ie. after transfer complete event). + + The following function can be used to write the Stream data counter value: + - void DMA_SetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx, uint16_t Counter); + +@note It is advised to use this function rather than DMA_Init() in situations where + only the Data buffer needs to be reloaded. + +@note If the Source and Destination Data Sizes are different, then the value written in + data counter, expressing the number of transfers, is relative to the number of + transfers from the Peripheral point of view. + ie. If Memory data size is Word, Peripheral data size is Half-Words, then the value + to be configured in the data counter is the number of Half-Words to be transferred + from/to the peripheral. + + The DMA data counter can be read to indicate the number of remaining transfers for + the relative DMA Stream. This counter is decremented at the end of each data + transfer and when the transfer is complete: + - If Normal mode is selected: the counter is set to 0. + - If Circular mode is selected: the counter is reloaded with the initial value + (configured before enabling the DMA Stream) + + The following function can be used to read the Stream data counter value: + - uint16_t DMA_GetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx); + +@endverbatim + * @{ + */ + +/** + * @brief Writes the number of data units to be transferred on the DMAy Streamx. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param Counter: Number of data units to be transferred (from 0 to 65535) + * Number of data items depends only on the Peripheral data format. + * + * @note If Peripheral data format is Bytes: number of data units is equal + * to total number of bytes to be transferred. + * + * @note If Peripheral data format is Half-Word: number of data units is + * equal to total number of bytes to be transferred / 2. + * + * @note If Peripheral data format is Word: number of data units is equal + * to total number of bytes to be transferred / 4. + * + * @note In Memory-to-Memory transfer mode, the memory buffer pointed by + * DMAy_SxPAR register is considered as Peripheral. + * + * @retval The number of remaining data units in the current DMAy Streamx transfer. + */ +void DMA_SetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx, uint16_t Counter) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + + /* Write the number of data units to be transferred */ + DMAy_Streamx->NDTR = (uint16_t)Counter; +} + +/** + * @brief Returns the number of remaining data units in the current DMAy Streamx transfer. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @retval The number of remaining data units in the current DMAy Streamx transfer. + */ +uint16_t DMA_GetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + + /* Return the number of remaining data units for DMAy Streamx */ + return ((uint16_t)(DMAy_Streamx->NDTR)); +} +/** + * @} + */ + +/** @defgroup DMA_Group3 Double Buffer mode functions + * @brief Double Buffer mode functions + * +@verbatim + =============================================================================== + Double Buffer mode functions + =============================================================================== + + This subsection provides function allowing to configure and control the double + buffer mode parameters. + + The Double Buffer mode can be used only when Circular mode is enabled. + The Double Buffer mode cannot be used when transferring data from Memory to Memory. + + The Double Buffer mode allows to set two different Memory addresses from/to which + the DMA controller will access alternatively (after completing transfer to/from target + memory 0, it will start transfer to/from target memory 1). + This allows to reduce software overhead for double buffering and reduce the CPU + access time. + + Two functions must be called before calling the DMA_Init() function: + - void DMA_DoubleBufferModeConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t Memory1BaseAddr, + uint32_t DMA_CurrentMemory); + - void DMA_DoubleBufferModeCmd(DMA_Stream_TypeDef* DMAy_Streamx, FunctionalState NewState); + + DMA_DoubleBufferModeConfig() is called to configure the Memory 1 base address and the first + Memory target from/to which the transfer will start after enabling the DMA Stream. + Then DMA_DoubleBufferModeCmd() must be called to enable the Double Buffer mode (or disable + it when it should not be used). + + + Two functions can be called dynamically when the transfer is ongoing (or when the DMA Stream is + stopped) to modify on of the target Memories addresses or to check wich Memory target is currently + used: + - void DMA_MemoryTargetConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t MemoryBaseAddr, + uint32_t DMA_MemoryTarget); + - uint32_t DMA_GetCurrentMemoryTarget(DMA_Stream_TypeDef* DMAy_Streamx); + + DMA_MemoryTargetConfig() can be called to modify the base address of one of the two target Memories. + The Memory of which the base address will be modified must not be currently be used by the DMA Stream + (ie. if the DMA Stream is currently transferring from Memory 1 then you can only modify base address + of target Memory 0 and vice versa). + To check this condition, it is recommended to use the function DMA_GetCurrentMemoryTarget() which + returns the index of the Memory target currently in use by the DMA Stream. + +@endverbatim + * @{ + */ + +/** + * @brief Configures, when the DMAy Streamx is disabled, the double buffer mode + * and the current memory target. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param Memory1BaseAddr: the base address of the second buffer (Memory 1) + * @param DMA_CurrentMemory: specifies which memory will be first buffer for + * the transactions when the Stream will be enabled. + * This parameter can be one of the following values: + * @arg DMA_Memory_0: Memory 0 is the current buffer. + * @arg DMA_Memory_1: Memory 1 is the current buffer. + * + * @note Memory0BaseAddr is set by the DMA structure configuration in DMA_Init(). + * + * @retval None + */ +void DMA_DoubleBufferModeConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t Memory1BaseAddr, + uint32_t DMA_CurrentMemory) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_DMA_CURRENT_MEM(DMA_CurrentMemory)); + + if (DMA_CurrentMemory != DMA_Memory_0) + { + /* Set Memory 1 as current memory address */ + DMAy_Streamx->CR |= (uint32_t)(DMA_SxCR_CT); + } + else + { + /* Set Memory 0 as current memory address */ + DMAy_Streamx->CR &= ~(uint32_t)(DMA_SxCR_CT); + } + + /* Write to DMAy Streamx M1AR */ + DMAy_Streamx->M1AR = Memory1BaseAddr; +} + +/** + * @brief Enables or disables the double buffer mode for the selected DMA stream. + * @note This function can be called only when the DMA Stream is disabled. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param NewState: new state of the DMAy Streamx double buffer mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DMA_DoubleBufferModeCmd(DMA_Stream_TypeDef* DMAy_Streamx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Configure the Double Buffer mode */ + if (NewState != DISABLE) + { + /* Enable the Double buffer mode */ + DMAy_Streamx->CR |= (uint32_t)DMA_SxCR_DBM; + } + else + { + /* Disable the Double buffer mode */ + DMAy_Streamx->CR &= ~(uint32_t)DMA_SxCR_DBM; + } +} + +/** + * @brief Configures the Memory address for the next buffer transfer in double + * buffer mode (for dynamic use). This function can be called when the + * DMA Stream is enabled and when the transfer is ongoing. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param MemoryBaseAddr: The base address of the target memory buffer + * @param DMA_MemoryTarget: Next memory target to be used. + * This parameter can be one of the following values: + * @arg DMA_Memory_0: To use the memory address 0 + * @arg DMA_Memory_1: To use the memory address 1 + * + * @note It is not allowed to modify the Base Address of a target Memory when + * this target is involved in the current transfer. ie. If the DMA Stream + * is currently transferring to/from Memory 1, then it not possible to + * modify Base address of Memory 1, but it is possible to modify Base + * address of Memory 0. + * To know which Memory is currently used, you can use the function + * DMA_GetCurrentMemoryTarget(). + * + * @retval None + */ +void DMA_MemoryTargetConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t MemoryBaseAddr, + uint32_t DMA_MemoryTarget) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_DMA_CURRENT_MEM(DMA_MemoryTarget)); + + /* Check the Memory target to be configured */ + if (DMA_MemoryTarget != DMA_Memory_0) + { + /* Write to DMAy Streamx M1AR */ + DMAy_Streamx->M1AR = MemoryBaseAddr; + } + else + { + /* Write to DMAy Streamx M0AR */ + DMAy_Streamx->M0AR = MemoryBaseAddr; + } +} + +/** + * @brief Returns the current memory target used by double buffer transfer. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @retval The memory target number: 0 for Memory0 or 1 for Memory1. + */ +uint32_t DMA_GetCurrentMemoryTarget(DMA_Stream_TypeDef* DMAy_Streamx) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + + /* Get the current memory target */ + if ((DMAy_Streamx->CR & DMA_SxCR_CT) != 0) + { + /* Current memory buffer used is Memory 1 */ + tmp = 1; + } + else + { + /* Current memory buffer used is Memory 0 */ + tmp = 0; + } + return tmp; +} +/** + * @} + */ + +/** @defgroup DMA_Group4 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + + This subsection provides functions allowing to + - Check the DMA enable status + - Check the FIFO status + - Configure the DMA Interrupts sources and check or clear the flags or pending bits status. + + 1. DMA Enable status: + After configuring the DMA Stream (DMA_Init() function) and enabling the stream, + it is recommended to check (or wait until) the DMA Stream is effectively enabled. + A Stream may remain disabled if a configuration parameter is wrong. + After disabling a DMA Stream, it is also recommended to check (or wait until) the DMA + Stream is effectively disabled. If a Stream is disabled while a data transfer is ongoing, + the current data will be transferred and the Stream will be effectively disabled only after + this data transfer completion. + To monitor this state it is possible to use the following function: + - FunctionalState DMA_GetCmdStatus(DMA_Stream_TypeDef* DMAy_Streamx); + + 2. FIFO Status: + It is possible to monitor the FIFO status when a transfer is ongoing using the following + function: + - uint32_t DMA_GetFIFOStatus(DMA_Stream_TypeDef* DMAy_Streamx); + + 3. DMA Interrupts and Flags: + The user should identify which mode will be used in his application to manage the + DMA controller events: Polling mode or Interrupt mode. + + Polling Mode + ============= + Each DMA stream can be managed through 4 event Flags: + (x : DMA Stream number ) + 1. DMA_FLAG_FEIFx : to indicate that a FIFO Mode Transfer Error event occurred. + 2. DMA_FLAG_DMEIFx : to indicate that a Direct Mode Transfer Error event occurred. + 3. DMA_FLAG_TEIFx : to indicate that a Transfer Error event occurred. + 4. DMA_FLAG_HTIFx : to indicate that a Half-Transfer Complete event occurred. + 5. DMA_FLAG_TCIFx : to indicate that a Transfer Complete event occurred . + + In this Mode it is advised to use the following functions: + - FlagStatus DMA_GetFlagStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG); + - void DMA_ClearFlag(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG); + + Interrupt Mode + =============== + Each DMA Stream can be managed through 4 Interrupts: + + Interrupt Source + ---------------- + 1. DMA_IT_FEIFx : specifies the interrupt source for the FIFO Mode Transfer Error event. + 2. DMA_IT_DMEIFx : specifies the interrupt source for the Direct Mode Transfer Error event. + 3. DMA_IT_TEIFx : specifies the interrupt source for the Transfer Error event. + 4. DMA_IT_HTIFx : specifies the interrupt source for the Half-Transfer Complete event. + 5. DMA_IT_TCIFx : specifies the interrupt source for the a Transfer Complete event. + + In this Mode it is advised to use the following functions: + - void DMA_ITConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT, FunctionalState NewState); + - ITStatus DMA_GetITStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT); + - void DMA_ClearITPendingBit(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT); + +@endverbatim + * @{ + */ + +/** + * @brief Returns the status of EN bit for the specified DMAy Streamx. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * + * @note After configuring the DMA Stream (DMA_Init() function) and enabling + * the stream, it is recommended to check (or wait until) the DMA Stream + * is effectively enabled. A Stream may remain disabled if a configuration + * parameter is wrong. + * After disabling a DMA Stream, it is also recommended to check (or wait + * until) the DMA Stream is effectively disabled. If a Stream is disabled + * while a data transfer is ongoing, the current data will be transferred + * and the Stream will be effectively disabled only after the transfer + * of this single data is finished. + * + * @retval Current state of the DMAy Streamx (ENABLE or DISABLE). + */ +FunctionalState DMA_GetCmdStatus(DMA_Stream_TypeDef* DMAy_Streamx) +{ + FunctionalState state = DISABLE; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + + if ((DMAy_Streamx->CR & (uint32_t)DMA_SxCR_EN) != 0) + { + /* The selected DMAy Streamx EN bit is set (DMA is still transferring) */ + state = ENABLE; + } + else + { + /* The selected DMAy Streamx EN bit is cleared (DMA is disabled and + all transfers are complete) */ + state = DISABLE; + } + return state; +} + +/** + * @brief Returns the current DMAy Streamx FIFO filled level. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @retval The FIFO filling state. + * - DMA_FIFOStatus_Less1QuarterFull: when FIFO is less than 1 quarter-full + * and not empty. + * - DMA_FIFOStatus_1QuarterFull: if more than 1 quarter-full. + * - DMA_FIFOStatus_HalfFull: if more than 1 half-full. + * - DMA_FIFOStatus_3QuartersFull: if more than 3 quarters-full. + * - DMA_FIFOStatus_Empty: when FIFO is empty + * - DMA_FIFOStatus_Full: when FIFO is full + */ +uint32_t DMA_GetFIFOStatus(DMA_Stream_TypeDef* DMAy_Streamx) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + + /* Get the FIFO level bits */ + tmpreg = (uint32_t)((DMAy_Streamx->FCR & DMA_SxFCR_FS)); + + return tmpreg; +} + +/** + * @brief Checks whether the specified DMAy Streamx flag is set or not. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param DMA_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg DMA_FLAG_TCIFx: Streamx transfer complete flag + * @arg DMA_FLAG_HTIFx: Streamx half transfer complete flag + * @arg DMA_FLAG_TEIFx: Streamx transfer error flag + * @arg DMA_FLAG_DMEIFx: Streamx direct mode error flag + * @arg DMA_FLAG_FEIFx: Streamx FIFO error flag + * Where x can be 0 to 7 to select the DMA Stream. + * @retval The new state of DMA_FLAG (SET or RESET). + */ +FlagStatus DMA_GetFlagStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG) +{ + FlagStatus bitstatus = RESET; + DMA_TypeDef* DMAy; + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_DMA_GET_FLAG(DMA_FLAG)); + + /* Determine the DMA to which belongs the stream */ + if (DMAy_Streamx < DMA2_Stream0) + { + /* DMAy_Streamx belongs to DMA1 */ + DMAy = DMA1; + } + else + { + /* DMAy_Streamx belongs to DMA2 */ + DMAy = DMA2; + } + + /* Check if the flag is in HISR or LISR */ + if ((DMA_FLAG & HIGH_ISR_MASK) != (uint32_t)RESET) + { + /* Get DMAy HISR register value */ + tmpreg = DMAy->HISR; + } + else + { + /* Get DMAy LISR register value */ + tmpreg = DMAy->LISR; + } + + /* Mask the reserved bits */ + tmpreg &= (uint32_t)RESERVED_MASK; + + /* Check the status of the specified DMA flag */ + if ((tmpreg & DMA_FLAG) != (uint32_t)RESET) + { + /* DMA_FLAG is set */ + bitstatus = SET; + } + else + { + /* DMA_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the DMA_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DMAy Streamx's pending flags. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param DMA_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg DMA_FLAG_TCIFx: Streamx transfer complete flag + * @arg DMA_FLAG_HTIFx: Streamx half transfer complete flag + * @arg DMA_FLAG_TEIFx: Streamx transfer error flag + * @arg DMA_FLAG_DMEIFx: Streamx direct mode error flag + * @arg DMA_FLAG_FEIFx: Streamx FIFO error flag + * Where x can be 0 to 7 to select the DMA Stream. + * @retval None + */ +void DMA_ClearFlag(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG) +{ + DMA_TypeDef* DMAy; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_DMA_CLEAR_FLAG(DMA_FLAG)); + + /* Determine the DMA to which belongs the stream */ + if (DMAy_Streamx < DMA2_Stream0) + { + /* DMAy_Streamx belongs to DMA1 */ + DMAy = DMA1; + } + else + { + /* DMAy_Streamx belongs to DMA2 */ + DMAy = DMA2; + } + + /* Check if LIFCR or HIFCR register is targeted */ + if ((DMA_FLAG & HIGH_ISR_MASK) != (uint32_t)RESET) + { + /* Set DMAy HIFCR register clear flag bits */ + DMAy->HIFCR = (uint32_t)(DMA_FLAG & RESERVED_MASK); + } + else + { + /* Set DMAy LIFCR register clear flag bits */ + DMAy->LIFCR = (uint32_t)(DMA_FLAG & RESERVED_MASK); + } +} + +/** + * @brief Enables or disables the specified DMAy Streamx interrupts. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param DMA_IT: specifies the DMA interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg DMA_IT_TC: Transfer complete interrupt mask + * @arg DMA_IT_HT: Half transfer complete interrupt mask + * @arg DMA_IT_TE: Transfer error interrupt mask + * @arg DMA_IT_FE: FIFO error interrupt mask + * @param NewState: new state of the specified DMA interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DMA_ITConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_DMA_CONFIG_IT(DMA_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Check if the DMA_IT parameter contains a FIFO interrupt */ + if ((DMA_IT & DMA_IT_FE) != 0) + { + if (NewState != DISABLE) + { + /* Enable the selected DMA FIFO interrupts */ + DMAy_Streamx->FCR |= (uint32_t)DMA_IT_FE; + } + else + { + /* Disable the selected DMA FIFO interrupts */ + DMAy_Streamx->FCR &= ~(uint32_t)DMA_IT_FE; + } + } + + /* Check if the DMA_IT parameter contains a Transfer interrupt */ + if (DMA_IT != DMA_IT_FE) + { + if (NewState != DISABLE) + { + /* Enable the selected DMA transfer interrupts */ + DMAy_Streamx->CR |= (uint32_t)(DMA_IT & TRANSFER_IT_ENABLE_MASK); + } + else + { + /* Disable the selected DMA transfer interrupts */ + DMAy_Streamx->CR &= ~(uint32_t)(DMA_IT & TRANSFER_IT_ENABLE_MASK); + } + } +} + +/** + * @brief Checks whether the specified DMAy Streamx interrupt has occurred or not. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param DMA_IT: specifies the DMA interrupt source to check. + * This parameter can be one of the following values: + * @arg DMA_IT_TCIFx: Streamx transfer complete interrupt + * @arg DMA_IT_HTIFx: Streamx half transfer complete interrupt + * @arg DMA_IT_TEIFx: Streamx transfer error interrupt + * @arg DMA_IT_DMEIFx: Streamx direct mode error interrupt + * @arg DMA_IT_FEIFx: Streamx FIFO error interrupt + * Where x can be 0 to 7 to select the DMA Stream. + * @retval The new state of DMA_IT (SET or RESET). + */ +ITStatus DMA_GetITStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT) +{ + ITStatus bitstatus = RESET; + DMA_TypeDef* DMAy; + uint32_t tmpreg = 0, enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_DMA_GET_IT(DMA_IT)); + + /* Determine the DMA to which belongs the stream */ + if (DMAy_Streamx < DMA2_Stream0) + { + /* DMAy_Streamx belongs to DMA1 */ + DMAy = DMA1; + } + else + { + /* DMAy_Streamx belongs to DMA2 */ + DMAy = DMA2; + } + + /* Check if the interrupt enable bit is in the CR or FCR register */ + if ((DMA_IT & TRANSFER_IT_MASK) != (uint32_t)RESET) + { + /* Get the interrupt enable position mask in CR register */ + tmpreg = (uint32_t)((DMA_IT >> 11) & TRANSFER_IT_ENABLE_MASK); + + /* Check the enable bit in CR register */ + enablestatus = (uint32_t)(DMAy_Streamx->CR & tmpreg); + } + else + { + /* Check the enable bit in FCR register */ + enablestatus = (uint32_t)(DMAy_Streamx->FCR & DMA_IT_FE); + } + + /* Check if the interrupt pending flag is in LISR or HISR */ + if ((DMA_IT & HIGH_ISR_MASK) != (uint32_t)RESET) + { + /* Get DMAy HISR register value */ + tmpreg = DMAy->HISR ; + } + else + { + /* Get DMAy LISR register value */ + tmpreg = DMAy->LISR ; + } + + /* mask all reserved bits */ + tmpreg &= (uint32_t)RESERVED_MASK; + + /* Check the status of the specified DMA interrupt */ + if (((tmpreg & DMA_IT) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET)) + { + /* DMA_IT is set */ + bitstatus = SET; + } + else + { + /* DMA_IT is reset */ + bitstatus = RESET; + } + + /* Return the DMA_IT status */ + return bitstatus; +} + +/** + * @brief Clears the DMAy Streamx's interrupt pending bits. + * @param DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 + * to 7 to select the DMA Stream. + * @param DMA_IT: specifies the DMA interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg DMA_IT_TCIFx: Streamx transfer complete interrupt + * @arg DMA_IT_HTIFx: Streamx half transfer complete interrupt + * @arg DMA_IT_TEIFx: Streamx transfer error interrupt + * @arg DMA_IT_DMEIFx: Streamx direct mode error interrupt + * @arg DMA_IT_FEIFx: Streamx FIFO error interrupt + * Where x can be 0 to 7 to select the DMA Stream. + * @retval None + */ +void DMA_ClearITPendingBit(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT) +{ + DMA_TypeDef* DMAy; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx)); + assert_param(IS_DMA_CLEAR_IT(DMA_IT)); + + /* Determine the DMA to which belongs the stream */ + if (DMAy_Streamx < DMA2_Stream0) + { + /* DMAy_Streamx belongs to DMA1 */ + DMAy = DMA1; + } + else + { + /* DMAy_Streamx belongs to DMA2 */ + DMAy = DMA2; + } + + /* Check if LIFCR or HIFCR register is targeted */ + if ((DMA_IT & HIGH_ISR_MASK) != (uint32_t)RESET) + { + /* Set DMAy HIFCR register clear interrupt bits */ + DMAy->HIFCR = (uint32_t)(DMA_IT & RESERVED_MASK); + } + else + { + /* Set DMAy LIFCR register clear interrupt bits */ + DMAy->LIFCR = (uint32_t)(DMA_IT & RESERVED_MASK); + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_exti.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_exti.c new file mode 100644 index 000000000..07da4fd28 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_exti.c @@ -0,0 +1,306 @@ +/** + ****************************************************************************** + * @file stm32f4xx_exti.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the EXTI peripheral: + * - Initialization and Configuration + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * EXTI features + * =================================================================== + * + * External interrupt/event lines are mapped as following: + * 1- All available GPIO pins are connected to the 16 external + * interrupt/event lines from EXTI0 to EXTI15. + * 2- EXTI line 16 is connected to the PVD Output + * 3- EXTI line 17 is connected to the RTC Alarm event + * 4- EXTI line 18 is connected to the USB OTG FS Wakeup from suspend event + * 5- EXTI line 19 is connected to the Ethernet Wakeup event + * 6- EXTI line 20 is connected to the USB OTG HS (configured in FS) Wakeup event + * 7- EXTI line 21 is connected to the RTC Tamper and Time Stamp events + * 8- EXTI line 22 is connected to the RTC Wakeup event + * + * =================================================================== + * How to use this driver + * =================================================================== + * + * In order to use an I/O pin as an external interrupt source, follow + * steps below: + * 1- Configure the I/O in input mode using GPIO_Init() + * 2- Select the input source pin for the EXTI line using SYSCFG_EXTILineConfig() + * 3- Select the mode(interrupt, event) and configure the trigger + * selection (Rising, falling or both) using EXTI_Init() + * 4- Configure NVIC IRQ channel mapped to the EXTI line using NVIC_Init() + * + * @note SYSCFG APB clock must be enabled to get write access to SYSCFG_EXTICRx + * registers using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_exti.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup EXTI + * @brief EXTI driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +#define EXTI_LINENONE ((uint32_t)0x00000) /* No interrupt selected */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup EXTI_Private_Functions + * @{ + */ + +/** @defgroup EXTI_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the EXTI peripheral registers to their default reset values. + * @param None + * @retval None + */ +void EXTI_DeInit(void) +{ + EXTI->IMR = 0x00000000; + EXTI->EMR = 0x00000000; + EXTI->RTSR = 0x00000000; + EXTI->FTSR = 0x00000000; + EXTI->PR = 0x007FFFFF; +} + +/** + * @brief Initializes the EXTI peripheral according to the specified + * parameters in the EXTI_InitStruct. + * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure + * that contains the configuration information for the EXTI peripheral. + * @retval None + */ +void EXTI_Init(const EXTI_InitTypeDef* EXTI_InitStruct) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode)); + assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger)); + assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line)); + assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd)); + + tmp = (uint32_t)EXTI_BASE; + + if (EXTI_InitStruct->EXTI_LineCmd != DISABLE) + { + /* Clear EXTI line configuration */ + EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line; + EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line; + + tmp += EXTI_InitStruct->EXTI_Mode; + + *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line; + + /* Clear Rising Falling edge configuration */ + EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line; + EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line; + + /* Select the trigger for the selected external interrupts */ + if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling) + { + /* Rising Falling edge */ + EXTI->RTSR |= EXTI_InitStruct->EXTI_Line; + EXTI->FTSR |= EXTI_InitStruct->EXTI_Line; + } + else + { + tmp = (uint32_t)EXTI_BASE; + tmp += EXTI_InitStruct->EXTI_Trigger; + + *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line; + } + } + else + { + tmp += EXTI_InitStruct->EXTI_Mode; + + /* Disable the selected external lines */ + *(__IO uint32_t *) tmp &= ~EXTI_InitStruct->EXTI_Line; + } +} + +/** + * @brief Fills each EXTI_InitStruct member with its reset value. + * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct) +{ + EXTI_InitStruct->EXTI_Line = EXTI_LINENONE; + EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt; + EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling; + EXTI_InitStruct->EXTI_LineCmd = DISABLE; +} + +/** + * @brief Generates a Software interrupt on selected EXTI line. + * @param EXTI_Line: specifies the EXTI line on which the software interrupt + * will be generated. + * This parameter can be any combination of EXTI_Linex where x can be (0..22) + * @retval None + */ +void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->SWIER |= EXTI_Line; +} + +/** + * @} + */ + +/** @defgroup EXTI_Group2 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Checks whether the specified EXTI line flag is set or not. + * @param EXTI_Line: specifies the EXTI line flag to check. + * This parameter can be EXTI_Linex where x can be(0..22) + * @retval The new state of EXTI_Line (SET or RESET). + */ +FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_GET_EXTI_LINE(EXTI_Line)); + + if ((EXTI->PR & EXTI_Line) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the EXTI's line pending flags. + * @param EXTI_Line: specifies the EXTI lines flags to clear. + * This parameter can be any combination of EXTI_Linex where x can be (0..22) + * @retval None + */ +void EXTI_ClearFlag(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->PR = EXTI_Line; +} + +/** + * @brief Checks whether the specified EXTI line is asserted or not. + * @param EXTI_Line: specifies the EXTI line to check. + * This parameter can be EXTI_Linex where x can be(0..22) + * @retval The new state of EXTI_Line (SET or RESET). + */ +ITStatus EXTI_GetITStatus(uint32_t EXTI_Line) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + /* Check the parameters */ + assert_param(IS_GET_EXTI_LINE(EXTI_Line)); + + enablestatus = EXTI->IMR & EXTI_Line; + if (((EXTI->PR & EXTI_Line) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the EXTI's line pending bits. + * @param EXTI_Line: specifies the EXTI lines to clear. + * This parameter can be any combination of EXTI_Linex where x can be (0..22) + * @retval None + */ +void EXTI_ClearITPendingBit(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->PR = EXTI_Line; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash.c new file mode 100644 index 000000000..280b1d394 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash.c @@ -0,0 +1,1056 @@ +/** + ****************************************************************************** + * @file stm32f4xx_flash.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the FLASH peripheral: + * - FLASH Interface configuration + * - FLASH Memory Programming + * - Option Bytes Programming + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * + * This driver provides functions to configure and program the FLASH + * memory of all STM32F4xx devices. + * These functions are split in 4 groups: + * + * 1. FLASH Interface configuration functions: this group includes the + * management of the following features: + * - Set the latency + * - Enable/Disable the prefetch buffer + * - Enable/Disable the Instruction cache and the Data cache + * - Reset the Instruction cache and the Data cache + * + * 2. FLASH Memory Programming functions: this group includes all needed + * functions to erase and program the main memory: + * - Lock and Unlock the FLASH interface + * - Erase function: Erase sector, erase all sectors + * - Program functions: byte, half word, word and double word + * + * 3. Option Bytes Programming functions: this group includes all needed + * functions to manage the Option Bytes: + * - Set/Reset the write protection + * - Set the Read protection Level + * - Set the BOR level + * - Program the user Option Bytes + * - Launch the Option Bytes loader + * + * 4. Interrupts and flags management functions: this group + * includes all needed functions to: + * - Enable/Disable the FLASH interrupt sources + * - Get flags status + * - Clear flags + * - Get FLASH operation status + * - Wait for last FLASH operation + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_flash.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup FLASH + * @brief FLASH driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define SECTOR_MASK ((uint32_t)0xFFFFFF07) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup FLASH_Private_Functions + * @{ + */ + +/** @defgroup FLASH_Group1 FLASH Interface configuration functions + * @brief FLASH Interface configuration functions + * + +@verbatim + =============================================================================== + FLASH Interface configuration functions + =============================================================================== + + This group includes the following functions: + - void FLASH_SetLatency(uint32_t FLASH_Latency) + To correctly read data from FLASH memory, the number of wait states (LATENCY) + must be correctly programmed according to the frequency of the CPU clock + (HCLK) and the supply voltage of the device. + +-------------------------------------------------------------------------------------+ + | Latency | HCLK clock frequency (MHz) | + | |---------------------------------------------------------------------| + | | voltage range | voltage range | voltage range | voltage range | + | | 2.7 V - 3.6 V | 2.4 V - 2.7 V | 2.1 V - 2.4 V | 1.8 V - 2.1 V | + |---------------|----------------|----------------|-----------------|-----------------| + |0WS(1CPU cycle)|0 < HCLK <= 30 |0 < HCLK <= 24 |0 < HCLK <= 18 |0 < HCLK <= 16 | + |---------------|----------------|----------------|-----------------|-----------------| + |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |18 < HCLK <= 36 |16 < HCLK <= 32 | + |---------------|----------------|----------------|-----------------|-----------------| + |2WS(3CPU cycle)|60 < HCLK <= 90 |48 < HCLK <= 72 |36 < HCLK <= 54 |32 < HCLK <= 48 | + |---------------|----------------|----------------|-----------------|-----------------| + |3WS(4CPU cycle)|90 < HCLK <= 120|72 < HCLK <= 96 |54 < HCLK <= 72 |48 < HCLK <= 64 | + |---------------|----------------|----------------|-----------------|-----------------| + |4WS(5CPU cycle)|120< HCLK <= 150|96 < HCLK <= 120|72 < HCLK <= 90 |64 < HCLK <= 80 | + |---------------|----------------|----------------|-----------------|-----------------| + |5WS(6CPU cycle)|120< HCLK <= 168|120< HCLK <= 144|90 < HCLK <= 108 |80 < HCLK <= 96 | + |---------------|----------------|----------------|-----------------|-----------------| + |6WS(7CPU cycle)| NA |144< HCLK <= 168|108 < HCLK <= 120|96 < HCLK <= 112 | + |---------------|----------------|----------------|-----------------|-----------------| + |7WS(8CPU cycle)| NA | NA |120 < HCLK <= 138|112 < HCLK <= 120| + |***************|****************|****************|*****************|*****************|*****************************+ + | | voltage range | voltage range | voltage range | voltage range | voltage range 2.7 V - 3.6 V | + | | 2.7 V - 3.6 V | 2.4 V - 2.7 V | 2.1 V - 2.4 V | 1.8 V - 2.1 V | with External Vpp = 9V | + |---------------|----------------|----------------|-----------------|-----------------|-----------------------------| + |Max Parallelism| x32 | x16 | x8 | x64 | + |---------------|----------------|----------------|-----------------|-----------------|-----------------------------| + |PSIZE[1:0] | 10 | 01 | 00 | 11 | + +-------------------------------------------------------------------------------------------------------------------+ + @note When VOS bit (in PWR_CR register) is reset to '0’, the maximum value of HCLK is 144 MHz. + You can use PWR_MainRegulatorModeConfig() function to set or reset this bit. + + - void FLASH_PrefetchBufferCmd(FunctionalState NewState) + - void FLASH_InstructionCacheCmd(FunctionalState NewState) + - void FLASH_DataCacheCmd(FunctionalState NewState) + - void FLASH_InstructionCacheReset(void) + - void FLASH_DataCacheReset(void) + + The unlock sequence is not needed for these functions. + +@endverbatim + * @{ + */ + +/** + * @brief Sets the code latency value. + * @param FLASH_Latency: specifies the FLASH Latency value. + * This parameter can be one of the following values: + * @arg FLASH_Latency_0: FLASH Zero Latency cycle + * @arg FLASH_Latency_1: FLASH One Latency cycle + * @arg FLASH_Latency_2: FLASH Two Latency cycles + * @arg FLASH_Latency_3: FLASH Three Latency cycles + * @arg FLASH_Latency_4: FLASH Four Latency cycles + * @arg FLASH_Latency_5: FLASH Five Latency cycles + * @arg FLASH_Latency_6: FLASH Six Latency cycles + * @arg FLASH_Latency_7: FLASH Seven Latency cycles + * @retval None + */ +void FLASH_SetLatency(uint32_t FLASH_Latency) +{ + /* Check the parameters */ + assert_param(IS_FLASH_LATENCY(FLASH_Latency)); + + /* Perform Byte access to FLASH_ACR[8:0] to set the Latency value */ + *(__IO uint8_t *)ACR_BYTE0_ADDRESS = (uint8_t)FLASH_Latency; +} + +/** + * @brief Enables or disables the Prefetch Buffer. + * @param NewState: new state of the Prefetch Buffer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FLASH_PrefetchBufferCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Enable or disable the Prefetch Buffer */ + if(NewState != DISABLE) + { + FLASH->ACR |= FLASH_ACR_PRFTEN; + } + else + { + FLASH->ACR &= (~FLASH_ACR_PRFTEN); + } +} + +/** + * @brief Enables or disables the Instruction Cache feature. + * @param NewState: new state of the Instruction Cache. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FLASH_InstructionCacheCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if(NewState != DISABLE) + { + FLASH->ACR |= FLASH_ACR_ICEN; + } + else + { + FLASH->ACR &= (~FLASH_ACR_ICEN); + } +} + +/** + * @brief Enables or disables the Data Cache feature. + * @param NewState: new state of the Data Cache. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FLASH_DataCacheCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if(NewState != DISABLE) + { + FLASH->ACR |= FLASH_ACR_DCEN; + } + else + { + FLASH->ACR &= (~FLASH_ACR_DCEN); + } +} + +/** + * @brief Resets the Instruction Cache. + * @note This function must be used only when the Instruction Cache is disabled. + * @param None + * @retval None + */ +void FLASH_InstructionCacheReset(void) +{ + FLASH->ACR |= FLASH_ACR_ICRST; +} + +/** + * @brief Resets the Data Cache. + * @note This function must be used only when the Data Cache is disabled. + * @param None + * @retval None + */ +void FLASH_DataCacheReset(void) +{ + FLASH->ACR |= FLASH_ACR_DCRST; +} + +/** + * @} + */ + +/** @defgroup FLASH_Group2 FLASH Memory Programming functions + * @brief FLASH Memory Programming functions + * +@verbatim + =============================================================================== + FLASH Memory Programming functions + =============================================================================== + + This group includes the following functions: + - void FLASH_Unlock(void) + - void FLASH_Lock(void) + - FLASH_Status FLASH_EraseSector(uint32_t FLASH_Sector, uint8_t VoltageRange) + - FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange) + - FLASH_Status FLASH_ProgramDoubleWord(uint32_t Address, uint64_t Data) + - FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data) + - FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data) + - FLASH_Status FLASH_ProgramByte(uint32_t Address, uint8_t Data) + + Any operation of erase or program should follow these steps: + 1. Call the FLASH_Unlock() function to enable the FLASH control register access + + 2. Call the desired function to erase sector(s) or program data + + 3. Call the FLASH_Lock() function to disable the FLASH control register access + (recommended to protect the FLASH memory against possible unwanted operation) + +@endverbatim + * @{ + */ + +/** + * @brief Unlocks the FLASH control register access + * @param None + * @retval None + */ +void FLASH_Unlock(void) +{ + if((FLASH->CR & FLASH_CR_LOCK) != RESET) + { + /* Authorize the FLASH Registers access */ + FLASH->KEYR = FLASH_KEY1; + FLASH->KEYR = FLASH_KEY2; + } +} + +/** + * @brief Locks the FLASH control register access + * @param None + * @retval None + */ +void FLASH_Lock(void) +{ + /* Set the LOCK Bit to lock the FLASH Registers access */ + FLASH->CR |= FLASH_CR_LOCK; +} + +/** + * @brief Erases a specified FLASH Sector. + * + * @param FLASH_Sector: The Sector number to be erased. + * This parameter can be a value between FLASH_Sector_0 and FLASH_Sector_11 + * + * @param VoltageRange: The device voltage range which defines the erase parallelism. + * This parameter can be one of the following values: + * @arg VoltageRange_1: when the device voltage range is 1.8V to 2.1V, + * the operation will be done by byte (8-bit) + * @arg VoltageRange_2: when the device voltage range is 2.1V to 2.7V, + * the operation will be done by half word (16-bit) + * @arg VoltageRange_3: when the device voltage range is 2.7V to 3.6V, + * the operation will be done by word (32-bit) + * @arg VoltageRange_4: when the device voltage range is 2.7V to 3.6V + External Vpp, + * the operation will be done by double word (64-bit) + * + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM, + * FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE. + */ +FLASH_Status FLASH_EraseSector(uint32_t FLASH_Sector, uint8_t VoltageRange) +{ + uint32_t tmp_psize = 0x0; + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_FLASH_SECTOR(FLASH_Sector)); + assert_param(IS_VOLTAGERANGE(VoltageRange)); + + if(VoltageRange == VoltageRange_1) + { + tmp_psize = FLASH_PSIZE_BYTE; + } + else if(VoltageRange == VoltageRange_2) + { + tmp_psize = FLASH_PSIZE_HALF_WORD; + } + else if(VoltageRange == VoltageRange_3) + { + tmp_psize = FLASH_PSIZE_WORD; + } + else + { + tmp_psize = FLASH_PSIZE_DOUBLE_WORD; + } + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase the sector */ + FLASH->CR &= CR_PSIZE_MASK; + FLASH->CR |= tmp_psize; + FLASH->CR &= SECTOR_MASK; + FLASH->CR |= FLASH_CR_SER | FLASH_Sector; + FLASH->CR |= FLASH_CR_STRT; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + /* if the erase operation is completed, disable the SER Bit */ + FLASH->CR &= (~FLASH_CR_SER); + FLASH->CR &= SECTOR_MASK; + } + /* Return the Erase Status */ + return status; +} + +/** + * @brief Erases all FLASH Sectors. + * + * @param VoltageRange: The device voltage range which defines the erase parallelism. + * This parameter can be one of the following values: + * @arg VoltageRange_1: when the device voltage range is 1.8V to 2.1V, + * the operation will be done by byte (8-bit) + * @arg VoltageRange_2: when the device voltage range is 2.1V to 2.7V, + * the operation will be done by half word (16-bit) + * @arg VoltageRange_3: when the device voltage range is 2.7V to 3.6V, + * the operation will be done by word (32-bit) + * @arg VoltageRange_4: when the device voltage range is 2.7V to 3.6V + External Vpp, + * the operation will be done by double word (64-bit) + * + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM, + * FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE. + */ +FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange) +{ + uint32_t tmp_psize = 0x0; + FLASH_Status status = FLASH_COMPLETE; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + assert_param(IS_VOLTAGERANGE(VoltageRange)); + + if(VoltageRange == VoltageRange_1) + { + tmp_psize = FLASH_PSIZE_BYTE; + } + else if(VoltageRange == VoltageRange_2) + { + tmp_psize = FLASH_PSIZE_HALF_WORD; + } + else if(VoltageRange == VoltageRange_3) + { + tmp_psize = FLASH_PSIZE_WORD; + } + else + { + tmp_psize = FLASH_PSIZE_DOUBLE_WORD; + } + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all sectors */ + FLASH->CR &= CR_PSIZE_MASK; + FLASH->CR |= tmp_psize; + FLASH->CR |= FLASH_CR_MER; + FLASH->CR |= FLASH_CR_STRT; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + /* if the erase operation is completed, disable the MER Bit */ + FLASH->CR &= (~FLASH_CR_MER); + + } + /* Return the Erase Status */ + return status; +} + +/** + * @brief Programs a double word (64-bit) at a specified address. + * @note This function must be used when the device voltage range is from + * 2.7V to 3.6V and an External Vpp is present. + * @param Address: specifies the address to be programmed. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM, + * FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE. + */ +FLASH_Status FLASH_ProgramDoubleWord(uint32_t Address, uint64_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR &= CR_PSIZE_MASK; + FLASH->CR |= FLASH_PSIZE_DOUBLE_WORD; + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint64_t*)Address = Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + /* if the program operation is completed, disable the PG Bit */ + FLASH->CR &= (~FLASH_CR_PG); + } + /* Return the Program Status */ + return status; +} + +/** + * @brief Programs a word (32-bit) at a specified address. + * @param Address: specifies the address to be programmed. + * This parameter can be any address in Program memory zone or in OTP zone. + * @note This function must be used when the device voltage range is from 2.7V to 3.6V. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM, + * FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE. + */ +FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR &= CR_PSIZE_MASK; + FLASH->CR |= FLASH_PSIZE_WORD; + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint32_t*)Address = Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + /* if the program operation is completed, disable the PG Bit */ + FLASH->CR &= (~FLASH_CR_PG); + } + /* Return the Program Status */ + return status; +} + +/** + * @brief Programs a half word (16-bit) at a specified address. + * @note This function must be used when the device voltage range is from 2.1V to 3.6V. + * @param Address: specifies the address to be programmed. + * This parameter can be any address in Program memory zone or in OTP zone. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM, + * FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE. + */ +FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR &= CR_PSIZE_MASK; + FLASH->CR |= FLASH_PSIZE_HALF_WORD; + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint16_t*)Address = Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + /* if the program operation is completed, disable the PG Bit */ + FLASH->CR &= (~FLASH_CR_PG); + } + /* Return the Program Status */ + return status; +} + +/** + * @brief Programs a byte (8-bit) at a specified address. + * @note This function can be used within all the device supply voltage ranges. + * @param Address: specifies the address to be programmed. + * This parameter can be any address in Program memory zone or in OTP zone. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM, + * FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE. + */ +FLASH_Status FLASH_ProgramByte(uint32_t Address, uint8_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR &= CR_PSIZE_MASK; + FLASH->CR |= FLASH_PSIZE_BYTE; + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint8_t*)Address = Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + /* if the program operation is completed, disable the PG Bit */ + FLASH->CR &= (~FLASH_CR_PG); + } + + /* Return the Program Status */ + return status; +} + +/** + * @} + */ + +/** @defgroup FLASH_Group3 Option Bytes Programming functions + * @brief Option Bytes Programming functions + * +@verbatim + =============================================================================== + Option Bytes Programming functions + =============================================================================== + + This group includes the following functions: + - void FLASH_OB_Unlock(void) + - void FLASH_OB_Lock(void) + - void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState) + - void FLASH_OB_RDPConfig(uint8_t OB_RDP) + - void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY) + - void FLASH_OB_BORConfig(uint8_t OB_BOR) + - FLASH_Status FLASH_ProgramOTP(uint32_t Address, uint32_t Data) + - FLASH_Status FLASH_OB_Launch(void) + - uint32_t FLASH_OB_GetUser(void) + - uint8_t FLASH_OB_GetWRP(void) + - uint8_t FLASH_OB_GetRDP(void) + - uint8_t FLASH_OB_GetBOR(void) + + Any operation of erase or program should follow these steps: + 1. Call the FLASH_OB_Unlock() function to enable the FLASH option control register access + + 2. Call one or several functions to program the desired Option Bytes: + - void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState) => to Enable/Disable + the desired sector write protection + - void FLASH_OB_RDPConfig(uint8_t OB_RDP) => to set the desired read Protection Level + - void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY) => to configure + the user Option Bytes. + - void FLASH_OB_BORConfig(uint8_t OB_BOR) => to set the BOR Level + + 3. Once all needed Option Bytes to be programmed are correctly written, call the + FLASH_OB_Launch() function to launch the Option Bytes programming process. + + @note When changing the IWDG mode from HW to SW or from SW to HW, a system + reset is needed to make the change effective. + + 4. Call the FLASH_OB_Lock() function to disable the FLASH option control register + access (recommended to protect the Option Bytes against possible unwanted operations) + +@endverbatim + * @{ + */ + +/** + * @brief Unlocks the FLASH Option Control Registers access. + * @param None + * @retval None + */ +void FLASH_OB_Unlock(void) +{ + if((FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) != RESET) + { + /* Authorizes the Option Byte register programming */ + FLASH->OPTKEYR = FLASH_OPT_KEY1; + FLASH->OPTKEYR = FLASH_OPT_KEY2; + } +} + +/** + * @brief Locks the FLASH Option Control Registers access. + * @param None + * @retval None + */ +void FLASH_OB_Lock(void) +{ + /* Set the OPTLOCK Bit to lock the FLASH Option Byte Registers access */ + FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK; +} + +/** + * @brief Enables or disables the write protection of the desired sectors + * @param OB_WRP: specifies the sector(s) to be write protected or unprotected. + * This parameter can be one of the following values: + * @arg OB_WRP: A value between OB_WRP_Sector0 and OB_WRP_Sector11 + * @arg OB_WRP_Sector_All + * @param Newstate: new state of the Write Protection. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_WRP(OB_WRP)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + status = FLASH_WaitForLastOperation(); + + if(status == FLASH_COMPLETE) + { + if(NewState != DISABLE) + { + *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS &= (~OB_WRP); + } + else + { + *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS |= (uint16_t)OB_WRP; + } + } +} + +/** + * @brief Sets the read protection level. + * @param OB_RDP: specifies the read protection level. + * This parameter can be one of the following values: + * @arg OB_RDP_Level_0: No protection + * @arg OB_RDP_Level_1: Read protection of the memory + * @arg OB_RDP_Level_2: Full chip protection + * + * !!!Warning!!! When enabling OB_RDP level 2 it's no more possible to go back to level 1 or 0 + * + * @retval None + */ +void FLASH_OB_RDPConfig(uint8_t OB_RDP) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_RDP(OB_RDP)); + + status = FLASH_WaitForLastOperation(); + + if(status == FLASH_COMPLETE) + { + *(__IO uint8_t*)OPTCR_BYTE1_ADDRESS = OB_RDP; + + } +} + +/** + * @brief Programs the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. + * @param OB_IWDG: Selects the IWDG mode + * This parameter can be one of the following values: + * @arg OB_IWDG_SW: Software IWDG selected + * @arg OB_IWDG_HW: Hardware IWDG selected + * @param OB_STOP: Reset event when entering STOP mode. + * This parameter can be one of the following values: + * @arg OB_STOP_NoRST: No reset generated when entering in STOP + * @arg OB_STOP_RST: Reset generated when entering in STOP + * @param OB_STDBY: Reset event when entering Standby mode. + * This parameter can be one of the following values: + * @arg OB_STDBY_NoRST: No reset generated when entering in STANDBY + * @arg OB_STDBY_RST: Reset generated when entering in STANDBY + * @retval None + */ +void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY) +{ + uint8_t optiontmp = 0xFF; + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_IWDG_SOURCE(OB_IWDG)); + assert_param(IS_OB_STOP_SOURCE(OB_STOP)); + assert_param(IS_OB_STDBY_SOURCE(OB_STDBY)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + if(status == FLASH_COMPLETE) + { + /* Mask OPTLOCK, OPTSTRT and BOR_LEV bits */ + optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE0_ADDRESS) & (uint8_t)0x0F); + + /* Update User Option Byte */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS = OB_IWDG | (uint8_t)(OB_STDBY | (uint8_t)(OB_STOP | ((uint8_t)optiontmp))); + } +} + +/** + * @brief Sets the BOR Level. + * @param OB_BOR: specifies the Option Bytes BOR Reset Level. + * This parameter can be one of the following values: + * @arg OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V + * @arg OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V + * @arg OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V + * @arg OB_BOR_OFF: Supply voltage ranges from 1.62 to 2.1 V + * @retval None + */ +void FLASH_OB_BORConfig(uint8_t OB_BOR) +{ + /* Check the parameters */ + assert_param(IS_OB_BOR(OB_BOR)); + + /* Set the BOR Level */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BOR_LEV); + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= OB_BOR; + +} + +/** + * @brief Launch the option byte loading. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM, + * FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE. + */ +FLASH_Status FLASH_OB_Launch(void) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Set the OPTSTRT bit in OPTCR register */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= FLASH_OPTCR_OPTSTRT; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(); + + return status; +} + +/** + * @brief Returns the FLASH User Option Bytes values. + * @param None + * @retval The FLASH User Option Bytes values: IWDG_SW(Bit0), RST_STOP(Bit1) + * and RST_STDBY(Bit2). + */ +uint8_t FLASH_OB_GetUser(void) +{ + /* Return the User Option Byte */ + return (uint8_t)(FLASH->OPTCR >> 5); +} + +/** + * @brief Returns the FLASH Write Protection Option Bytes value. + * @param None + * @retval The FLASH Write Protection Option Bytes value + */ +uint16_t FLASH_OB_GetWRP(void) +{ + /* Return the FLASH write protection Register value */ + return (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); +} + +/** + * @brief Returns the FLASH Read Protection level. + * @param None + * @retval FLASH ReadOut Protection Status: + * - SET, when OB_RDP_Level_1 or OB_RDP_Level_2 is set + * - RESET, when OB_RDP_Level_0 is set + */ +FlagStatus FLASH_OB_GetRDP(void) +{ + FlagStatus readstatus = RESET; + + if ((*(__IO uint8_t*)(OPTCR_BYTE1_ADDRESS) != (uint8_t)OB_RDP_Level_0)) + { + readstatus = SET; + } + else + { + readstatus = RESET; + } + return readstatus; +} + +/** + * @brief Returns the FLASH BOR level. + * @param None + * @retval The FLASH BOR level: + * - OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V + * - OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V + * - OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V + * - OB_BOR_OFF : Supply voltage ranges from 1.62 to 2.1 V + */ +uint8_t FLASH_OB_GetBOR(void) +{ + /* Return the FLASH BOR level */ + return (uint8_t)(*(__IO uint8_t *)(OPTCR_BYTE0_ADDRESS) & (uint8_t)0x0C); +} + +/** + * @} + */ + +/** @defgroup FLASH_Group4 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified FLASH interrupts. + * @param FLASH_IT: specifies the FLASH interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg FLASH_IT_ERR: FLASH Error Interrupt + * @arg FLASH_IT_EOP: FLASH end of operation Interrupt + * @retval None + */ +void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FLASH_IT(FLASH_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR |= FLASH_IT; + } + else + { + /* Disable the interrupt sources */ + FLASH->CR &= ~(uint32_t)FLASH_IT; + } +} + +/** + * @brief Checks whether the specified FLASH flag is set or not. + * @param FLASH_FLAG: specifies the FLASH flag to check. + * This parameter can be one of the following values: + * @arg FLASH_FLAG_EOP: FLASH End of Operation flag + * @arg FLASH_FLAG_OPERR: FLASH operation Error flag + * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag + * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag + * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag + * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag + * @arg FLASH_FLAG_BSY: FLASH Busy flag + * @retval The new state of FLASH_FLAG (SET or RESET). + */ +FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)); + + if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the new state of FLASH_FLAG (SET or RESET) */ + return bitstatus; +} + +/** + * @brief Clears the FLASH's pending flags. + * @param FLASH_FLAG: specifies the FLASH flags to clear. + * This parameter can be any combination of the following values: + * @arg FLASH_FLAG_EOP: FLASH End of Operation flag + * @arg FLASH_FLAG_OPERR: FLASH operation Error flag + * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag + * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag + * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag + * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag + * @retval None + */ +void FLASH_ClearFlag(uint32_t FLASH_FLAG) +{ + /* Check the parameters */ + assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)); + + /* Clear the flags */ + FLASH->SR = FLASH_FLAG; +} + +/** + * @brief Returns the FLASH Status. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM, + * FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE. + */ +FLASH_Status FLASH_GetStatus(void) +{ + FLASH_Status flashstatus = FLASH_COMPLETE; + + if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY) + { + flashstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR & FLASH_FLAG_WRPERR) != (uint32_t)0x00) + { + flashstatus = FLASH_ERROR_WRP; + } + else + { + if((FLASH->SR & (uint32_t)0xEF) != (uint32_t)0x00) + { + flashstatus = FLASH_ERROR_PROGRAM; + } + else + { + if((FLASH->SR & FLASH_FLAG_OPERR) != (uint32_t)0x00) + { + flashstatus = FLASH_ERROR_OPERATION; + } + else + { + flashstatus = FLASH_COMPLETE; + } + } + } + } + /* Return the FLASH Status */ + return flashstatus; +} + +/** + * @brief Waits for a FLASH operation to complete. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM, + * FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE. + */ +FLASH_Status FLASH_WaitForLastOperation(void) +{ + __IO FLASH_Status status = FLASH_COMPLETE; + + /* Check for the FLASH Status */ + status = FLASH_GetStatus(); + + /* Wait for the FLASH operation to complete by polling on BUSY flag to be reset. + Even if the FLASH operation fails, the BUSY flag will be reset and an error + flag will be set */ + while(status == FLASH_BUSY) + { + status = FLASH_GetStatus(); + } + /* Return the operation status */ + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fsmc.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fsmc.c new file mode 100644 index 000000000..c9780a576 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fsmc.c @@ -0,0 +1,982 @@ +/** + ****************************************************************************** + * @file stm32f4xx_fsmc.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the FSMC peripheral: + * - Interface with SRAM, PSRAM, NOR and OneNAND memories + * - Interface with NAND memories + * - Interface with 16-bit PC Card compatible memories + * - Interrupts and flags management + * + ****************************************************************************** + + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_fsmc.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup FSMC + * @brief FSMC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* --------------------- FSMC registers bit mask ---------------------------- */ +/* FSMC BCRx Mask */ +#define BCR_MBKEN_SET ((uint32_t)0x00000001) +#define BCR_MBKEN_RESET ((uint32_t)0x000FFFFE) +#define BCR_FACCEN_SET ((uint32_t)0x00000040) + +/* FSMC PCRx Mask */ +#define PCR_PBKEN_SET ((uint32_t)0x00000004) +#define PCR_PBKEN_RESET ((uint32_t)0x000FFFFB) +#define PCR_ECCEN_SET ((uint32_t)0x00000040) +#define PCR_ECCEN_RESET ((uint32_t)0x000FFFBF) +#define PCR_MEMORYTYPE_NAND ((uint32_t)0x00000008) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup FSMC_Private_Functions + * @{ + */ + +/** @defgroup FSMC_Group1 NOR/SRAM Controller functions + * @brief NOR/SRAM Controller functions + * +@verbatim + =============================================================================== + NOR/SRAM Controller functions + =============================================================================== + + The following sequence should be followed to configure the FSMC to interface with + SRAM, PSRAM, NOR or OneNAND memory connected to the NOR/SRAM Bank: + + 1. Enable the clock for the FSMC and associated GPIOs using the following functions: + RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_FSMC, ENABLE); + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE); + + 2. FSMC pins configuration + - Connect the involved FSMC pins to AF12 using the following function + GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_FSMC); + - Configure these FSMC pins in alternate function mode by calling the function + GPIO_Init(); + + 3. Declare a FSMC_NORSRAMInitTypeDef structure, for example: + FSMC_NORSRAMInitTypeDef FSMC_NORSRAMInitStructure; + and fill the FSMC_NORSRAMInitStructure variable with the allowed values of + the structure member. + + 4. Initialize the NOR/SRAM Controller by calling the function + FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure); + + 5. Then enable the NOR/SRAM Bank, for example: + FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM2, ENABLE); + + 6. At this stage you can read/write from/to the memory connected to the NOR/SRAM Bank. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the FSMC NOR/SRAM Banks registers to their default + * reset values. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1 + * @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 + * @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 + * @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 + * @retval None + */ +void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank) +{ + /* Check the parameter */ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank)); + + /* FSMC_Bank1_NORSRAM1 */ + if(FSMC_Bank == FSMC_Bank1_NORSRAM1) + { + FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030DB; + } + /* FSMC_Bank1_NORSRAM2, FSMC_Bank1_NORSRAM3 or FSMC_Bank1_NORSRAM4 */ + else + { + FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030D2; + } + FSMC_Bank1->BTCR[FSMC_Bank + 1] = 0x0FFFFFFF; + FSMC_Bank1E->BWTR[FSMC_Bank] = 0x0FFFFFFF; +} + +/** + * @brief Initializes the FSMC NOR/SRAM Banks according to the specified + * parameters in the FSMC_NORSRAMInitStruct. + * @param FSMC_NORSRAMInitStruct : pointer to a FSMC_NORSRAMInitTypeDef structure + * that contains the configuration information for the FSMC NOR/SRAM + * specified Banks. + * @retval None + */ +void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct) +{ + /* Check the parameters */ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_NORSRAMInitStruct->FSMC_Bank)); + assert_param(IS_FSMC_MUX(FSMC_NORSRAMInitStruct->FSMC_DataAddressMux)); + assert_param(IS_FSMC_MEMORY(FSMC_NORSRAMInitStruct->FSMC_MemoryType)); + assert_param(IS_FSMC_MEMORY_WIDTH(FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth)); + assert_param(IS_FSMC_BURSTMODE(FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode)); + assert_param(IS_FSMC_ASYNWAIT(FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait)); + assert_param(IS_FSMC_WAIT_POLARITY(FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity)); + assert_param(IS_FSMC_WRAP_MODE(FSMC_NORSRAMInitStruct->FSMC_WrapMode)); + assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive)); + assert_param(IS_FSMC_WRITE_OPERATION(FSMC_NORSRAMInitStruct->FSMC_WriteOperation)); + assert_param(IS_FSMC_WAITE_SIGNAL(FSMC_NORSRAMInitStruct->FSMC_WaitSignal)); + assert_param(IS_FSMC_EXTENDED_MODE(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode)); + assert_param(IS_FSMC_WRITE_BURST(FSMC_NORSRAMInitStruct->FSMC_WriteBurst)); + assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime)); + assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime)); + assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime)); + assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration)); + assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision)); + assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency)); + assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode)); + + /* Bank1 NOR/SRAM control register configuration */ + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_DataAddressMux | + FSMC_NORSRAMInitStruct->FSMC_MemoryType | + FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth | + FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode | + FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait | + FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity | + FSMC_NORSRAMInitStruct->FSMC_WrapMode | + FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive | + FSMC_NORSRAMInitStruct->FSMC_WriteOperation | + FSMC_NORSRAMInitStruct->FSMC_WaitSignal | + FSMC_NORSRAMInitStruct->FSMC_ExtendedMode | + FSMC_NORSRAMInitStruct->FSMC_WriteBurst; + if(FSMC_NORSRAMInitStruct->FSMC_MemoryType == FSMC_MemoryType_NOR) + { + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] |= (uint32_t)BCR_FACCEN_SET; + } + /* Bank1 NOR/SRAM timing register configuration */ + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank+1] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime << 4) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime << 8) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration << 16) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision << 20) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency << 24) | + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode; + + + /* Bank1 NOR/SRAM timing register for write configuration, if extended mode is used */ + if(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode == FSMC_ExtendedMode_Enable) + { + assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime)); + assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime)); + assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime)); + assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision)); + assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency)); + assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode)); + FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime << 4 )| + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime << 8) | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision << 20) | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency << 24) | + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode; + } + else + { + FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 0x0FFFFFFF; + } +} + +/** + * @brief Fills each FSMC_NORSRAMInitStruct member with its default value. + * @param FSMC_NORSRAMInitStruct: pointer to a FSMC_NORSRAMInitTypeDef structure + * which will be initialized. + * @retval None + */ +void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct) +{ + /* Reset NOR/SRAM Init structure parameters values */ + FSMC_NORSRAMInitStruct->FSMC_Bank = FSMC_Bank1_NORSRAM1; + FSMC_NORSRAMInitStruct->FSMC_DataAddressMux = FSMC_DataAddressMux_Enable; + FSMC_NORSRAMInitStruct->FSMC_MemoryType = FSMC_MemoryType_SRAM; + FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b; + FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; + FSMC_NORSRAMInitStruct->FSMC_WrapMode = FSMC_WrapMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; + FSMC_NORSRAMInitStruct->FSMC_WriteOperation = FSMC_WriteOperation_Enable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignal = FSMC_WaitSignal_Enable; + FSMC_NORSRAMInitStruct->FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_WriteBurst = FSMC_WriteBurst_Disable; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime = 0xFF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime = 0xFF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; +} + +/** + * @brief Enables or disables the specified NOR/SRAM Memory Bank. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1 + * @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 + * @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 + * @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 + * @param NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */ + FSMC_Bank1->BTCR[FSMC_Bank] |= BCR_MBKEN_SET; + } + else + { + /* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */ + FSMC_Bank1->BTCR[FSMC_Bank] &= BCR_MBKEN_RESET; + } +} +/** + * @} + */ + +/** @defgroup FSMC_Group2 NAND Controller functions + * @brief NAND Controller functions + * +@verbatim + =============================================================================== + NAND Controller functions + =============================================================================== + + The following sequence should be followed to configure the FSMC to interface with + 8-bit or 16-bit NAND memory connected to the NAND Bank: + + 1. Enable the clock for the FSMC and associated GPIOs using the following functions: + RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_FSMC, ENABLE); + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE); + + 2. FSMC pins configuration + - Connect the involved FSMC pins to AF12 using the following function + GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_FSMC); + - Configure these FSMC pins in alternate function mode by calling the function + GPIO_Init(); + + 3. Declare a FSMC_NANDInitTypeDef structure, for example: + FSMC_NANDInitTypeDef FSMC_NANDInitStructure; + and fill the FSMC_NANDInitStructure variable with the allowed values of + the structure member. + + 4. Initialize the NAND Controller by calling the function + FSMC_NANDInit(&FSMC_NANDInitStructure); + + 5. Then enable the NAND Bank, for example: + FSMC_NANDCmd(FSMC_Bank3_NAND, ENABLE); + + 6. At this stage you can read/write from/to the memory connected to the NAND Bank. + +@note To enable the Error Correction Code (ECC), you have to use the function + FSMC_NANDECCCmd(FSMC_Bank3_NAND, ENABLE); + and to get the current ECC value you have to use the function + ECCval = FSMC_GetECC(FSMC_Bank3_NAND); + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the FSMC NAND Banks registers to their default reset values. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @retval None + */ +void FSMC_NANDDeInit(uint32_t FSMC_Bank) +{ + /* Check the parameter */ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + /* Set the FSMC_Bank2 registers to their reset values */ + FSMC_Bank2->PCR2 = 0x00000018; + FSMC_Bank2->SR2 = 0x00000040; + FSMC_Bank2->PMEM2 = 0xFCFCFCFC; + FSMC_Bank2->PATT2 = 0xFCFCFCFC; + } + /* FSMC_Bank3_NAND */ + else + { + /* Set the FSMC_Bank3 registers to their reset values */ + FSMC_Bank3->PCR3 = 0x00000018; + FSMC_Bank3->SR3 = 0x00000040; + FSMC_Bank3->PMEM3 = 0xFCFCFCFC; + FSMC_Bank3->PATT3 = 0xFCFCFCFC; + } +} + +/** + * @brief Initializes the FSMC NAND Banks according to the specified parameters + * in the FSMC_NANDInitStruct. + * @param FSMC_NANDInitStruct : pointer to a FSMC_NANDInitTypeDef structure that + * contains the configuration information for the FSMC NAND specified Banks. + * @retval None + */ +void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct) +{ + uint32_t tmppcr = 0x00000000, tmppmem = 0x00000000, tmppatt = 0x00000000; + + /* Check the parameters */ + assert_param( IS_FSMC_NAND_BANK(FSMC_NANDInitStruct->FSMC_Bank)); + assert_param( IS_FSMC_WAIT_FEATURE(FSMC_NANDInitStruct->FSMC_Waitfeature)); + assert_param( IS_FSMC_MEMORY_WIDTH(FSMC_NANDInitStruct->FSMC_MemoryDataWidth)); + assert_param( IS_FSMC_ECC_STATE(FSMC_NANDInitStruct->FSMC_ECC)); + assert_param( IS_FSMC_ECCPAGE_SIZE(FSMC_NANDInitStruct->FSMC_ECCPageSize)); + assert_param( IS_FSMC_TCLR_TIME(FSMC_NANDInitStruct->FSMC_TCLRSetupTime)); + assert_param( IS_FSMC_TAR_TIME(FSMC_NANDInitStruct->FSMC_TARSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime)); + + /* Set the tmppcr value according to FSMC_NANDInitStruct parameters */ + tmppcr = (uint32_t)FSMC_NANDInitStruct->FSMC_Waitfeature | + PCR_MEMORYTYPE_NAND | + FSMC_NANDInitStruct->FSMC_MemoryDataWidth | + FSMC_NANDInitStruct->FSMC_ECC | + FSMC_NANDInitStruct->FSMC_ECCPageSize | + (FSMC_NANDInitStruct->FSMC_TCLRSetupTime << 9 )| + (FSMC_NANDInitStruct->FSMC_TARSetupTime << 13); + + /* Set tmppmem value according to FSMC_CommonSpaceTimingStructure parameters */ + tmppmem = (uint32_t)FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime | + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set tmppatt value according to FSMC_AttributeSpaceTimingStructure parameters */ + tmppatt = (uint32_t)FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime | + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + if(FSMC_NANDInitStruct->FSMC_Bank == FSMC_Bank2_NAND) + { + /* FSMC_Bank2_NAND registers configuration */ + FSMC_Bank2->PCR2 = tmppcr; + FSMC_Bank2->PMEM2 = tmppmem; + FSMC_Bank2->PATT2 = tmppatt; + } + else + { + /* FSMC_Bank3_NAND registers configuration */ + FSMC_Bank3->PCR3 = tmppcr; + FSMC_Bank3->PMEM3 = tmppmem; + FSMC_Bank3->PATT3 = tmppatt; + } +} + + +/** + * @brief Fills each FSMC_NANDInitStruct member with its default value. + * @param FSMC_NANDInitStruct: pointer to a FSMC_NANDInitTypeDef structure which + * will be initialized. + * @retval None + */ +void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct) +{ + /* Reset NAND Init structure parameters values */ + FSMC_NANDInitStruct->FSMC_Bank = FSMC_Bank2_NAND; + FSMC_NANDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable; + FSMC_NANDInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b; + FSMC_NANDInitStruct->FSMC_ECC = FSMC_ECC_Disable; + FSMC_NANDInitStruct->FSMC_ECCPageSize = FSMC_ECCPageSize_256Bytes; + FSMC_NANDInitStruct->FSMC_TCLRSetupTime = 0x0; + FSMC_NANDInitStruct->FSMC_TARSetupTime = 0x0; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; +} + +/** + * @brief Enables or disables the specified NAND Memory Bank. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @param NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 |= PCR_PBKEN_SET; + } + else + { + FSMC_Bank3->PCR3 |= PCR_PBKEN_SET; + } + } + else + { + /* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 &= PCR_PBKEN_RESET; + } + else + { + FSMC_Bank3->PCR3 &= PCR_PBKEN_RESET; + } + } +} +/** + * @brief Enables or disables the FSMC NAND ECC feature. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @param NewState: new state of the FSMC NAND ECC feature. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 |= PCR_ECCEN_SET; + } + else + { + FSMC_Bank3->PCR3 |= PCR_ECCEN_SET; + } + } + else + { + /* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 &= PCR_ECCEN_RESET; + } + else + { + FSMC_Bank3->PCR3 &= PCR_ECCEN_RESET; + } + } +} + +/** + * @brief Returns the error correction code register value. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @retval The Error Correction Code (ECC) value. + */ +uint32_t FSMC_GetECC(uint32_t FSMC_Bank) +{ + uint32_t eccval = 0x00000000; + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + /* Get the ECCR2 register value */ + eccval = FSMC_Bank2->ECCR2; + } + else + { + /* Get the ECCR3 register value */ + eccval = FSMC_Bank3->ECCR3; + } + /* Return the error correction code value */ + return(eccval); +} +/** + * @} + */ + +/** @defgroup FSMC_Group3 PCCARD Controller functions + * @brief PCCARD Controller functions + * +@verbatim + =============================================================================== + PCCARD Controller functions + =============================================================================== + + The following sequence should be followed to configure the FSMC to interface with + 16-bit PC Card compatible memory connected to the PCCARD Bank: + + 1. Enable the clock for the FSMC and associated GPIOs using the following functions: + RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_FSMC, ENABLE); + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE); + + 2. FSMC pins configuration + - Connect the involved FSMC pins to AF12 using the following function + GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_FSMC); + - Configure these FSMC pins in alternate function mode by calling the function + GPIO_Init(); + + 3. Declare a FSMC_PCCARDInitTypeDef structure, for example: + FSMC_PCCARDInitTypeDef FSMC_PCCARDInitStructure; + and fill the FSMC_PCCARDInitStructure variable with the allowed values of + the structure member. + + 4. Initialize the PCCARD Controller by calling the function + FSMC_PCCARDInit(&FSMC_PCCARDInitStructure); + + 5. Then enable the PCCARD Bank: + FSMC_PCCARDCmd(ENABLE); + + 6. At this stage you can read/write from/to the memory connected to the PCCARD Bank. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the FSMC PCCARD Bank registers to their default reset values. + * @param None + * @retval None + */ +void FSMC_PCCARDDeInit(void) +{ + /* Set the FSMC_Bank4 registers to their reset values */ + FSMC_Bank4->PCR4 = 0x00000018; + FSMC_Bank4->SR4 = 0x00000000; + FSMC_Bank4->PMEM4 = 0xFCFCFCFC; + FSMC_Bank4->PATT4 = 0xFCFCFCFC; + FSMC_Bank4->PIO4 = 0xFCFCFCFC; +} + +/** + * @brief Initializes the FSMC PCCARD Bank according to the specified parameters + * in the FSMC_PCCARDInitStruct. + * @param FSMC_PCCARDInitStruct : pointer to a FSMC_PCCARDInitTypeDef structure + * that contains the configuration information for the FSMC PCCARD Bank. + * @retval None + */ +void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct) +{ + /* Check the parameters */ + assert_param(IS_FSMC_WAIT_FEATURE(FSMC_PCCARDInitStruct->FSMC_Waitfeature)); + assert_param(IS_FSMC_TCLR_TIME(FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime)); + assert_param(IS_FSMC_TAR_TIME(FSMC_PCCARDInitStruct->FSMC_TARSetupTime)); + + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime)); + + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime)); + + /* Set the PCR4 register value according to FSMC_PCCARDInitStruct parameters */ + FSMC_Bank4->PCR4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_Waitfeature | + FSMC_MemoryDataWidth_16b | + (FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime << 9) | + (FSMC_PCCARDInitStruct->FSMC_TARSetupTime << 13); + + /* Set PMEM4 register value according to FSMC_CommonSpaceTimingStructure parameters */ + FSMC_Bank4->PMEM4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set PATT4 register value according to FSMC_AttributeSpaceTimingStructure parameters */ + FSMC_Bank4->PATT4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set PIO4 register value according to FSMC_IOSpaceTimingStructure parameters */ + FSMC_Bank4->PIO4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime << 24); +} + +/** + * @brief Fills each FSMC_PCCARDInitStruct member with its default value. + * @param FSMC_PCCARDInitStruct: pointer to a FSMC_PCCARDInitTypeDef structure + * which will be initialized. + * @retval None + */ +void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct) +{ + /* Reset PCCARD Init structure parameters values */ + FSMC_PCCARDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable; + FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime = 0x0; + FSMC_PCCARDInitStruct->FSMC_TARSetupTime = 0x0; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; +} + +/** + * @brief Enables or disables the PCCARD Memory Bank. + * @param NewState: new state of the PCCARD Memory Bank. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_PCCARDCmd(FunctionalState NewState) +{ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the PCCARD Bank by setting the PBKEN bit in the PCR4 register */ + FSMC_Bank4->PCR4 |= PCR_PBKEN_SET; + } + else + { + /* Disable the PCCARD Bank by clearing the PBKEN bit in the PCR4 register */ + FSMC_Bank4->PCR4 &= PCR_PBKEN_RESET; + } +} +/** + * @} + */ + +/** @defgroup FSMC_Group4 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified FSMC interrupts. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the FSMC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @param NewState: new state of the specified FSMC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState) +{ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_IT(FSMC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected FSMC_Bank2 interrupts */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 |= FSMC_IT; + } + /* Enable the selected FSMC_Bank3 interrupts */ + else if (FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 |= FSMC_IT; + } + /* Enable the selected FSMC_Bank4 interrupts */ + else + { + FSMC_Bank4->SR4 |= FSMC_IT; + } + } + else + { + /* Disable the selected FSMC_Bank2 interrupts */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + + FSMC_Bank2->SR2 &= (uint32_t)~FSMC_IT; + } + /* Disable the selected FSMC_Bank3 interrupts */ + else if (FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= (uint32_t)~FSMC_IT; + } + /* Disable the selected FSMC_Bank4 interrupts */ + else + { + FSMC_Bank4->SR4 &= (uint32_t)~FSMC_IT; + } + } +} + +/** + * @brief Checks whether the specified FSMC flag is set or not. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg FSMC_FLAG_RisingEdge: Rising edge detection Flag. + * @arg FSMC_FLAG_Level: Level detection Flag. + * @arg FSMC_FLAG_FallingEdge: Falling edge detection Flag. + * @arg FSMC_FLAG_FEMPT: Fifo empty Flag. + * @retval The new state of FSMC_FLAG (SET or RESET). + */ +FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tmpsr = 0x00000000; + + /* Check the parameters */ + assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank)); + assert_param(IS_FSMC_GET_FLAG(FSMC_FLAG)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + tmpsr = FSMC_Bank2->SR2; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + tmpsr = FSMC_Bank3->SR3; + } + /* FSMC_Bank4_PCCARD*/ + else + { + tmpsr = FSMC_Bank4->SR4; + } + + /* Get the flag status */ + if ((tmpsr & FSMC_FLAG) != (uint16_t)RESET ) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the FSMC's pending flags. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg FSMC_FLAG_RisingEdge: Rising edge detection Flag. + * @arg FSMC_FLAG_Level: Level detection Flag. + * @arg FSMC_FLAG_FallingEdge: Falling edge detection Flag. + * @retval None + */ +void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank)); + assert_param(IS_FSMC_CLEAR_FLAG(FSMC_FLAG)) ; + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 &= ~FSMC_FLAG; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= ~FSMC_FLAG; + } + /* FSMC_Bank4_PCCARD*/ + else + { + FSMC_Bank4->SR4 &= ~FSMC_FLAG; + } +} + +/** + * @brief Checks whether the specified FSMC interrupt has occurred or not. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the FSMC interrupt source to check. + * This parameter can be one of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @retval The new state of FSMC_IT (SET or RESET). + */ +ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpsr = 0x0, itstatus = 0x0, itenable = 0x0; + + /* Check the parameters */ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_GET_IT(FSMC_IT)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + tmpsr = FSMC_Bank2->SR2; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + tmpsr = FSMC_Bank3->SR3; + } + /* FSMC_Bank4_PCCARD*/ + else + { + tmpsr = FSMC_Bank4->SR4; + } + + itstatus = tmpsr & FSMC_IT; + + itenable = tmpsr & (FSMC_IT >> 3); + if ((itstatus != (uint32_t)RESET) && (itenable != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the FSMC's interrupt pending bits. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @retval None + */ +void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT) +{ + /* Check the parameters */ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_IT(FSMC_IT)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 &= ~(FSMC_IT >> 3); + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= ~(FSMC_IT >> 3); + } + /* FSMC_Bank4_PCCARD*/ + else + { + FSMC_Bank4->SR4 &= ~(FSMC_IT >> 3); + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c new file mode 100644 index 000000000..5ea2385ce --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c @@ -0,0 +1,561 @@ +/** + ****************************************************************************** + * @file stm32f4xx_gpio.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the GPIO peripheral: + * - Initialization and Configuration + * - GPIO Read and Write + * - GPIO Alternate functions configuration + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * 1. Enable the GPIO AHB clock using the following function + * RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE); + * + * 2. Configure the GPIO pin(s) using GPIO_Init() + * Four possible configuration are available for each pin: + * - Input: Floating, Pull-up, Pull-down. + * - Output: Push-Pull (Pull-up, Pull-down or no Pull) + * Open Drain (Pull-up, Pull-down or no Pull). + * In output mode, the speed is configurable: 2 MHz, 25 MHz, + * 50 MHz or 100 MHz. + * - Alternate Function: Push-Pull (Pull-up, Pull-down or no Pull) + * Open Drain (Pull-up, Pull-down or no Pull). + * - Analog: required mode when a pin is to be used as ADC channel + * or DAC output. + * + * 3- Peripherals alternate function: + * - For ADC and DAC, configure the desired pin in analog mode using + * GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AN; + * - For other peripherals (TIM, USART...): + * - Connect the pin to the desired peripherals' Alternate + * Function (AF) using GPIO_PinAFConfig() function + * - Configure the desired pin in alternate function mode using + * GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF + * - Select the type, pull-up/pull-down and output speed via + * GPIO_PuPd, GPIO_OType and GPIO_Speed members + * - Call GPIO_Init() function + * + * 4. To get the level of a pin configured in input mode use GPIO_ReadInputDataBit() + * + * 5. To set/reset the level of a pin configured in output mode use + * GPIO_SetBits()/GPIO_ResetBits() + * + * 6. During and just after reset, the alternate functions are not + * active and the GPIO pins are configured in input floating mode + * (except JTAG pins). + * + * 7. The LSE oscillator pins OSC32_IN and OSC32_OUT can be used as + * general-purpose (PC14 and PC15, respectively) when the LSE + * oscillator is off. The LSE has priority over the GPIO function. + * + * 8. The HSE oscillator pins OSC_IN/OSC_OUT can be used as + * general-purpose PH0 and PH1, respectively, when the HSE + * oscillator is off. The HSE has priority over the GPIO function. + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_gpio.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup GPIO + * @brief GPIO driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup GPIO_Private_Functions + * @{ + */ + +/** @defgroup GPIO_Group1 Initialization and Configuration + * @brief Initialization and Configuration + * +@verbatim + =============================================================================== + Initialization and Configuration + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the GPIOx peripheral registers to their default reset values. + * @note By default, The GPIO pins are configured in input floating mode (except JTAG pins). + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @retval None + */ +void GPIO_DeInit(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + if (GPIOx == GPIOA) + { + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOA, ENABLE); + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOA, DISABLE); + } + else if (GPIOx == GPIOB) + { + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOB, ENABLE); + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOB, DISABLE); + } + else if (GPIOx == GPIOC) + { + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOC, ENABLE); + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOC, DISABLE); + } + else if (GPIOx == GPIOD) + { + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOD, ENABLE); + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOD, DISABLE); + } + else if (GPIOx == GPIOE) + { + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOE, ENABLE); + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOE, DISABLE); + } + else if (GPIOx == GPIOF) + { + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOF, ENABLE); + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOF, DISABLE); + } + else if (GPIOx == GPIOG) + { + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOG, ENABLE); + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOG, DISABLE); + } + else if (GPIOx == GPIOH) + { + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOH, ENABLE); + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOH, DISABLE); + } + else + { + if (GPIOx == GPIOI) + { + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOI, ENABLE); + RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOI, DISABLE); + } + } +} + +/** + * @brief Initializes the GPIOx peripheral according to the specified parameters in the GPIO_InitStruct. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that contains + * the configuration information for the specified GPIO peripheral. + * @retval None + */ +void GPIO_Init(GPIO_TypeDef* GPIOx, const GPIO_InitTypeDef* GPIO_InitStruct) +{ + uint32_t pinpos = 0x00, pos = 0x00 , currentpin = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin)); + assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode)); + assert_param(IS_GPIO_PUPD(GPIO_InitStruct->GPIO_PuPd)); + + /* -------------------------Configure the port pins---------------- */ + /*-- GPIO Mode Configuration --*/ + for (pinpos = 0x00; pinpos < 0x10; pinpos++) + { + pos = ((uint32_t)0x01) << pinpos; + /* Get the port pins position */ + currentpin = (GPIO_InitStruct->GPIO_Pin) & pos; + + if (currentpin == pos) + { + GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (pinpos * 2)); + GPIOx->MODER |= (((uint32_t)GPIO_InitStruct->GPIO_Mode) << (pinpos * 2)); + + if ((GPIO_InitStruct->GPIO_Mode == GPIO_Mode_OUT) || (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_AF)) + { + /* Check Speed mode parameters */ + assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed)); + + /* Speed mode configuration */ + GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (pinpos * 2)); + GPIOx->OSPEEDR |= ((uint32_t)(GPIO_InitStruct->GPIO_Speed) << (pinpos * 2)); + + /* Check Output mode parameters */ + assert_param(IS_GPIO_OTYPE(GPIO_InitStruct->GPIO_OType)); + + /* Output mode configuration*/ + GPIOx->OTYPER &= ~((GPIO_OTYPER_OT_0) << ((uint16_t)pinpos)) ; + GPIOx->OTYPER |= (uint16_t)(((uint16_t)GPIO_InitStruct->GPIO_OType) << ((uint16_t)pinpos)); + } + + /* Pull-up Pull down resistor configuration*/ + GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << ((uint16_t)pinpos * 2)); + GPIOx->PUPDR |= (((uint32_t)GPIO_InitStruct->GPIO_PuPd) << (pinpos * 2)); + } + } +} + +/** + * @brief Fills each GPIO_InitStruct member with its default value. + * @param GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure which will be initialized. + * @retval None + */ +void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct) +{ + /* Reset GPIO init structure parameters values */ + GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All; + GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN; + GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStruct->GPIO_OType = GPIO_OType_PP; + GPIO_InitStruct->GPIO_PuPd = GPIO_PuPd_NOPULL; +} + +/** + * @brief Locks GPIO Pins configuration registers. + * @note The locked registers are GPIOx_MODER, GPIOx_OTYPER, GPIOx_OSPEEDR, + * GPIOx_PUPDR, GPIOx_AFRL and GPIOx_AFRH. + * @note The configuration of the locked GPIO pins can no longer be modified + * until the next reset. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to be locked. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + __IO uint32_t tmp = 0x00010000; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + tmp |= GPIO_Pin; + /* Set LCKK bit */ + GPIOx->LCKR = tmp; + /* Reset LCKK bit */ + GPIOx->LCKR = GPIO_Pin; + /* Set LCKK bit */ + GPIOx->LCKR = tmp; + /* Read LCKK bit*/ + tmp = GPIOx->LCKR; + /* Read LCKK bit*/ + tmp = GPIOx->LCKR; +} + +/** + * @} + */ + +/** @defgroup GPIO_Group2 GPIO Read and Write + * @brief GPIO Read and Write + * +@verbatim + =============================================================================== + GPIO Read and Write + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Reads the specified input port pin. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to read. + * This parameter can be GPIO_Pin_x where x can be (0..15). + * @retval The input port pin value. + */ +uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint8_t bitstatus = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + + if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET) + { + bitstatus = (uint8_t)Bit_SET; + } + else + { + bitstatus = (uint8_t)Bit_RESET; + } + return bitstatus; +} + +/** + * @brief Reads the specified GPIO input data port. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @retval GPIO input data port value. + */ +uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + return ((uint16_t)GPIOx->IDR); +} + +/** + * @brief Reads the specified output data port bit. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to read. + * This parameter can be GPIO_Pin_x where x can be (0..15). + * @retval The output port pin value. + */ +uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint8_t bitstatus = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + + if ((GPIOx->ODR & GPIO_Pin) != (uint32_t)Bit_RESET) + { + bitstatus = (uint8_t)Bit_SET; + } + else + { + bitstatus = (uint8_t)Bit_RESET; + } + return bitstatus; +} + +/** + * @brief Reads the specified GPIO output data port. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @retval GPIO output data port value. + */ +uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + return ((uint16_t)GPIOx->ODR); +} + +/** + * @brief Sets the selected data port bits. + * @note This functions uses GPIOx_BSRR register to allow atomic read/modify + * accesses. In this way, there is no risk of an IRQ occurring between + * the read and the modify access. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bits to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + GPIOx->BSRRL = GPIO_Pin; +} + +/** + * @brief Clears the selected data port bits. + * @note This functions uses GPIOx_BSRR register to allow atomic read/modify + * accesses. In this way, there is no risk of an IRQ occurring between + * the read and the modify access. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bits to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + GPIOx->BSRRH = GPIO_Pin; +} + +/** + * @brief Sets or clears the selected data port bit. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to be written. + * This parameter can be one of GPIO_Pin_x where x can be (0..15). + * @param BitVal: specifies the value to be written to the selected bit. + * This parameter can be one of the BitAction enum values: + * @arg Bit_RESET: to clear the port pin + * @arg Bit_SET: to set the port pin + * @retval None + */ +void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + assert_param(IS_GPIO_BIT_ACTION(BitVal)); + + if (BitVal != Bit_RESET) + { + GPIOx->BSRRL = GPIO_Pin; + } + else + { + GPIOx->BSRRH = GPIO_Pin ; + } +} + +/** + * @brief Writes data to the specified GPIO data port. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @param PortVal: specifies the value to be written to the port output data register. + * @retval None + */ +void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + GPIOx->ODR = PortVal; +} + +/** + * @brief Toggles the specified GPIO pins.. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @param GPIO_Pin: Specifies the pins to be toggled. + * @retval None + */ +void GPIO_ToggleBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + GPIOx->ODR ^= GPIO_Pin; +} + +/** + * @} + */ + +/** @defgroup GPIO_Group3 GPIO Alternate functions configuration function + * @brief GPIO Alternate functions configuration function + * +@verbatim + =============================================================================== + GPIO Alternate functions configuration function + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Changes the mapping of the specified pin. + * @param GPIOx: where x can be (A..I) to select the GPIO peripheral. + * @param GPIO_PinSource: specifies the pin for the Alternate function. + * This parameter can be GPIO_PinSourcex where x can be (0..15). + * @param GPIO_AFSelection: selects the pin to used as Alternate function. + * This parameter can be one of the following values: + * @arg GPIO_AF_RTC_50Hz: Connect RTC_50Hz pin to AF0 (default after reset) + * @arg GPIO_AF_MCO: Connect MCO pin (MCO1 and MCO2) to AF0 (default after reset) + * @arg GPIO_AF_TAMPER: Connect TAMPER pins (TAMPER_1 and TAMPER_2) to AF0 (default after reset) + * @arg GPIO_AF_SWJ: Connect SWJ pins (SWD and JTAG)to AF0 (default after reset) + * @arg GPIO_AF_TRACE: Connect TRACE pins to AF0 (default after reset) + * @arg GPIO_AF_TIM1: Connect TIM1 pins to AF1 + * @arg GPIO_AF_TIM2: Connect TIM2 pins to AF1 + * @arg GPIO_AF_TIM3: Connect TIM3 pins to AF2 + * @arg GPIO_AF_TIM4: Connect TIM4 pins to AF2 + * @arg GPIO_AF_TIM5: Connect TIM5 pins to AF2 + * @arg GPIO_AF_TIM8: Connect TIM8 pins to AF3 + * @arg GPIO_AF_TIM9: Connect TIM9 pins to AF3 + * @arg GPIO_AF_TIM10: Connect TIM10 pins to AF3 + * @arg GPIO_AF_TIM11: Connect TIM11 pins to AF3 + * @arg GPIO_AF_I2C1: Connect I2C1 pins to AF4 + * @arg GPIO_AF_I2C2: Connect I2C2 pins to AF4 + * @arg GPIO_AF_I2C3: Connect I2C3 pins to AF4 + * @arg GPIO_AF_SPI1: Connect SPI1 pins to AF5 + * @arg GPIO_AF_SPI2: Connect SPI2/I2S2 pins to AF5 + * @arg GPIO_AF_SPI3: Connect SPI3/I2S3 pins to AF6 + * @arg GPIO_AF_I2S3ext: Connect I2S3ext pins to AF7 + * @arg GPIO_AF_USART1: Connect USART1 pins to AF7 + * @arg GPIO_AF_USART2: Connect USART2 pins to AF7 + * @arg GPIO_AF_USART3: Connect USART3 pins to AF7 + * @arg GPIO_AF_UART4: Connect UART4 pins to AF8 + * @arg GPIO_AF_UART5: Connect UART5 pins to AF8 + * @arg GPIO_AF_USART6: Connect USART6 pins to AF8 + * @arg GPIO_AF_CAN1: Connect CAN1 pins to AF9 + * @arg GPIO_AF_CAN2: Connect CAN2 pins to AF9 + * @arg GPIO_AF_TIM12: Connect TIM12 pins to AF9 + * @arg GPIO_AF_TIM13: Connect TIM13 pins to AF9 + * @arg GPIO_AF_TIM14: Connect TIM14 pins to AF9 + * @arg GPIO_AF_OTG_FS: Connect OTG_FS pins to AF10 + * @arg GPIO_AF_OTG_HS: Connect OTG_HS pins to AF10 + * @arg GPIO_AF_ETH: Connect ETHERNET pins to AF11 + * @arg GPIO_AF_FSMC: Connect FSMC pins to AF12 + * @arg GPIO_AF_OTG_HS_FS: Connect OTG HS (configured in FS) pins to AF12 + * @arg GPIO_AF_SDIO: Connect SDIO pins to AF12 + * @arg GPIO_AF_DCMI: Connect DCMI pins to AF13 + * @arg GPIO_AF_EVENTOUT: Connect EVENTOUT pins to AF15 + * @retval None + */ +void GPIO_PinAFConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF) +{ + uint32_t temp = 0x00; + uint32_t temp_2 = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); + assert_param(IS_GPIO_AF(GPIO_AF)); + + temp = ((uint32_t)(GPIO_AF) << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4)) ; + GPIOx->AFR[GPIO_PinSource >> 0x03] &= ~((uint32_t)0xF << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4)) ; + temp_2 = GPIOx->AFR[GPIO_PinSource >> 0x03] | temp; + GPIOx->AFR[GPIO_PinSource >> 0x03] = temp_2; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash.c new file mode 100644 index 000000000..d4fe401d7 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash.c @@ -0,0 +1,700 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hash.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the HASH / HMAC Processor (HASH) peripheral: + * - Initialization and Configuration functions + * - Message Digest generation functions + * - context swapping functions + * - DMA interface function + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * HASH operation : + * ---------------- + * 1. Enable the HASH controller clock using + * RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_HASH, ENABLE) function. + * + * 2. Initialise the HASH using HASH_Init() function. + * + * 3 . Reset the HASH processor core, so that the HASH will be ready + * to compute he message digest of a new message by using + * HASH_Reset() function. + * + * 4. Enable the HASH controller using the HASH_Cmd() function. + * + * 5. if using DMA for Data input transfer, Activate the DMA Request + * using HASH_DMACmd() function + * + * 6. if DMA is not used for data transfer, use HASH_DataIn() function + * to enter data to IN FIFO. + * + * + * 7. Configure the Number of valid bits in last word of the message + * using HASH_SetLastWordValidBitsNbr() function. + * + * 8. if the message length is not an exact multiple of 512 bits, + * then the function HASH_StartDigest() must be called to + * launch the computation of the final digest. + * + * 9. Once computed, the digest can be read using HASH_GetDigest() + * function. + * + * 10. To control HASH events you can use one of the following + * two methods: + * a- Check on HASH flags using the HASH_GetFlagStatus() function. + * b- Use HASH interrupts through the function HASH_ITConfig() at + * initialization phase and HASH_GetITStatus() function into + * interrupt routines in hashing phase. + * After checking on a flag you should clear it using HASH_ClearFlag() + * function. And after checking on an interrupt event you should + * clear it using HASH_ClearITPendingBit() function. + * + * 11. Save and restore hash processor context using + * HASH_SaveContext() and HASH_RestoreContext() functions. + * + * + * + * HMAC operation : + * ---------------- + * The HMAC algorithm is used for message authentication, by + * irreversibly binding the message being processed to a key chosen + * by the user. + * For HMAC specifications, refer to "HMAC: keyed-hashing for message + * authentication, H. Krawczyk, M. Bellare, R. Canetti, February 1997" + * + * Basically, the HMAC algorithm consists of two nested hash operations: + * HMAC(message) = Hash[((key | pad) XOR 0x5C) | Hash(((key | pad) XOR 0x36) | message)] + * where: + * - "pad" is a sequence of zeroes needed to extend the key to the + * length of the underlying hash function data block (that is + * 512 bits for both the SHA-1 and MD5 hash algorithms) + * - "|" represents the concatenation operator + * + * + * To compute the HMAC, four different phases are required: + * + * 1. Initialise the HASH using HASH_Init() function to do HMAC + * operation. + * + * 2. The key (to be used for the inner hash function) is then given + * to the core. This operation follows the same mechanism as the + * one used to send the message in the hash operation (that is, + * by HASH_DataIn() function and, finally, + * HASH_StartDigest() function. + * + * 3. Once the last word has been entered and computation has started, + * the hash processor elaborates the key. It is then ready to + * accept the message text using the same mechanism as the one + * used to send the message in the hash operation. + * + * 4. After the first hash round, the hash processor returns "ready" + * to indicate that it is ready to receive the key to be used for + * the outer hash function (normally, this key is the same as the + * one used for the inner hash function). When the last word of + * the key is entered and computation starts, the HMAC result is + * made available using HASH_GetDigest() function. + * + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hash.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup HASH + * @brief HASH driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup HASH_Private_Functions + * @{ + */ + +/** @defgroup HASH_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + This section provides functions allowing to + - Initialize the HASH peripheral + - Configure the HASH Processor + - MD5/SHA1, + - HASH/HMAC, + - datatype + - HMAC Key (if mode = HMAC) + - Reset the HASH Processor + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the HASH peripheral registers to their default reset values + * @param None + * @retval None + */ +void HASH_DeInit(void) +{ + /* Enable HASH reset state */ + RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_HASH, ENABLE); + /* Release HASH from reset state */ + RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_HASH, DISABLE); +} + +/** + * @brief Initializes the HASH peripheral according to the specified parameters + * in the HASH_InitStruct structure. + * @note the hash processor is reset when calling this function so that the + * HASH will be ready to compute the message digest of a new message. + * There is no need to call HASH_Reset() function. + * @param HASH_InitStruct: pointer to a HASH_InitTypeDef structure that contains + * the configuration information for the HASH peripheral. + * @note The field HASH_HMACKeyType in HASH_InitTypeDef must be filled only + * if the algorithm mode is HMAC. + * @retval None + */ +void HASH_Init(HASH_InitTypeDef* HASH_InitStruct) +{ + /* Check the parameters */ + assert_param(IS_HASH_ALGOSELECTION(HASH_InitStruct->HASH_AlgoSelection)); + assert_param(IS_HASH_DATATYPE(HASH_InitStruct->HASH_DataType)); + assert_param(IS_HASH_ALGOMODE(HASH_InitStruct->HASH_AlgoMode)); + + /* Configure the Algorithm used, algorithm mode and the datatype */ + HASH->CR &= ~ (HASH_CR_ALGO | HASH_CR_DATATYPE | HASH_CR_MODE); + HASH->CR |= (HASH_InitStruct->HASH_AlgoSelection | \ + HASH_InitStruct->HASH_DataType | \ + HASH_InitStruct->HASH_AlgoMode); + + /* if algorithm mode is HMAC, set the Key */ + if(HASH_InitStruct->HASH_AlgoMode == HASH_AlgoMode_HMAC) + { + assert_param(IS_HASH_HMAC_KEYTYPE(HASH_InitStruct->HASH_HMACKeyType)); + HASH->CR &= ~HASH_CR_LKEY; + HASH->CR |= HASH_InitStruct->HASH_HMACKeyType; + } + + /* Reset the HASH processor core, so that the HASH will be ready to compute + the message digest of a new message */ + HASH->CR |= HASH_CR_INIT; +} + +/** + * @brief Fills each HASH_InitStruct member with its default value. + * @param HASH_InitStruct : pointer to a HASH_InitTypeDef structure which will + * be initialized. + * @note The default values set are : Processor mode is HASH, Algorithm selected is SHA1, + * Data type selected is 32b and HMAC Key Type is short key. + * @retval None + */ +void HASH_StructInit(HASH_InitTypeDef* HASH_InitStruct) +{ + /* Initialize the HASH_AlgoSelection member */ + HASH_InitStruct->HASH_AlgoSelection = HASH_AlgoSelection_SHA1; + + /* Initialize the HASH_AlgoMode member */ + HASH_InitStruct->HASH_AlgoMode = HASH_AlgoMode_HASH; + + /* Initialize the HASH_DataType member */ + HASH_InitStruct->HASH_DataType = HASH_DataType_32b; + + /* Initialize the HASH_HMACKeyType member */ + HASH_InitStruct->HASH_HMACKeyType = HASH_HMACKeyType_ShortKey; +} + +/** + * @brief Resets the HASH processor core, so that the HASH will be ready + * to compute the message digest of a new message. + * @note Calling this function will clear the HASH_SR_DCIS (Digest calculation + * completion interrupt status) bit corresponding to HASH_IT_DCI + * interrupt and HASH_FLAG_DCIS flag. + * @param None + * @retval None + */ +void HASH_Reset(void) +{ + /* Reset the HASH processor core */ + HASH->CR |= HASH_CR_INIT; +} +/** + * @} + */ + +/** @defgroup HASH_Group2 Message Digest generation functions + * @brief Message Digest generation functions + * +@verbatim + =============================================================================== + Message Digest generation functions + =============================================================================== + This section provides functions allowing the generation of message digest: + - Push data in the IN FIFO : using HASH_DataIn() + - Get the number of words set in IN FIFO, use HASH_GetInFIFOWordsNbr() + - set the last word valid bits number using HASH_SetLastWordValidBitsNbr() + - start digest calculation : using HASH_StartDigest() + - Get the Digest message : using HASH_GetDigest() + +@endverbatim + * @{ + */ + + +/** + * @brief Configure the Number of valid bits in last word of the message + * @param ValidNumber: Number of valid bits in last word of the message. + * This parameter must be a number between 0 and 0x1F. + * - 0x00: All 32 bits of the last data written are valid + * - 0x01: Only bit [0] of the last data written is valid + * - 0x02: Only bits[1:0] of the last data written are valid + * - 0x03: Only bits[2:0] of the last data written are valid + * - ... + * - 0x1F: Only bits[30:0] of the last data written are valid + * @note The Number of valid bits must be set before to start the message + * digest competition (in Hash and HMAC) and key treatment(in HMAC). + * @retval None + */ +void HASH_SetLastWordValidBitsNbr(uint16_t ValidNumber) +{ + /* Check the parameters */ + assert_param(IS_HASH_VALIDBITSNUMBER(ValidNumber)); + + /* Configure the Number of valid bits in last word of the message */ + HASH->STR &= ~(HASH_STR_NBW); + HASH->STR |= ValidNumber; +} + +/** + * @brief Writes data in the Data Input FIFO + * @param Data: new data of the message to be processed. + * @retval None + */ +void HASH_DataIn(uint32_t Data) +{ + /* Write in the DIN register a new data */ + HASH->DIN = Data; +} + +/** + * @brief Returns the number of words already pushed into the IN FIFO. + * @param None + * @retval The value of words already pushed into the IN FIFO. + */ +uint8_t HASH_GetInFIFOWordsNbr(void) +{ + /* Return the value of NBW bits */ + return ((HASH->CR & HASH_CR_NBW) >> 8); +} + +/** + * @brief Provides the message digest result. + * @note In MD5 mode, Data[4] filed of HASH_MsgDigest structure is not used + * and is read as zero. + * @param HASH_MessageDigest: pointer to a HASH_MsgDigest structure which will + * hold the message digest result + * @retval None + */ +void HASH_GetDigest(HASH_MsgDigest* HASH_MessageDigest) +{ + /* Get the data field */ + HASH_MessageDigest->Data[0] = HASH->HR[0]; + HASH_MessageDigest->Data[1] = HASH->HR[1]; + HASH_MessageDigest->Data[2] = HASH->HR[2]; + HASH_MessageDigest->Data[3] = HASH->HR[3]; + HASH_MessageDigest->Data[4] = HASH->HR[4]; +} + +/** + * @brief Starts the message padding and calculation of the final message + * @param None + * @retval None + */ +void HASH_StartDigest(void) +{ + /* Start the Digest calculation */ + HASH->STR |= HASH_STR_DCAL; +} +/** + * @} + */ + +/** @defgroup HASH_Group3 Context swapping functions + * @brief Context swapping functions + * +@verbatim + =============================================================================== + Context swapping functions + =============================================================================== + + This section provides functions allowing to save and store HASH Context + + It is possible to interrupt a HASH/HMAC process to perform another processing + with a higher priority, and to complete the interrupted process later on, when + the higher priority task is complete. To do so, the context of the interrupted + task must be saved from the HASH registers to memory, and then be restored + from memory to the HASH registers. + + 1. To save the current context, use HASH_SaveContext() function + 2. To restore the saved context, use HASH_RestoreContext() function + + +@endverbatim + * @{ + */ + +/** + * @brief Save the Hash peripheral Context. + * @note The context can be saved only when no block is currently being + * processed. So user must wait for DINIS = 1 (the last block has been + * processed and the input FIFO is empty) or NBW != 0 (the FIFO is not + * full and no processing is ongoing). + * @param HASH_ContextSave: pointer to a HASH_Context structure that contains + * the repository for current context. + * @retval None + */ +void HASH_SaveContext(HASH_Context* HASH_ContextSave) +{ + uint8_t i = 0; + + /* save context registers */ + HASH_ContextSave->HASH_IMR = HASH->IMR; + HASH_ContextSave->HASH_STR = HASH->STR; + HASH_ContextSave->HASH_CR = HASH->CR; + for(i=0; i<=50;i++) + { + HASH_ContextSave->HASH_CSR[i] = HASH->CSR[i]; + } +} + +/** + * @brief Restore the Hash peripheral Context. + * @note After calling this function, user can restart the processing from the + * point where it has been interrupted. + * @param HASH_ContextRestore: pointer to a HASH_Context structure that contains + * the repository for saved context. + * @retval None + */ +void HASH_RestoreContext(HASH_Context* HASH_ContextRestore) +{ + uint8_t i = 0; + + /* restore context registers */ + HASH->IMR = HASH_ContextRestore->HASH_IMR; + HASH->STR = HASH_ContextRestore->HASH_STR; + HASH->CR = HASH_ContextRestore->HASH_CR; + + /* Initialize the hash processor */ + HASH->CR |= HASH_CR_INIT; + + /* continue restoring context registers */ + for(i=0; i<=50;i++) + { + HASH->CSR[i] = HASH_ContextRestore->HASH_CSR[i]; + } +} +/** + * @} + */ + +/** @defgroup HASH_Group4 HASH's DMA interface Configuration function + * @brief HASH's DMA interface Configuration function + * +@verbatim + =============================================================================== + HASH's DMA interface Configuration function + =============================================================================== + + This section provides functions allowing to configure the DMA interface for + HASH/ HMAC data input transfer. + + When the DMA mode is enabled (using the HASH_DMACmd() function), data can be + sent to the IN FIFO using the DMA peripheral. + + + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the HASH DMA interface. + * @note The DMA is disabled by hardware after the end of transfer. + * @param NewState: new state of the selected HASH DMA transfer request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void HASH_DMACmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the HASH DMA request */ + HASH->CR |= HASH_CR_DMAE; + } + else + { + /* Disable the HASH DMA request */ + HASH->CR &= ~HASH_CR_DMAE; + } +} +/** + * @} + */ + +/** @defgroup HASH_Group5 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + + This section provides functions allowing to configure the HASH Interrupts and + to get the status and clear flags and Interrupts pending bits. + + The HASH provides 2 Interrupts sources and 5 Flags: + + Flags : + ---------- + 1. HASH_FLAG_DINIS : set when 16 locations are free in the Data IN FIFO + which means that a new block (512 bit) can be entered + into the input buffer. + + 2. HASH_FLAG_DCIS : set when Digest calculation is complete + + 3. HASH_FLAG_DMAS : set when HASH's DMA interface is enabled (DMAE=1) or + a transfer is ongoing. + This Flag is cleared only by hardware. + + 4. HASH_FLAG_BUSY : set when The hash core is processing a block of data + This Flag is cleared only by hardware. + + 5. HASH_FLAG_DINNE : set when Data IN FIFO is not empty which means that + the Data IN FIFO contains at least one word of data. + This Flag is cleared only by hardware. + + Interrupts : + ------------ + + 1. HASH_IT_DINI : if enabled, this interrupt source is pending when 16 + locations are free in the Data IN FIFO which means that + a new block (512 bit) can be entered into the input buffer. + This interrupt source is cleared using + HASH_ClearITPendingBit(HASH_IT_DINI) function. + + 2. HASH_IT_DCI : if enabled, this interrupt source is pending when Digest + calculation is complete. + This interrupt source is cleared using + HASH_ClearITPendingBit(HASH_IT_DCI) function. + + Managing the HASH controller events : + ------------------------------------ + The user should identify which mode will be used in his application to manage + the HASH controller events: Polling mode or Interrupt mode. + + 1. In the Polling Mode it is advised to use the following functions: + - HASH_GetFlagStatus() : to check if flags events occur. + - HASH_ClearFlag() : to clear the flags events. + + 2. In the Interrupt Mode it is advised to use the following functions: + - HASH_ITConfig() : to enable or disable the interrupt source. + - HASH_GetITStatus() : to check if Interrupt occurs. + - HASH_ClearITPendingBit() : to clear the Interrupt pending Bit + (corresponding Flag). + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified HASH interrupts. + * @param HASH_IT: specifies the HASH interrupt source to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg HASH_IT_DINI: Data Input interrupt + * @arg HASH_IT_DCI: Digest Calculation Completion Interrupt + * @param NewState: new state of the specified HASH interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void HASH_ITConfig(uint8_t HASH_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_HASH_IT(HASH_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected HASH interrupt */ + HASH->IMR |= HASH_IT; + } + else + { + /* Disable the selected HASH interrupt */ + HASH->IMR &= (uint8_t) ~HASH_IT; + } +} + +/** + * @brief Checks whether the specified HASH flag is set or not. + * @param HASH_FLAG: specifies the HASH flag to check. + * This parameter can be one of the following values: + * @arg HASH_FLAG_DINIS: Data input interrupt status flag + * @arg HASH_FLAG_DCIS: Digest calculation completion interrupt status flag + * @arg HASH_FLAG_BUSY: Busy flag + * @arg HASH_FLAG_DMAS: DMAS Status flag + * @arg HASH_FLAG_DINNE: Data Input register (DIN) not empty status flag + * @retval The new state of HASH_FLAG (SET or RESET) + */ +FlagStatus HASH_GetFlagStatus(uint16_t HASH_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tempreg = 0; + + /* Check the parameters */ + assert_param(IS_HASH_GET_FLAG(HASH_FLAG)); + + /* check if the FLAG is in CR register */ + if ((HASH_FLAG & HASH_FLAG_DINNE) != (uint16_t)RESET ) + { + tempreg = HASH->CR; + } + else /* The FLAG is in SR register */ + { + tempreg = HASH->SR; + } + + /* Check the status of the specified HASH flag */ + if ((tempreg & HASH_FLAG) != (uint16_t)RESET) + { + /* HASH is set */ + bitstatus = SET; + } + else + { + /* HASH_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the HASH_FLAG status */ + return bitstatus; +} +/** + * @brief Clears the HASH flags. + * @param HASH_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg HASH_FLAG_DINIS: Data Input Flag + * @arg HASH_FLAG_DCIS: Digest Calculation Completion Flag + * @retval None + */ +void HASH_ClearFlag(uint16_t HASH_FLAG) +{ + /* Check the parameters */ + assert_param(IS_HASH_CLEAR_FLAG(HASH_FLAG)); + + /* Clear the selected HASH flags */ + HASH->SR = ~(uint32_t)HASH_FLAG; +} +/** + * @brief Checks whether the specified HASH interrupt has occurred or not. + * @param HASH_IT: specifies the HASH interrupt source to check. + * This parameter can be one of the following values: + * @arg HASH_IT_DINI: Data Input interrupt + * @arg HASH_IT_DCI: Digest Calculation Completion Interrupt + * @retval The new state of HASH_IT (SET or RESET). + */ +ITStatus HASH_GetITStatus(uint8_t HASH_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_HASH_GET_IT(HASH_IT)); + + + /* Check the status of the specified HASH interrupt */ + tmpreg = HASH->SR; + + if (((HASH->IMR & tmpreg) & HASH_IT) != RESET) + { + /* HASH_IT is set */ + bitstatus = SET; + } + else + { + /* HASH_IT is reset */ + bitstatus = RESET; + } + /* Return the HASH_IT status */ + return bitstatus; +} + +/** + * @brief Clears the HASH interrupt pending bit(s). + * @param HASH_IT: specifies the HASH interrupt pending bit(s) to clear. + * This parameter can be any combination of the following values: + * @arg HASH_IT_DINI: Data Input interrupt + * @arg HASH_IT_DCI: Digest Calculation Completion Interrupt + * @retval None + */ +void HASH_ClearITPendingBit(uint8_t HASH_IT) +{ + /* Check the parameters */ + assert_param(IS_HASH_IT(HASH_IT)); + + /* Clear the selected HASH interrupt pending bit */ + HASH->SR = (uint8_t)~HASH_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_md5.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_md5.c new file mode 100644 index 000000000..56d495fd6 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_md5.c @@ -0,0 +1,314 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hash_md5.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides high level functions to compute the HASH MD5 and + * HMAC MD5 Digest of an input message. + * It uses the stm32f4xx_hash.c/.h drivers to access the STM32F4xx HASH + * peripheral. + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * 1. Enable The HASH controller clock using + * RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_HASH, ENABLE); function. + * + * 2. Calculate the HASH MD5 Digest using HASH_MD5() function. + * + * 3. Calculate the HMAC MD5 Digest using HMAC_MD5() function. + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hash.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup HASH + * @brief HASH driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define MD5BUSY_TIMEOUT ((uint32_t) 0x00010000) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup HASH_Private_Functions + * @{ + */ + +/** @defgroup HASH_Group7 High Level MD5 functions + * @brief High Level MD5 Hash and HMAC functions + * +@verbatim + =============================================================================== + High Level MD5 Hash and HMAC functions + =============================================================================== + + +@endverbatim + * @{ + */ + +/** + * @brief Compute the HASH MD5 digest. + * @param Input: pointer to the Input buffer to be treated. + * @param Ilen: length of the Input buffer. + * @param Output: the returned digest + * @retval An ErrorStatus enumeration value: + * - SUCCESS: digest computation done + * - ERROR: digest computation failed + */ +ErrorStatus HASH_MD5(uint8_t *Input, uint32_t Ilen, uint8_t Output[16]) +{ + HASH_InitTypeDef MD5_HASH_InitStructure; + HASH_MsgDigest MD5_MessageDigest; + __IO uint16_t nbvalidbitsdata = 0; + uint32_t i = 0; + __IO uint32_t counter = 0; + uint32_t busystatus = 0; + ErrorStatus status = SUCCESS; + uint32_t inputaddr = (uint32_t)Input; + uint32_t outputaddr = (uint32_t)Output; + + + /* Number of valid bits in last word of the Input data */ + nbvalidbitsdata = 8 * (Ilen % 4); + + /* HASH peripheral initialization */ + HASH_DeInit(); + + /* HASH Configuration */ + MD5_HASH_InitStructure.HASH_AlgoSelection = HASH_AlgoSelection_MD5; + MD5_HASH_InitStructure.HASH_AlgoMode = HASH_AlgoMode_HASH; + MD5_HASH_InitStructure.HASH_DataType = HASH_DataType_8b; + HASH_Init(&MD5_HASH_InitStructure); + + /* Configure the number of valid bits in last word of the data */ + HASH_SetLastWordValidBitsNbr(nbvalidbitsdata); + + /* Write the Input block in the IN FIFO */ + for(i=0; i 64) + { + /* HMAC long Key */ + MD5_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_LongKey; + } + else + { + /* HMAC short Key */ + MD5_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_ShortKey; + } + HASH_Init(&MD5_HASH_InitStructure); + + /* Configure the number of valid bits in last word of the Key */ + HASH_SetLastWordValidBitsNbr(nbvalidbitskey); + + /* Write the Key */ + for(i=0; i
© COPYRIGHT 2011 STMicroelectronics
+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hash.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup HASH + * @brief HASH driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define SHA1BUSY_TIMEOUT ((uint32_t) 0x00010000) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup HASH_Private_Functions + * @{ + */ + +/** @defgroup HASH_Group6 High Level SHA1 functions + * @brief High Level SHA1 Hash and HMAC functions + * +@verbatim + =============================================================================== + High Level SHA1 Hash and HMAC functions + =============================================================================== + + +@endverbatim + * @{ + */ + +/** + * @brief Compute the HASH SHA1 digest. + * @param Input: pointer to the Input buffer to be treated. + * @param Ilen: length of the Input buffer. + * @param Output: the returned digest + * @retval An ErrorStatus enumeration value: + * - SUCCESS: digest computation done + * - ERROR: digest computation failed + */ +ErrorStatus HASH_SHA1(uint8_t *Input, uint32_t Ilen, uint8_t Output[20]) +{ + HASH_InitTypeDef SHA1_HASH_InitStructure; + HASH_MsgDigest SHA1_MessageDigest; + __IO uint16_t nbvalidbitsdata = 0; + uint32_t i = 0; + __IO uint32_t counter = 0; + uint32_t busystatus = 0; + ErrorStatus status = SUCCESS; + uint32_t inputaddr = (uint32_t)Input; + uint32_t outputaddr = (uint32_t)Output; + + /* Number of valid bits in last word of the Input data */ + nbvalidbitsdata = 8 * (Ilen % 4); + + /* HASH peripheral initialization */ + HASH_DeInit(); + + /* HASH Configuration */ + SHA1_HASH_InitStructure.HASH_AlgoSelection = HASH_AlgoSelection_SHA1; + SHA1_HASH_InitStructure.HASH_AlgoMode = HASH_AlgoMode_HASH; + SHA1_HASH_InitStructure.HASH_DataType = HASH_DataType_8b; + HASH_Init(&SHA1_HASH_InitStructure); + + /* Configure the number of valid bits in last word of the data */ + HASH_SetLastWordValidBitsNbr(nbvalidbitsdata); + + /* Write the Input block in the IN FIFO */ + for(i=0; i 64) + { + /* HMAC long Key */ + SHA1_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_LongKey; + } + else + { + /* HMAC short Key */ + SHA1_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_ShortKey; + } + HASH_Init(&SHA1_HASH_InitStructure); + + /* Configure the number of valid bits in last word of the Key */ + HASH_SetLastWordValidBitsNbr(nbvalidbitskey); + + /* Write the Key */ + for(i=0; iGPIO_Mode = GPIO_Mode_AF + * - Select the type, pull-up/pull-down and output speed via + * GPIO_PuPd, GPIO_OType and GPIO_Speed members + * - Call GPIO_Init() function + * Recommended configuration is Push-Pull, Pull-up, Open-Drain. + * Add an external pull up if necessary (typically 4.7 KOhm). + * + * 4. Program the Mode, duty cycle , Own address, Ack, Speed and Acknowledged + * Address using the I2C_Init() function. + * + * 5. Optionally you can enable/configure the following parameters without + * re-initialization (i.e there is no need to call again I2C_Init() function): + * - Enable the acknowledge feature using I2C_AcknowledgeConfig() function + * - Enable the dual addressing mode using I2C_DualAddressCmd() function + * - Enable the general call using the I2C_GeneralCallCmd() function + * - Enable the clock stretching using I2C_StretchClockCmd() function + * - Enable the fast mode duty cycle using the I2C_FastModeDutyCycleConfig() + * function. + * - Configure the NACK position for Master Receiver mode in case of + * 2 bytes reception using the function I2C_NACKPositionConfig(). + * - Enable the PEC Calculation using I2C_CalculatePEC() function + * - For SMBus Mode: + * - Enable the Address Resolution Protocol (ARP) using I2C_ARPCmd() function + * - Configure the SMBusAlert pin using I2C_SMBusAlertConfig() function + * + * 6. Enable the NVIC and the corresponding interrupt using the function + * I2C_ITConfig() if you need to use interrupt mode. + * + * 7. When using the DMA mode + * - Configure the DMA using DMA_Init() function + * - Active the needed channel Request using I2C_DMACmd() or + * I2C_DMALastTransferCmd() function. + * @note When using DMA mode, I2C interrupts may be used at the same time to + * control the communication flow (Start/Stop/Ack... events and errors). + * + * 8. Enable the I2C using the I2C_Cmd() function. + * + * 9. Enable the DMA using the DMA_Cmd() function when using DMA mode in the + * transfers. + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_i2c.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup I2C + * @brief I2C driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +#define CR1_CLEAR_MASK ((uint16_t)0xFBF5) /*I2C_ClockSpeed)); + assert_param(IS_I2C_MODE(I2C_InitStruct->I2C_Mode)); + assert_param(IS_I2C_DUTY_CYCLE(I2C_InitStruct->I2C_DutyCycle)); + assert_param(IS_I2C_OWN_ADDRESS1(I2C_InitStruct->I2C_OwnAddress1)); + assert_param(IS_I2C_ACK_STATE(I2C_InitStruct->I2C_Ack)); + assert_param(IS_I2C_ACKNOWLEDGE_ADDRESS(I2C_InitStruct->I2C_AcknowledgedAddress)); + +/*---------------------------- I2Cx CR2 Configuration ------------------------*/ + /* Get the I2Cx CR2 value */ + tmpreg = I2Cx->CR2; + /* Clear frequency FREQ[5:0] bits */ + tmpreg &= (uint16_t)~((uint16_t)I2C_CR2_FREQ); + /* Get pclk1 frequency value */ + RCC_GetClocksFreq(&rcc_clocks); + pclk1 = rcc_clocks.PCLK1_Frequency; + /* Set frequency bits depending on pclk1 value */ + freqrange = (uint16_t)(pclk1 / 1000000); + tmpreg |= freqrange; + /* Write to I2Cx CR2 */ + I2Cx->CR2 = tmpreg; + +/*---------------------------- I2Cx CCR Configuration ------------------------*/ + /* Disable the selected I2C peripheral to configure TRISE */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_PE); + /* Reset tmpreg value */ + /* Clear F/S, DUTY and CCR[11:0] bits */ + tmpreg = 0; + + /* Configure speed in standard mode */ + if (I2C_InitStruct->I2C_ClockSpeed <= 100000) + { + /* Standard mode speed calculate */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed << 1)); + /* Test if CCR value is under 0x4*/ + if (result < 0x04) + { + /* Set minimum allowed value */ + result = 0x04; + } + /* Set speed value for standard mode */ + tmpreg |= result; + /* Set Maximum Rise Time for standard mode */ + I2Cx->TRISE = freqrange + 1; + } + /* Configure speed in fast mode */ + /* To use the I2C at 400 KHz (in fast mode), the PCLK1 frequency (I2C peripheral + input clock) must be a multiple of 10 MHz */ + else /*(I2C_InitStruct->I2C_ClockSpeed <= 400000)*/ + { + if (I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_2) + { + /* Fast mode speed calculate: Tlow/Thigh = 2 */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 3)); + } + else /*I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_16_9*/ + { + /* Fast mode speed calculate: Tlow/Thigh = 16/9 */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 25)); + /* Set DUTY bit */ + result |= I2C_DutyCycle_16_9; + } + + /* Test if CCR value is under 0x1*/ + if ((result & I2C_CCR_CCR) == 0) + { + /* Set minimum allowed value */ + result |= (uint16_t)0x0001; + } + /* Set speed value and set F/S bit for fast mode */ + tmpreg |= (uint16_t)(result | I2C_CCR_FS); + /* Set Maximum Rise Time for fast mode */ + I2Cx->TRISE = (uint16_t)(((freqrange * (uint16_t)300) / (uint16_t)1000) + (uint16_t)1); + } + + /* Write to I2Cx CCR */ + I2Cx->CCR = tmpreg; + /* Enable the selected I2C peripheral */ + I2Cx->CR1 |= I2C_CR1_PE; + +/*---------------------------- I2Cx CR1 Configuration ------------------------*/ + /* Get the I2Cx CR1 value */ + tmpreg = I2Cx->CR1; + /* Clear ACK, SMBTYPE and SMBUS bits */ + tmpreg &= CR1_CLEAR_MASK; + /* Configure I2Cx: mode and acknowledgement */ + /* Set SMBTYPE and SMBUS bits according to I2C_Mode value */ + /* Set ACK bit according to I2C_Ack value */ + tmpreg |= (uint16_t)((uint32_t)I2C_InitStruct->I2C_Mode | I2C_InitStruct->I2C_Ack); + /* Write to I2Cx CR1 */ + I2Cx->CR1 = tmpreg; + +/*---------------------------- I2Cx OAR1 Configuration -----------------------*/ + /* Set I2Cx Own Address1 and acknowledged address */ + I2Cx->OAR1 = (I2C_InitStruct->I2C_AcknowledgedAddress | I2C_InitStruct->I2C_OwnAddress1); +} + +/** + * @brief Fills each I2C_InitStruct member with its default value. + * @param I2C_InitStruct: pointer to an I2C_InitTypeDef structure which will be initialized. + * @retval None + */ +void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct) +{ +/*---------------- Reset I2C init structure parameters values ----------------*/ + /* initialize the I2C_ClockSpeed member */ + I2C_InitStruct->I2C_ClockSpeed = 5000; + /* Initialize the I2C_Mode member */ + I2C_InitStruct->I2C_Mode = I2C_Mode_I2C; + /* Initialize the I2C_DutyCycle member */ + I2C_InitStruct->I2C_DutyCycle = I2C_DutyCycle_2; + /* Initialize the I2C_OwnAddress1 member */ + I2C_InitStruct->I2C_OwnAddress1 = 0; + /* Initialize the I2C_Ack member */ + I2C_InitStruct->I2C_Ack = I2C_Ack_Disable; + /* Initialize the I2C_AcknowledgedAddress member */ + I2C_InitStruct->I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; +} + +/** + * @brief Enables or disables the specified I2C peripheral. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2Cx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C peripheral */ + I2Cx->CR1 |= I2C_CR1_PE; + } + else + { + /* Disable the selected I2C peripheral */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_PE); + } +} + +/** + * @brief Generates I2Cx communication START condition. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2C START condition generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Generate a START condition */ + I2Cx->CR1 |= I2C_CR1_START; + } + else + { + /* Disable the START condition generation */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_START); + } +} + +/** + * @brief Generates I2Cx communication STOP condition. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2C STOP condition generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Generate a STOP condition */ + I2Cx->CR1 |= I2C_CR1_STOP; + } + else + { + /* Disable the STOP condition generation */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_STOP); + } +} + +/** + * @brief Transmits the address byte to select the slave device. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param Address: specifies the slave address which will be transmitted + * @param I2C_Direction: specifies whether the I2C device will be a Transmitter + * or a Receiver. + * This parameter can be one of the following values + * @arg I2C_Direction_Transmitter: Transmitter mode + * @arg I2C_Direction_Receiver: Receiver mode + * @retval None. + */ +void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_DIRECTION(I2C_Direction)); + /* Test on the direction to set/reset the read/write bit */ + if (I2C_Direction != I2C_Direction_Transmitter) + { + /* Set the address bit0 for read */ + Address |= I2C_OAR1_ADD0; + } + else + { + /* Reset the address bit0 for write */ + Address &= (uint8_t)~((uint8_t)I2C_OAR1_ADD0); + } + /* Send the address */ + I2Cx->DR = Address; +} + +/** + * @brief Enables or disables the specified I2C acknowledge feature. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2C Acknowledgement. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the acknowledgement */ + I2Cx->CR1 |= I2C_CR1_ACK; + } + else + { + /* Disable the acknowledgement */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_ACK); + } +} + +/** + * @brief Configures the specified I2C own address2. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param Address: specifies the 7bit I2C own address2. + * @retval None. + */ +void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Get the old register value */ + tmpreg = I2Cx->OAR2; + + /* Reset I2Cx Own address2 bit [7:1] */ + tmpreg &= (uint16_t)~((uint16_t)I2C_OAR2_ADD2); + + /* Set I2Cx Own address2 */ + tmpreg |= (uint16_t)((uint16_t)Address & (uint16_t)0x00FE); + + /* Store the new register value */ + I2Cx->OAR2 = tmpreg; +} + +/** + * @brief Enables or disables the specified I2C dual addressing mode. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2C dual addressing mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable dual addressing mode */ + I2Cx->OAR2 |= I2C_OAR2_ENDUAL; + } + else + { + /* Disable dual addressing mode */ + I2Cx->OAR2 &= (uint16_t)~((uint16_t)I2C_OAR2_ENDUAL); + } +} + +/** + * @brief Enables or disables the specified I2C general call feature. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2C General call. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable generall call */ + I2Cx->CR1 |= I2C_CR1_ENGC; + } + else + { + /* Disable generall call */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_ENGC); + } +} + +/** + * @brief Enables or disables the specified I2C software reset. + * @note When software reset is enabled, the I2C IOs are released (this can + * be useful to recover from bus errors). + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2C software reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Peripheral under reset */ + I2Cx->CR1 |= I2C_CR1_SWRST; + } + else + { + /* Peripheral not under reset */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_SWRST); + } +} + +/** + * @brief Enables or disables the specified I2C Clock stretching. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2Cx Clock stretching. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState == DISABLE) + { + /* Enable the selected I2C Clock stretching */ + I2Cx->CR1 |= I2C_CR1_NOSTRETCH; + } + else + { + /* Disable the selected I2C Clock stretching */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_NOSTRETCH); + } +} + +/** + * @brief Selects the specified I2C fast mode duty cycle. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param I2C_DutyCycle: specifies the fast mode duty cycle. + * This parameter can be one of the following values: + * @arg I2C_DutyCycle_2: I2C fast mode Tlow/Thigh = 2 + * @arg I2C_DutyCycle_16_9: I2C fast mode Tlow/Thigh = 16/9 + * @retval None + */ +void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_DUTY_CYCLE(I2C_DutyCycle)); + if (I2C_DutyCycle != I2C_DutyCycle_16_9) + { + /* I2C fast mode Tlow/Thigh=2 */ + I2Cx->CCR &= I2C_DutyCycle_2; + } + else + { + /* I2C fast mode Tlow/Thigh=16/9 */ + I2Cx->CCR |= I2C_DutyCycle_16_9; + } +} + +/** + * @brief Selects the specified I2C NACK position in master receiver mode. + * @note This function is useful in I2C Master Receiver mode when the number + * of data to be received is equal to 2. In this case, this function + * should be called (with parameter I2C_NACKPosition_Next) before data + * reception starts,as described in the 2-byte reception procedure + * recommended in Reference Manual in Section: Master receiver. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param I2C_NACKPosition: specifies the NACK position. + * This parameter can be one of the following values: + * @arg I2C_NACKPosition_Next: indicates that the next byte will be the last + * received byte. + * @arg I2C_NACKPosition_Current: indicates that current byte is the last + * received byte. + * + * @note This function configures the same bit (POS) as I2C_PECPositionConfig() + * but is intended to be used in I2C mode while I2C_PECPositionConfig() + * is intended to used in SMBUS mode. + * + * @retval None + */ +void I2C_NACKPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_NACKPosition) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_NACK_POSITION(I2C_NACKPosition)); + + /* Check the input parameter */ + if (I2C_NACKPosition == I2C_NACKPosition_Next) + { + /* Next byte in shift register is the last received byte */ + I2Cx->CR1 |= I2C_NACKPosition_Next; + } + else + { + /* Current byte in shift register is the last received byte */ + I2Cx->CR1 &= I2C_NACKPosition_Current; + } +} + +/** + * @brief Drives the SMBusAlert pin high or low for the specified I2C. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param I2C_SMBusAlert: specifies SMBAlert pin level. + * This parameter can be one of the following values: + * @arg I2C_SMBusAlert_Low: SMBAlert pin driven low + * @arg I2C_SMBusAlert_High: SMBAlert pin driven high + * @retval None + */ +void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_SMBUS_ALERT(I2C_SMBusAlert)); + if (I2C_SMBusAlert == I2C_SMBusAlert_Low) + { + /* Drive the SMBusAlert pin Low */ + I2Cx->CR1 |= I2C_SMBusAlert_Low; + } + else + { + /* Drive the SMBusAlert pin High */ + I2Cx->CR1 &= I2C_SMBusAlert_High; + } +} + +/** + * @brief Enables or disables the specified I2C ARP. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2Cx ARP. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C ARP */ + I2Cx->CR1 |= I2C_CR1_ENARP; + } + else + { + /* Disable the selected I2C ARP */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_ENARP); + } +} +/** + * @} + */ + +/** @defgroup I2C_Group2 Data transfers functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + Data transfers functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Sends a data byte through the I2Cx peripheral. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param Data: Byte to be transmitted.. + * @retval None + */ +void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Write in the DR register the data to be sent */ + I2Cx->DR = Data; +} + +/** + * @brief Returns the most recent received data by the I2Cx peripheral. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @retval The value of the received data. + */ +uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Return the data in the DR register */ + return (uint8_t)I2Cx->DR; +} + +/** + * @} + */ + +/** @defgroup I2C_Group3 PEC management functions + * @brief PEC management functions + * +@verbatim + =============================================================================== + PEC management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified I2C PEC transfer. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2C PEC transmission. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C PEC transmission */ + I2Cx->CR1 |= I2C_CR1_PEC; + } + else + { + /* Disable the selected I2C PEC transmission */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_PEC); + } +} + +/** + * @brief Selects the specified I2C PEC position. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param I2C_PECPosition: specifies the PEC position. + * This parameter can be one of the following values: + * @arg I2C_PECPosition_Next: indicates that the next byte is PEC + * @arg I2C_PECPosition_Current: indicates that current byte is PEC + * + * @note This function configures the same bit (POS) as I2C_NACKPositionConfig() + * but is intended to be used in SMBUS mode while I2C_NACKPositionConfig() + * is intended to used in I2C mode. + * + * @retval None + */ +void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_PEC_POSITION(I2C_PECPosition)); + if (I2C_PECPosition == I2C_PECPosition_Next) + { + /* Next byte in shift register is PEC */ + I2Cx->CR1 |= I2C_PECPosition_Next; + } + else + { + /* Current byte in shift register is PEC */ + I2Cx->CR1 &= I2C_PECPosition_Current; + } +} + +/** + * @brief Enables or disables the PEC value calculation of the transferred bytes. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2Cx PEC value calculation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C PEC calculation */ + I2Cx->CR1 |= I2C_CR1_ENPEC; + } + else + { + /* Disable the selected I2C PEC calculation */ + I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_ENPEC); + } +} + +/** + * @brief Returns the PEC value for the specified I2C. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @retval The PEC value. + */ +uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Return the selected I2C PEC value */ + return ((I2Cx->SR2) >> 8); +} + +/** + * @} + */ + +/** @defgroup I2C_Group4 DMA transfers management functions + * @brief DMA transfers management functions + * +@verbatim + =============================================================================== + DMA transfers management functions + =============================================================================== + This section provides functions allowing to configure the I2C DMA channels + requests. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified I2C DMA requests. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2C DMA transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C DMA requests */ + I2Cx->CR2 |= I2C_CR2_DMAEN; + } + else + { + /* Disable the selected I2C DMA requests */ + I2Cx->CR2 &= (uint16_t)~((uint16_t)I2C_CR2_DMAEN); + } +} + +/** + * @brief Specifies that the next DMA transfer is the last one. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param NewState: new state of the I2C DMA last transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Next DMA transfer is the last transfer */ + I2Cx->CR2 |= I2C_CR2_LAST; + } + else + { + /* Next DMA transfer is not the last transfer */ + I2Cx->CR2 &= (uint16_t)~((uint16_t)I2C_CR2_LAST); + } +} + +/** + * @} + */ + +/** @defgroup I2C_Group5 Interrupts events and flags management functions + * @brief Interrupts, events and flags management functions + * +@verbatim + =============================================================================== + Interrupts, events and flags management functions + =============================================================================== + This section provides functions allowing to configure the I2C Interrupts + sources and check or clear the flags or pending bits status. + The user should identify which mode will be used in his application to manage + the communication: Polling mode, Interrupt mode or DMA mode. + + =============================================================================== + I2C State Monitoring Functions + =============================================================================== + This I2C driver provides three different ways for I2C state monitoring + depending on the application requirements and constraints: + + + 1. Basic state monitoring (Using I2C_CheckEvent() function) + ----------------------------------------------------------- + It compares the status registers (SR1 and SR2) content to a given event + (can be the combination of one or more flags). + It returns SUCCESS if the current status includes the given flags + and returns ERROR if one or more flags are missing in the current status. + + - When to use + - This function is suitable for most applications as well as for startup + activity since the events are fully described in the product reference + manual (RM0090). + - It is also suitable for users who need to define their own events. + + - Limitations + - If an error occurs (ie. error flags are set besides to the monitored + flags), the I2C_CheckEvent() function may return SUCCESS despite + the communication hold or corrupted real state. + In this case, it is advised to use error interrupts to monitor + the error events and handle them in the interrupt IRQ handler. + + @note + For error management, it is advised to use the following functions: + - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR). + - I2Cx_ER_IRQHandler() which is called when the error interrupt occurs. + Where x is the peripheral instance (I2C1, I2C2 ...) + - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into the + I2Cx_ER_IRQHandler() function in order to determine which error occurred. + - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() + and/or I2C_GenerateStop() in order to clear the error flag and source + and return to correct communication status. + + + 2. Advanced state monitoring (Using the function I2C_GetLastEvent()) + -------------------------------------------------------------------- + Using the function I2C_GetLastEvent() which returns the image of both status + registers in a single word (uint32_t) (Status Register 2 value is shifted left + by 16 bits and concatenated to Status Register 1). + + - When to use + - This function is suitable for the same applications above but it + allows to overcome the mentioned limitation of I2C_GetFlagStatus() + function. + - The returned value could be compared to events already defined in + the library (stm32f4xx_i2c.h) or to custom values defined by user. + This function is suitable when multiple flags are monitored at the + same time. + - At the opposite of I2C_CheckEvent() function, this function allows + user to choose when an event is accepted (when all events flags are + set and no other flags are set or just when the needed flags are set + like I2C_CheckEvent() function. + + - Limitations + - User may need to define his own events. + - Same remark concerning the error management is applicable for this + function if user decides to check only regular communication flags + (and ignores error flags). + + + 3. Flag-based state monitoring (Using the function I2C_GetFlagStatus()) + ----------------------------------------------------------------------- + + Using the function I2C_GetFlagStatus() which simply returns the status of + one single flag (ie. I2C_FLAG_RXNE ...). + + - When to use + - This function could be used for specific applications or in debug + phase. + - It is suitable when only one flag checking is needed (most I2C + events are monitored through multiple flags). + - Limitations: + - When calling this function, the Status register is accessed. + Some flags are cleared when the status register is accessed. + So checking the status of one Flag, may clear other ones. + - Function may need to be called twice or more in order to monitor + one single event. + + For detailed description of Events, please refer to section I2C_Events in + stm32f4xx_i2c.h file. + +@endverbatim + * @{ + */ + +/** + * @brief Reads the specified I2C register and returns its value. + * @param I2C_Register: specifies the register to read. + * This parameter can be one of the following values: + * @arg I2C_Register_CR1: CR1 register. + * @arg I2C_Register_CR2: CR2 register. + * @arg I2C_Register_OAR1: OAR1 register. + * @arg I2C_Register_OAR2: OAR2 register. + * @arg I2C_Register_DR: DR register. + * @arg I2C_Register_SR1: SR1 register. + * @arg I2C_Register_SR2: SR2 register. + * @arg I2C_Register_CCR: CCR register. + * @arg I2C_Register_TRISE: TRISE register. + * @retval The value of the read register. + */ +uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_REGISTER(I2C_Register)); + + tmp = (uint32_t) I2Cx; + tmp += I2C_Register; + + /* Return the selected register value */ + return (*(__IO uint16_t *) tmp); +} + +/** + * @brief Enables or disables the specified I2C interrupts. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param I2C_IT: specifies the I2C interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg I2C_IT_BUF: Buffer interrupt mask + * @arg I2C_IT_EVT: Event interrupt mask + * @arg I2C_IT_ERR: Error interrupt mask + * @param NewState: new state of the specified I2C interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_I2C_CONFIG_IT(I2C_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected I2C interrupts */ + I2Cx->CR2 |= I2C_IT; + } + else + { + /* Disable the selected I2C interrupts */ + I2Cx->CR2 &= (uint16_t)~I2C_IT; + } +} + +/* + =============================================================================== + 1. Basic state monitoring + =============================================================================== + */ + +/** + * @brief Checks whether the last I2Cx Event is equal to the one passed + * as parameter. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param I2C_EVENT: specifies the event to be checked. + * This parameter can be one of the following values: + * @arg I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED: EV1 + * @arg I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED: EV1 + * @arg I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED: EV1 + * @arg I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED: EV1 + * @arg I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED: EV1 + * @arg I2C_EVENT_SLAVE_BYTE_RECEIVED: EV2 + * @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF): EV2 + * @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL): EV2 + * @arg I2C_EVENT_SLAVE_BYTE_TRANSMITTED: EV3 + * @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF): EV3 + * @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL): EV3 + * @arg I2C_EVENT_SLAVE_ACK_FAILURE: EV3_2 + * @arg I2C_EVENT_SLAVE_STOP_DETECTED: EV4 + * @arg I2C_EVENT_MASTER_MODE_SELECT: EV5 + * @arg I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED: EV6 + * @arg I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED: EV6 + * @arg I2C_EVENT_MASTER_BYTE_RECEIVED: EV7 + * @arg I2C_EVENT_MASTER_BYTE_TRANSMITTING: EV8 + * @arg I2C_EVENT_MASTER_BYTE_TRANSMITTED: EV8_2 + * @arg I2C_EVENT_MASTER_MODE_ADDRESS10: EV9 + * + * @note For detailed description of Events, please refer to section I2C_Events + * in stm32f4xx_i2c.h file. + * + * @retval An ErrorStatus enumeration value: + * - SUCCESS: Last event is equal to the I2C_EVENT + * - ERROR: Last event is different from the I2C_EVENT + */ +ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT) +{ + uint32_t lastevent = 0; + uint32_t flag1 = 0, flag2 = 0; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_EVENT(I2C_EVENT)); + + /* Read the I2Cx status register */ + flag1 = I2Cx->SR1; + flag2 = I2Cx->SR2; + flag2 = flag2 << 16; + + /* Get the last event value from I2C status register */ + lastevent = (flag1 | flag2) & FLAG_MASK; + + /* Check whether the last event contains the I2C_EVENT */ + if ((lastevent & I2C_EVENT) == I2C_EVENT) + { + /* SUCCESS: last event is equal to I2C_EVENT */ + status = SUCCESS; + } + else + { + /* ERROR: last event is different from I2C_EVENT */ + status = ERROR; + } + /* Return status */ + return status; +} + +/* + =============================================================================== + 2. Advanced state monitoring + =============================================================================== + */ + +/** + * @brief Returns the last I2Cx Event. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * + * @note For detailed description of Events, please refer to section I2C_Events + * in stm32f4xx_i2c.h file. + * + * @retval The last event + */ +uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx) +{ + uint32_t lastevent = 0; + uint32_t flag1 = 0, flag2 = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Read the I2Cx status register */ + flag1 = I2Cx->SR1; + flag2 = I2Cx->SR2; + flag2 = flag2 << 16; + + /* Get the last event value from I2C status register */ + lastevent = (flag1 | flag2) & FLAG_MASK; + + /* Return status */ + return lastevent; +} + +/* + =============================================================================== + 3. Flag-based state monitoring + =============================================================================== + */ + +/** + * @brief Checks whether the specified I2C flag is set or not. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param I2C_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg I2C_FLAG_DUALF: Dual flag (Slave mode) + * @arg I2C_FLAG_SMBHOST: SMBus host header (Slave mode) + * @arg I2C_FLAG_SMBDEFAULT: SMBus default header (Slave mode) + * @arg I2C_FLAG_GENCALL: General call header flag (Slave mode) + * @arg I2C_FLAG_TRA: Transmitter/Receiver flag + * @arg I2C_FLAG_BUSY: Bus busy flag + * @arg I2C_FLAG_MSL: Master/Slave flag + * @arg I2C_FLAG_SMBALERT: SMBus Alert flag + * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_FLAG_PECERR: PEC error in reception flag + * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_FLAG_AF: Acknowledge failure flag + * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_FLAG_BERR: Bus error flag + * @arg I2C_FLAG_TXE: Data register empty flag (Transmitter) + * @arg I2C_FLAG_RXNE: Data register not empty (Receiver) flag + * @arg I2C_FLAG_STOPF: Stop detection flag (Slave mode) + * @arg I2C_FLAG_ADD10: 10-bit header sent flag (Master mode) + * @arg I2C_FLAG_BTF: Byte transfer finished flag + * @arg I2C_FLAG_ADDR: Address sent flag (Master mode) "ADSL" + * Address matched flag (Slave mode)"ENDAD" + * @arg I2C_FLAG_SB: Start bit flag (Master mode) + * @retval The new state of I2C_FLAG (SET or RESET). + */ +FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) +{ + FlagStatus bitstatus = RESET; + __IO uint32_t i2creg = 0, i2cxbase = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_GET_FLAG(I2C_FLAG)); + + /* Get the I2Cx peripheral base address */ + i2cxbase = (uint32_t)I2Cx; + + /* Read flag register index */ + i2creg = I2C_FLAG >> 28; + + /* Get bit[23:0] of the flag */ + I2C_FLAG &= FLAG_MASK; + + if(i2creg != 0) + { + /* Get the I2Cx SR1 register address */ + i2cxbase += 0x14; + } + else + { + /* Flag in I2Cx SR2 Register */ + I2C_FLAG = (uint32_t)(I2C_FLAG >> 16); + /* Get the I2Cx SR2 register address */ + i2cxbase += 0x18; + } + + if(((*(__IO uint32_t *)i2cxbase) & I2C_FLAG) != (uint32_t)RESET) + { + /* I2C_FLAG is set */ + bitstatus = SET; + } + else + { + /* I2C_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the I2C_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the I2Cx's pending flags. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param I2C_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg I2C_FLAG_SMBALERT: SMBus Alert flag + * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_FLAG_PECERR: PEC error in reception flag + * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_FLAG_AF: Acknowledge failure flag + * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_FLAG_BERR: Bus error flag + * + * @note STOPF (STOP detection) is cleared by software sequence: a read operation + * to I2C_SR1 register (I2C_GetFlagStatus()) followed by a write operation + * to I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral). + * @note ADD10 (10-bit header sent) is cleared by software sequence: a read + * operation to I2C_SR1 (I2C_GetFlagStatus()) followed by writing the + * second byte of the address in DR register. + * @note BTF (Byte Transfer Finished) is cleared by software sequence: a read + * operation to I2C_SR1 register (I2C_GetFlagStatus()) followed by a + * read/write to I2C_DR register (I2C_SendData()). + * @note ADDR (Address sent) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetFlagStatus()) followed by a read operation to + * I2C_SR2 register ((void)(I2Cx->SR2)). + * @note SB (Start Bit) is cleared software sequence: a read operation to I2C_SR1 + * register (I2C_GetFlagStatus()) followed by a write operation to I2C_DR + * register (I2C_SendData()). + * + * @retval None + */ +void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) +{ + uint32_t flagpos = 0; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG)); + /* Get the I2C flag position */ + flagpos = I2C_FLAG & FLAG_MASK; + /* Clear the selected I2C flag */ + I2Cx->SR1 = (uint16_t)~flagpos; +} + +/** + * @brief Checks whether the specified I2C interrupt has occurred or not. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param I2C_IT: specifies the interrupt source to check. + * This parameter can be one of the following values: + * @arg I2C_IT_SMBALERT: SMBus Alert flag + * @arg I2C_IT_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_IT_PECERR: PEC error in reception flag + * @arg I2C_IT_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_IT_AF: Acknowledge failure flag + * @arg I2C_IT_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_IT_BERR: Bus error flag + * @arg I2C_IT_TXE: Data register empty flag (Transmitter) + * @arg I2C_IT_RXNE: Data register not empty (Receiver) flag + * @arg I2C_IT_STOPF: Stop detection flag (Slave mode) + * @arg I2C_IT_ADD10: 10-bit header sent flag (Master mode) + * @arg I2C_IT_BTF: Byte transfer finished flag + * @arg I2C_IT_ADDR: Address sent flag (Master mode) "ADSL" + * Address matched flag (Slave mode)"ENDAD" + * @arg I2C_IT_SB: Start bit flag (Master mode) + * @retval The new state of I2C_IT (SET or RESET). + */ +ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_GET_IT(I2C_IT)); + + /* Check if the interrupt source is enabled or not */ + enablestatus = (uint32_t)(((I2C_IT & ITEN_MASK) >> 16) & (I2Cx->CR2)) ; + + /* Get bit[23:0] of the flag */ + I2C_IT &= FLAG_MASK; + + /* Check the status of the specified I2C flag */ + if (((I2Cx->SR1 & I2C_IT) != (uint32_t)RESET) && enablestatus) + { + /* I2C_IT is set */ + bitstatus = SET; + } + else + { + /* I2C_IT is reset */ + bitstatus = RESET; + } + /* Return the I2C_IT status */ + return bitstatus; +} + +/** + * @brief Clears the I2Cx's interrupt pending bits. + * @param I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral. + * @param I2C_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg I2C_IT_SMBALERT: SMBus Alert interrupt + * @arg I2C_IT_TIMEOUT: Timeout or Tlow error interrupt + * @arg I2C_IT_PECERR: PEC error in reception interrupt + * @arg I2C_IT_OVR: Overrun/Underrun interrupt (Slave mode) + * @arg I2C_IT_AF: Acknowledge failure interrupt + * @arg I2C_IT_ARLO: Arbitration lost interrupt (Master mode) + * @arg I2C_IT_BERR: Bus error interrupt + * + * @note STOPF (STOP detection) is cleared by software sequence: a read operation + * to I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to + * I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral). + * @note ADD10 (10-bit header sent) is cleared by software sequence: a read + * operation to I2C_SR1 (I2C_GetITStatus()) followed by writing the second + * byte of the address in I2C_DR register. + * @note BTF (Byte Transfer Finished) is cleared by software sequence: a read + * operation to I2C_SR1 register (I2C_GetITStatus()) followed by a + * read/write to I2C_DR register (I2C_SendData()). + * @note ADDR (Address sent) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetITStatus()) followed by a read operation to + * I2C_SR2 register ((void)(I2Cx->SR2)). + * @note SB (Start Bit) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to + * I2C_DR register (I2C_SendData()). + * @retval None + */ +void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT) +{ + uint32_t flagpos = 0; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLEAR_IT(I2C_IT)); + + /* Get the I2C flag position */ + flagpos = I2C_IT & FLAG_MASK; + + /* Clear the selected I2C flag */ + I2Cx->SR1 = (uint16_t)~flagpos; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_iwdg.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_iwdg.c new file mode 100644 index 000000000..a4fddec2a --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_iwdg.c @@ -0,0 +1,263 @@ +/** + ****************************************************************************** + * @file stm32f4xx_iwdg.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Independent watchdog (IWDG) peripheral: + * - Prescaler and Counter configuration + * - IWDG activation + * - Flag management + * + * @verbatim + * + * =================================================================== + * IWDG features + * =================================================================== + * + * The IWDG can be started by either software or hardware (configurable + * through option byte). + * + * The IWDG is clocked by its own dedicated low-speed clock (LSI) and + * thus stays active even if the main clock fails. + * Once the IWDG is started, the LSI is forced ON and cannot be disabled + * (LSI cannot be disabled too), and the counter starts counting down from + * the reset value of 0xFFF. When it reaches the end of count value (0x000) + * a system reset is generated. + * The IWDG counter should be reloaded at regular intervals to prevent + * an MCU reset. + * + * The IWDG is implemented in the VDD voltage domain that is still functional + * in STOP and STANDBY mode (IWDG reset can wake-up from STANDBY). + * + * IWDGRST flag in RCC_CSR register can be used to inform when a IWDG + * reset occurs. + * + * Min-max timeout value @32KHz (LSI): ~125us / ~32.7s + * The IWDG timeout may vary due to LSI frequency dispersion. STM32F4xx + * devices provide the capability to measure the LSI frequency (LSI clock + * connected internally to TIM5 CH4 input capture). The measured value + * can be used to have an IWDG timeout with an acceptable accuracy. + * For more information, please refer to the STM32F4xx Reference manual + * + * + * =================================================================== + * How to use this driver + * =================================================================== + * 1. Enable write access to IWDG_PR and IWDG_RLR registers using + * IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable) function + * + * 2. Configure the IWDG prescaler using IWDG_SetPrescaler() function + * + * 3. Configure the IWDG counter value using IWDG_SetReload() function. + * This value will be loaded in the IWDG counter each time the counter + * is reloaded, then the IWDG will start counting down from this value. + * + * 4. Start the IWDG using IWDG_Enable() function, when the IWDG is used + * in software mode (no need to enable the LSI, it will be enabled + * by hardware) + * + * 5. Then the application program must reload the IWDG counter at regular + * intervals during normal operation to prevent an MCU reset, using + * IWDG_ReloadCounter() function. + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_iwdg.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup IWDG + * @brief IWDG driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* KR register bit mask */ +#define KR_KEY_RELOAD ((uint16_t)0xAAAA) +#define KR_KEY_ENABLE ((uint16_t)0xCCCC) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup IWDG_Private_Functions + * @{ + */ + +/** @defgroup IWDG_Group1 Prescaler and Counter configuration functions + * @brief Prescaler and Counter configuration functions + * +@verbatim + =============================================================================== + Prescaler and Counter configuration functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables write access to IWDG_PR and IWDG_RLR registers. + * @param IWDG_WriteAccess: new state of write access to IWDG_PR and IWDG_RLR registers. + * This parameter can be one of the following values: + * @arg IWDG_WriteAccess_Enable: Enable write access to IWDG_PR and IWDG_RLR registers + * @arg IWDG_WriteAccess_Disable: Disable write access to IWDG_PR and IWDG_RLR registers + * @retval None + */ +void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess) +{ + /* Check the parameters */ + assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess)); + IWDG->KR = IWDG_WriteAccess; +} + +/** + * @brief Sets IWDG Prescaler value. + * @param IWDG_Prescaler: specifies the IWDG Prescaler value. + * This parameter can be one of the following values: + * @arg IWDG_Prescaler_4: IWDG prescaler set to 4 + * @arg IWDG_Prescaler_8: IWDG prescaler set to 8 + * @arg IWDG_Prescaler_16: IWDG prescaler set to 16 + * @arg IWDG_Prescaler_32: IWDG prescaler set to 32 + * @arg IWDG_Prescaler_64: IWDG prescaler set to 64 + * @arg IWDG_Prescaler_128: IWDG prescaler set to 128 + * @arg IWDG_Prescaler_256: IWDG prescaler set to 256 + * @retval None + */ +void IWDG_SetPrescaler(uint8_t IWDG_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler)); + IWDG->PR = IWDG_Prescaler; +} + +/** + * @brief Sets IWDG Reload value. + * @param Reload: specifies the IWDG Reload value. + * This parameter must be a number between 0 and 0x0FFF. + * @retval None + */ +void IWDG_SetReload(uint16_t Reload) +{ + /* Check the parameters */ + assert_param(IS_IWDG_RELOAD(Reload)); + IWDG->RLR = Reload; +} + +/** + * @brief Reloads IWDG counter with value defined in the reload register + * (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param None + * @retval None + */ +void IWDG_ReloadCounter(void) +{ + IWDG->KR = KR_KEY_RELOAD; +} + +/** + * @} + */ + +/** @defgroup IWDG_Group2 IWDG activation function + * @brief IWDG activation function + * +@verbatim + =============================================================================== + IWDG activation function + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables IWDG (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param None + * @retval None + */ +void IWDG_Enable(void) +{ + IWDG->KR = KR_KEY_ENABLE; +} + +/** + * @} + */ + +/** @defgroup IWDG_Group3 Flag management function + * @brief Flag management function + * +@verbatim + =============================================================================== + Flag management function + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Checks whether the specified IWDG flag is set or not. + * @param IWDG_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg IWDG_FLAG_PVU: Prescaler Value Update on going + * @arg IWDG_FLAG_RVU: Reload Value Update on going + * @retval The new state of IWDG_FLAG (SET or RESET). + */ +FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_IWDG_FLAG(IWDG_FLAG)); + if ((IWDG->SR & IWDG_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_pwr.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_pwr.c new file mode 100644 index 000000000..9a14f5583 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_pwr.c @@ -0,0 +1,656 @@ +/** + ****************************************************************************** + * @file stm32f4xx_pwr.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Power Controller (PWR) peripheral: + * - Backup Domain Access + * - PVD configuration + * - WakeUp pin configuration + * - Main and Backup Regulators configuration + * - FLASH Power Down configuration + * - Low Power modes configuration + * - Flags management + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_pwr.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup PWR + * @brief PWR driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* --------- PWR registers bit address in the alias region ---------- */ +#define PWR_OFFSET (PWR_BASE - PERIPH_BASE) + +/* --- CR Register ---*/ + +/* Alias word address of DBP bit */ +#define CR_OFFSET (PWR_OFFSET + 0x00) +#define DBP_BitNumber 0x08 +#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4)) + +/* Alias word address of PVDE bit */ +#define PVDE_BitNumber 0x04 +#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4)) + +/* Alias word address of FPDS bit */ +#define FPDS_BitNumber 0x09 +#define CR_FPDS_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (FPDS_BitNumber * 4)) + +/* Alias word address of PMODE bit */ +#define PMODE_BitNumber 0x0E +#define CR_PMODE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PMODE_BitNumber * 4)) + + +/* --- CSR Register ---*/ + +/* Alias word address of EWUP bit */ +#define CSR_OFFSET (PWR_OFFSET + 0x04) +#define EWUP_BitNumber 0x08 +#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4)) + +/* Alias word address of BRE bit */ +#define BRE_BitNumber 0x09 +#define CSR_BRE_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (BRE_BitNumber * 4)) + +/* ------------------ PWR registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_DS_MASK ((uint32_t)0xFFFFFFFC) +#define CR_PLS_MASK ((uint32_t)0xFFFFFF1F) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup PWR_Private_Functions + * @{ + */ + +/** @defgroup PWR_Group1 Backup Domain Access function + * @brief Backup Domain Access function + * +@verbatim + =============================================================================== + Backup Domain Access function + =============================================================================== + + After reset, the backup domain (RTC registers, RTC backup data + registers and backup SRAM) is protected against possible unwanted + write accesses. + To enable access to the RTC Domain and RTC registers, proceed as follows: + - Enable the Power Controller (PWR) APB1 interface clock using the + RCC_APB1PeriphClockCmd() function. + - Enable access to RTC domain using the PWR_BackupAccessCmd() function. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the PWR peripheral registers to their default reset values. + * @param None + * @retval None + */ +void PWR_DeInit(void) +{ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE); +} + +/** + * @brief Enables or disables access to the backup domain (RTC registers, RTC + * backup data registers and backup SRAM). + * @note If the HSE divided by 2, 3, ..31 is used as the RTC clock, the + * Backup Domain Access should be kept enabled. + * @param NewState: new state of the access to the backup domain. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_BackupAccessCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_DBP_BB = (uint32_t)NewState; +} + +/** + * @} + */ + +/** @defgroup PWR_Group2 PVD configuration functions + * @brief PVD configuration functions + * +@verbatim + =============================================================================== + PVD configuration functions + =============================================================================== + + - The PVD is used to monitor the VDD power supply by comparing it to a threshold + selected by the PVD Level (PLS[2:0] bits in the PWR_CR). + - A PVDO flag is available to indicate if VDD/VDDA is higher or lower than the + PVD threshold. This event is internally connected to the EXTI line16 + and can generate an interrupt if enabled through the EXTI registers. + - The PVD is stopped in Standby mode. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD). + * @param PWR_PVDLevel: specifies the PVD detection level + * This parameter can be one of the following values: + * @arg PWR_PVDLevel_0: PVD detection level set to 2.0V + * @arg PWR_PVDLevel_1: PVD detection level set to 2.2V + * @arg PWR_PVDLevel_2: PVD detection level set to 2.3V + * @arg PWR_PVDLevel_3: PVD detection level set to 2.5V + * @arg PWR_PVDLevel_4: PVD detection level set to 2.7V + * @arg PWR_PVDLevel_5: PVD detection level set to 2.8V + * @arg PWR_PVDLevel_6: PVD detection level set to 2.9V + * @arg PWR_PVDLevel_7: PVD detection level set to 3.0V + * @note Refer to the electrical characteristics of you device datasheet for more details. + * @retval None + */ +void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel)); + + tmpreg = PWR->CR; + + /* Clear PLS[7:5] bits */ + tmpreg &= CR_PLS_MASK; + + /* Set PLS[7:5] bits according to PWR_PVDLevel value */ + tmpreg |= PWR_PVDLevel; + + /* Store the new value */ + PWR->CR = tmpreg; +} + +/** + * @brief Enables or disables the Power Voltage Detector(PVD). + * @param NewState: new state of the PVD. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_PVDCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)NewState; +} + +/** + * @} + */ + +/** @defgroup PWR_Group3 WakeUp pin configuration functions + * @brief WakeUp pin configuration functions + * +@verbatim + =============================================================================== + WakeUp pin configuration functions + =============================================================================== + + - WakeUp pin is used to wakeup the system from Standby mode. This pin is + forced in input pull down configuration and is active on rising edges. + - There is only one WakeUp pin: WakeUp Pin 1 on PA.00. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the WakeUp Pin functionality. + * @param NewState: new state of the WakeUp Pin functionality. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_WakeUpPinCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CSR_EWUP_BB = (uint32_t)NewState; +} + +/** + * @} + */ + +/** @defgroup PWR_Group4 Main and Backup Regulators configuration functions + * @brief Main and Backup Regulators configuration functions + * +@verbatim + =============================================================================== + Main and Backup Regulators configuration functions + =============================================================================== + + - The backup domain includes 4 Kbytes of backup SRAM accessible only from the + CPU, and address in 32-bit, 16-bit or 8-bit mode. Its content is retained + even in Standby or VBAT mode when the low power backup regulator is enabled. + It can be considered as an internal EEPROM when VBAT is always present. + You can use the PWR_BackupRegulatorCmd() function to enable the low power + backup regulator and use the PWR_GetFlagStatus(PWR_FLAG_BRR) to check if it is + ready or not. + + - When the backup domain is supplied by VDD (analog switch connected to VDD) + the backup SRAM is powered from VDD which replaces the VBAT power supply to + save battery life. + + - The backup SRAM is not mass erased by an tamper event. It is read protected + to prevent confidential data, such as cryptographic private key, from being + accessed. The backup SRAM can be erased only through the Flash interface when + a protection level change from level 1 to level 0 is requested. + Refer to the description of Read protection (RDP) in the Flash programming manual. + + - The main internal regulator can be configured to have a tradeoff between performance + and power consumption when the device does not operate at the maximum frequency. + This is done through PWR_MainRegulatorModeConfig() function which configure VOS bit + in PWR_CR register: + - When this bit is set (Regulator voltage output Scale 1 mode selected) the System + frequency can go up to 168 MHz. + - When this bit is reset (Regulator voltage output Scale 2 mode selected) the System + frequency can go up to 144 MHz. + Refer to the datasheets for more details. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the Backup Regulator. + * @param NewState: new state of the Backup Regulator. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_BackupRegulatorCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CSR_BRE_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the main internal regulator output voltage. + * @param PWR_Regulator_Voltage: specifies the regulator output voltage to achieve + * a tradeoff between performance and power consumption when the device does + * not operate at the maximum frequency (refer to the datasheets for more details). + * This parameter can be one of the following values: + * @arg PWR_Regulator_Voltage_Scale1: Regulator voltage output Scale 1 mode, + * System frequency up to 168 MHz. + * @arg PWR_Regulator_Voltage_Scale2: Regulator voltage output Scale 2 mode, + * System frequency up to 144 MHz. + * @retval None + */ +void PWR_MainRegulatorModeConfig(uint32_t PWR_Regulator_Voltage) +{ + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR_VOLTAGE(PWR_Regulator_Voltage)); + + if (PWR_Regulator_Voltage == PWR_Regulator_Voltage_Scale2) + { + PWR->CR &= ~PWR_Regulator_Voltage_Scale1; + } + else + { + PWR->CR |= PWR_Regulator_Voltage_Scale1; + } +} + +/** + * @} + */ + +/** @defgroup PWR_Group5 FLASH Power Down configuration functions + * @brief FLASH Power Down configuration functions + * +@verbatim + =============================================================================== + FLASH Power Down configuration functions + =============================================================================== + + - By setting the FPDS bit in the PWR_CR register by using the PWR_FlashPowerDownCmd() + function, the Flash memory also enters power down mode when the device enters + Stop mode. When the Flash memory is in power down mode, an additional startup + delay is incurred when waking up from Stop mode. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the Flash Power Down in STOP mode. + * @param NewState: new state of the Flash power mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_FlashPowerDownCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_FPDS_BB = (uint32_t)NewState; +} + +/** + * @} + */ + +/** @defgroup PWR_Group6 Low Power modes configuration functions + * @brief Low Power modes configuration functions + * +@verbatim + =============================================================================== + Low Power modes configuration functions + =============================================================================== + + The devices feature 3 low-power modes: + - Sleep mode: Cortex-M4 core stopped, peripherals kept running. + - Stop mode: all clocks are stopped, regulator running, regulator in low power mode + - Standby mode: 1.2V domain powered off. + + Sleep mode + =========== + - Entry: + - The Sleep mode is entered by using the __WFI() or __WFE() functions. + - Exit: + - Any peripheral interrupt acknowledged by the nested vectored interrupt + controller (NVIC) can wake up the device from Sleep mode. + + Stop mode + ========== + In Stop mode, all clocks in the 1.2V domain are stopped, the PLL, the HSI, + and the HSE RC oscillators are disabled. Internal SRAM and register contents + are preserved. + The voltage regulator can be configured either in normal or low-power mode. + To minimize the consumption In Stop mode, FLASH can be powered off before + entering the Stop mode. It can be switched on again by software after exiting + the Stop mode using the PWR_FlashPowerDownCmd() function. + + - Entry: + - The Stop mode is entered using the PWR_EnterSTOPMode(PWR_Regulator_LowPower,) + function with regulator in LowPower or with Regulator ON. + - Exit: + - Any EXTI Line (Internal or External) configured in Interrupt/Event mode. + + Standby mode + ============ + The Standby mode allows to achieve the lowest power consumption. It is based + on the Cortex-M4 deepsleep mode, with the voltage regulator disabled. + The 1.2V domain is consequently powered off. The PLL, the HSI oscillator and + the HSE oscillator are also switched off. SRAM and register contents are lost + except for the RTC registers, RTC backup registers, backup SRAM and Standby + circuitry. + + The voltage regulator is OFF. + + - Entry: + - The Standby mode is entered using the PWR_EnterSTANDBYMode() function. + - Exit: + - WKUP pin rising edge, RTC alarm (Alarm A and Alarm B), RTC wakeup, + tamper event, time-stamp event, external reset in NRST pin, IWDG reset. + + Auto-wakeup (AWU) from low-power mode + ===================================== + The MCU can be woken up from low-power mode by an RTC Alarm event, an RTC + Wakeup event, a tamper event, a time-stamp event, or a comparator event, + without depending on an external interrupt (Auto-wakeup mode). + + - RTC auto-wakeup (AWU) from the Stop mode + ---------------------------------------- + + - To wake up from the Stop mode with an RTC alarm event, it is necessary to: + - Configure the EXTI Line 17 to be sensitive to rising edges (Interrupt + or Event modes) using the EXTI_Init() function. + - Enable the RTC Alarm Interrupt using the RTC_ITConfig() function + - Configure the RTC to generate the RTC alarm using the RTC_SetAlarm() + and RTC_AlarmCmd() functions. + - To wake up from the Stop mode with an RTC Tamper or time stamp event, it + is necessary to: + - Configure the EXTI Line 21 to be sensitive to rising edges (Interrupt + or Event modes) using the EXTI_Init() function. + - Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig() + function + - Configure the RTC to detect the tamper or time stamp event using the + RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd() + functions. + - To wake up from the Stop mode with an RTC WakeUp event, it is necessary to: + - Configure the EXTI Line 22 to be sensitive to rising edges (Interrupt + or Event modes) using the EXTI_Init() function. + - Enable the RTC WakeUp Interrupt using the RTC_ITConfig() function + - Configure the RTC to generate the RTC WakeUp event using the RTC_WakeUpClockConfig(), + RTC_SetWakeUpCounter() and RTC_WakeUpCmd() functions. + + - RTC auto-wakeup (AWU) from the Standby mode + ------------------------------------------- + - To wake up from the Standby mode with an RTC alarm event, it is necessary to: + - Enable the RTC Alarm Interrupt using the RTC_ITConfig() function + - Configure the RTC to generate the RTC alarm using the RTC_SetAlarm() + and RTC_AlarmCmd() functions. + - To wake up from the Standby mode with an RTC Tamper or time stamp event, it + is necessary to: + - Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig() + function + - Configure the RTC to detect the tamper or time stamp event using the + RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd() + functions. + - To wake up from the Standby mode with an RTC WakeUp event, it is necessary to: + - Enable the RTC WakeUp Interrupt using the RTC_ITConfig() function + - Configure the RTC to generate the RTC WakeUp event using the RTC_WakeUpClockConfig(), + RTC_SetWakeUpCounter() and RTC_WakeUpCmd() functions. + +@endverbatim + * @{ + */ + +/** + * @brief Enters STOP mode. + * + * @note In Stop mode, all I/O pins keep the same state as in Run mode. + * @note When exiting Stop mode by issuing an interrupt or a wakeup event, + * the HSI RC oscillator is selected as system clock. + * @note When the voltage regulator operates in low power mode, an additional + * startup delay is incurred when waking up from Stop mode. + * By keeping the internal regulator ON during Stop mode, the consumption + * is higher although the startup time is reduced. + * + * @param PWR_Regulator: specifies the regulator state in STOP mode. + * This parameter can be one of the following values: + * @arg PWR_Regulator_ON: STOP mode with regulator ON + * @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode + * @param PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction + * @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction + * @retval None + */ +void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR(PWR_Regulator)); + assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry)); + + /* Select the regulator state in STOP mode ---------------------------------*/ + tmpreg = PWR->CR; + /* Clear PDDS and LPDSR bits */ + tmpreg &= CR_DS_MASK; + + /* Set LPDSR bit according to PWR_Regulator value */ + tmpreg |= PWR_Regulator; + + /* Store the new value */ + PWR->CR = tmpreg; + + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; + + /* Select STOP mode entry --------------------------------------------------*/ + if(PWR_STOPEntry == PWR_STOPEntry_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __WFE(); + } + /* Reset SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk); +} + +/** + * @brief Enters STANDBY mode. + * @note In Standby mode, all I/O pins are high impedance except for: + * - Reset pad (still available) + * - RTC_AF1 pin (PC13) if configured for tamper, time-stamp, RTC + * Alarm out, or RTC clock calibration out. + * - RTC_AF2 pin (PI8) if configured for tamper or time-stamp. + * - WKUP pin 1 (PA0) if enabled. + * @param None + * @retval None + */ +void PWR_EnterSTANDBYMode(void) +{ + /* Clear Wakeup flag */ + PWR->CR |= PWR_CR_CWUF; + + /* Select STANDBY mode */ + PWR->CR |= PWR_CR_PDDS; + + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; + +/* This option is used to ensure that store operations are completed */ +#if defined ( __CC_ARM ) + __force_stores(); +#endif + /* Request Wait For Interrupt */ + __WFI(); +} + +/** + * @} + */ + +/** @defgroup PWR_Group7 Flags management functions + * @brief Flags management functions + * +@verbatim + =============================================================================== + Flags management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Checks whether the specified PWR flag is set or not. + * @param PWR_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event + * was received from the WKUP pin or from the RTC alarm (Alarm A + * or Alarm B), RTC Tamper event, RTC TimeStamp event or RTC Wakeup. + * An additional wakeup event is detected if the WKUP pin is enabled + * (by setting the EWUP bit) when the WKUP pin level is already high. + * @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was + * resumed from StandBy mode. + * @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled + * by the PWR_PVDCmd() function. The PVD is stopped by Standby mode + * For this reason, this bit is equal to 0 after Standby or reset + * until the PVDE bit is set. + * @arg PWR_FLAG_BRR: Backup regulator ready flag. This bit is not reset + * when the device wakes up from Standby mode or by a system reset + * or power reset. + * @arg PWR_FLAG_VOSRDY: This flag indicates that the Regulator voltage + * scaling output selection is ready. + * @retval The new state of PWR_FLAG (SET or RESET). + */ +FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_PWR_GET_FLAG(PWR_FLAG)); + + if ((PWR->CSR & PWR_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the PWR's pending flags. + * @param PWR_FLAG: specifies the flag to clear. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag + * @arg PWR_FLAG_SB: StandBy flag + * @retval None + */ +void PWR_ClearFlag(uint32_t PWR_FLAG) +{ + /* Check the parameters */ + assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG)); + + PWR->CR |= PWR_FLAG << 2; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c new file mode 100644 index 000000000..87763748a --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c @@ -0,0 +1,1808 @@ +/** + ****************************************************************************** + * @file stm32f4xx_rcc.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Reset and clock control (RCC) peripheral: + * - Internal/external clocks, PLL, CSS and MCO configuration + * - System, AHB and APB busses clocks configuration + * - Peripheral clocks configuration + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * RCC specific features + * =================================================================== + * + * After reset the device is running from Internal High Speed oscillator + * (HSI 16MHz) with Flash 0 wait state, Flash prefetch buffer, D-Cache + * and I-Cache are disabled, and all peripherals are off except internal + * SRAM, Flash and JTAG. + * - There is no prescaler on High speed (AHB) and Low speed (APB) busses; + * all peripherals mapped on these busses are running at HSI speed. + * - The clock for all peripherals is switched off, except the SRAM and FLASH. + * - All GPIOs are in input floating state, except the JTAG pins which + * are assigned to be used for debug purpose. + * + * Once the device started from reset, the user application has to: + * - Configure the clock source to be used to drive the System clock + * (if the application needs higher frequency/performance) + * - Configure the System clock frequency and Flash settings + * - Configure the AHB and APB busses prescalers + * - Enable the clock for the peripheral(s) to be used + * - Configure the clock source(s) for peripherals which clocks are not + * derived from the System clock (I2S, RTC, ADC, USB OTG FS/SDIO/RNG) + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup RCC + * @brief RCC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* ------------ RCC registers bit address in the alias region ----------- */ +#define RCC_OFFSET (RCC_BASE - PERIPH_BASE) +/* --- CR Register ---*/ +/* Alias word address of HSION bit */ +#define CR_OFFSET (RCC_OFFSET + 0x00) +#define HSION_BitNumber 0x00 +#define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) +/* Alias word address of CSSON bit */ +#define CSSON_BitNumber 0x13 +#define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) +/* Alias word address of PLLON bit */ +#define PLLON_BitNumber 0x18 +#define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) +/* Alias word address of PLLI2SON bit */ +#define PLLI2SON_BitNumber 0x1A +#define CR_PLLI2SON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLI2SON_BitNumber * 4)) + +/* --- CFGR Register ---*/ +/* Alias word address of I2SSRC bit */ +#define CFGR_OFFSET (RCC_OFFSET + 0x08) +#define I2SSRC_BitNumber 0x17 +#define CFGR_I2SSRC_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (I2SSRC_BitNumber * 4)) + +/* --- BDCR Register ---*/ +/* Alias word address of RTCEN bit */ +#define BDCR_OFFSET (RCC_OFFSET + 0x70) +#define RTCEN_BitNumber 0x0F +#define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) +/* Alias word address of BDRST bit */ +#define BDRST_BitNumber 0x10 +#define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) +/* --- CSR Register ---*/ +/* Alias word address of LSION bit */ +#define CSR_OFFSET (RCC_OFFSET + 0x74) +#define LSION_BitNumber 0x00 +#define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) +/* ---------------------- RCC registers bit mask ------------------------ */ +/* CFGR register bit mask */ +#define CFGR_MCO2_RESET_MASK ((uint32_t)0x07FFFFFF) +#define CFGR_MCO1_RESET_MASK ((uint32_t)0xF89FFFFF) + +/* RCC Flag Mask */ +#define FLAG_MASK ((uint8_t)0x1F) + +/* CR register byte 3 (Bits[23:16]) base address */ +#define CR_BYTE3_ADDRESS ((uint32_t)0x40023802) + +/* CIR register byte 2 (Bits[15:8]) base address */ +#define CIR_BYTE2_ADDRESS ((uint32_t)(RCC_BASE + 0x0C + 0x01)) + +/* CIR register byte 3 (Bits[23:16]) base address */ +#define CIR_BYTE3_ADDRESS ((uint32_t)(RCC_BASE + 0x0C + 0x02)) + +/* BDCR register base address */ +#define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}; + +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup RCC_Private_Functions + * @{ + */ + +/** @defgroup RCC_Group1 Internal and external clocks, PLL, CSS and MCO configuration functions + * @brief Internal and external clocks, PLL, CSS and MCO configuration functions + * +@verbatim + =============================================================================== + Internal/external clocks, PLL, CSS and MCO configuration functions + =============================================================================== + + This section provide functions allowing to configure the internal/external clocks, + PLLs, CSS and MCO pins. + + 1. HSI (high-speed internal), 16 MHz factory-trimmed RC used directly or through + the PLL as System clock source. + + 2. LSI (low-speed internal), 32 KHz low consumption RC used as IWDG and/or RTC + clock source. + + 3. HSE (high-speed external), 4 to 26 MHz crystal oscillator used directly or + through the PLL as System clock source. Can be used also as RTC clock source. + + 4. LSE (low-speed external), 32 KHz oscillator used as RTC clock source. + + 5. PLL (clocked by HSI or HSE), featuring two different output clocks: + - The first output is used to generate the high speed system clock (up to 168 MHz) + - The second output is used to generate the clock for the USB OTG FS (48 MHz), + the random analog generator (<=48 MHz) and the SDIO (<= 48 MHz). + + 6. PLLI2S (clocked by HSI or HSE), used to generate an accurate clock to achieve + high-quality audio performance on the I2S interface. + + 7. CSS (Clock security system), once enable and if a HSE clock failure occurs + (HSE used directly or through PLL as System clock source), the System clock + is automatically switched to HSI and an interrupt is generated if enabled. + The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt) + exception vector. + + 8. MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL + clock (through a configurable prescaler) on PA8 pin. + + 9. MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or PLLI2S + clock (through a configurable prescaler) on PC9 pin. + +@endverbatim + * @{ + */ + +/** + * @brief Resets the RCC clock configuration to the default reset state. + * @note The default reset state of the clock configuration is given below: + * - HSI ON and used as system clock source + * - HSE, PLL and PLLI2S OFF + * - AHB, APB1 and APB2 prescaler set to 1. + * - CSS, MCO1 and MCO2 OFF + * - All interrupts disabled + * @note This function doesn't modify the configuration of the + * - Peripheral clocks + * - LSI, LSE and RTC clocks + * @param None + * @retval None + */ +void RCC_DeInit(void) +{ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset CFGR register */ + RCC->CFGR = 0x00000000; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset PLLCFGR register */ + RCC->PLLCFGR = 0x24003010; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Disable all interrupts */ + RCC->CIR = 0x00000000; +} + +/** + * @brief Configures the External High Speed oscillator (HSE). + * @note After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application + * software should wait on HSERDY flag to be set indicating that HSE clock + * is stable and can be used to clock the PLL and/or system clock. + * @note HSE state can not be changed if it is used directly or through the + * PLL as system clock. In this case, you have to select another source + * of the system clock then change the HSE state (ex. disable it). + * @note The HSE is stopped by hardware when entering STOP and STANDBY modes. + * @note This function reset the CSSON bit, so if the Clock security system(CSS) + * was previously enabled you have to enable it again after calling this + * function. + * @param RCC_HSE: specifies the new state of the HSE. + * This parameter can be one of the following values: + * @arg RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after + * 6 HSE oscillator clock cycles. + * @arg RCC_HSE_ON: turn ON the HSE oscillator + * @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock + * @retval None + */ +void RCC_HSEConfig(uint8_t RCC_HSE) +{ + /* Check the parameters */ + assert_param(IS_RCC_HSE(RCC_HSE)); + + /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/ + *(__IO uint8_t *) CR_BYTE3_ADDRESS = RCC_HSE_OFF; + + /* Set the new HSE configuration -------------------------------------------*/ + *(__IO uint8_t *) CR_BYTE3_ADDRESS = RCC_HSE; +} + +/** + * @brief Waits for HSE start-up. + * @note This functions waits on HSERDY flag to be set and return SUCCESS if + * this flag is set, otherwise returns ERROR if the timeout is reached + * and this flag is not set. The timeout value is defined by the constant + * HSE_STARTUP_TIMEOUT in stm32f4xx.h file. You can tailor it depending + * on the HSE crystal used in your application. + * @param None + * @retval An ErrorStatus enumeration value: + * - SUCCESS: HSE oscillator is stable and ready to use + * - ERROR: HSE oscillator not yet ready + */ +ErrorStatus RCC_WaitForHSEStartUp(void) +{ + __IO uint32_t startupcounter = 0; + ErrorStatus status = ERROR; + FlagStatus hsestatus = RESET; + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + hsestatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY); + startupcounter++; + } while((startupcounter != HSE_STARTUP_TIMEOUT) && (hsestatus == RESET)); + + if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET) + { + status = SUCCESS; + } + else + { + status = ERROR; + } + return (status); +} + +/** + * @brief Adjusts the Internal High Speed oscillator (HSI) calibration value. + * @note The calibration is used to compensate for the variations in voltage + * and temperature that influence the frequency of the internal HSI RC. + * @param HSICalibrationValue: specifies the calibration trimming value. + * This parameter must be a number between 0 and 0x1F. + * @retval None + */ +void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue)); + + tmpreg = RCC->CR; + + /* Clear HSITRIM[4:0] bits */ + tmpreg &= ~RCC_CR_HSITRIM; + + /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */ + tmpreg |= (uint32_t)HSICalibrationValue << 3; + + /* Store the new value */ + RCC->CR = tmpreg; +} + +/** + * @brief Enables or disables the Internal High Speed oscillator (HSI). + * @note The HSI is stopped by hardware when entering STOP and STANDBY modes. + * It is used (enabled by hardware) as system clock source after startup + * from Reset, wakeup from STOP and STANDBY mode, or in case of failure + * of the HSE used directly or indirectly as system clock (if the Clock + * Security System CSS is enabled). + * @note HSI can not be stopped if it is used as system clock source. In this case, + * you have to select another source of the system clock then stop the HSI. + * @note After enabling the HSI, the application software should wait on HSIRDY + * flag to be set indicating that HSI clock is stable and can be used as + * system clock source. + * @param NewState: new state of the HSI. + * This parameter can be: ENABLE or DISABLE. + * @note When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator + * clock cycles. + * @retval None + */ +void RCC_HSICmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the External Low Speed oscillator (LSE). + * @note As the LSE is in the Backup domain and write access is denied to + * this domain after reset, you have to enable write access using + * PWR_BackupAccessCmd(ENABLE) function before to configure the LSE + * (to be done once after reset). + * @note After enabling the LSE (RCC_LSE_ON or RCC_LSE_Bypass), the application + * software should wait on LSERDY flag to be set indicating that LSE clock + * is stable and can be used to clock the RTC. + * @param RCC_LSE: specifies the new state of the LSE. + * This parameter can be one of the following values: + * @arg RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after + * 6 LSE oscillator clock cycles. + * @arg RCC_LSE_ON: turn ON the LSE oscillator + * @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock + * @retval None + */ +void RCC_LSEConfig(uint8_t RCC_LSE) +{ + /* Check the parameters */ + assert_param(IS_RCC_LSE(RCC_LSE)); + + /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/ + /* Reset LSEON bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF; + + /* Reset LSEBYP bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF; + + /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */ + switch (RCC_LSE) + { + case RCC_LSE_ON: + /* Set LSEON bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_ON; + break; + case RCC_LSE_Bypass: + /* Set LSEBYP and LSEON bits */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON; + break; + default: + break; + } +} + +/** + * @brief Enables or disables the Internal Low Speed oscillator (LSI). + * @note After enabling the LSI, the application software should wait on + * LSIRDY flag to be set indicating that LSI clock is stable and can + * be used to clock the IWDG and/or the RTC. + * @note LSI can not be disabled if the IWDG is running. + * @param NewState: new state of the LSI. + * This parameter can be: ENABLE or DISABLE. + * @note When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator + * clock cycles. + * @retval None + */ +void RCC_LSICmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the main PLL clock source, multiplication and division factors. + * @note This function must be used only when the main PLL is disabled. + * + * @param RCC_PLLSource: specifies the PLL entry clock source. + * This parameter can be one of the following values: + * @arg RCC_PLLSource_HSI: HSI oscillator clock selected as PLL clock entry + * @arg RCC_PLLSource_HSE: HSE oscillator clock selected as PLL clock entry + * @note This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S. + * + * @param PLLM: specifies the division factor for PLL VCO input clock + * This parameter must be a number between 0 and 63. + * @note You have to set the PLLM parameter correctly to ensure that the VCO input + * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency + * of 2 MHz to limit PLL jitter. + * + * @param PLLN: specifies the multiplication factor for PLL VCO output clock + * This parameter must be a number between 192 and 432. + * @note You have to set the PLLN parameter correctly to ensure that the VCO + * output frequency is between 192 and 432 MHz. + * + * @param PLLP: specifies the division factor for main system clock (SYSCLK) + * This parameter must be a number in the range {2, 4, 6, or 8}. + * @note You have to set the PLLP parameter correctly to not exceed 168 MHz on + * the System clock frequency. + * + * @param PLLQ: specifies the division factor for OTG FS, SDIO and RNG clocks + * This parameter must be a number between 4 and 15. + * @note If the USB OTG FS is used in your application, you have to set the + * PLLQ parameter correctly to have 48 MHz clock for the USB. However, + * the SDIO and RNG need a frequency lower than or equal to 48 MHz to work + * correctly. + * + * @retval None + */ +void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ) +{ + /* Check the parameters */ + assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource)); + assert_param(IS_RCC_PLLM_VALUE(PLLM)); + assert_param(IS_RCC_PLLN_VALUE(PLLN)); + assert_param(IS_RCC_PLLP_VALUE(PLLP)); + assert_param(IS_RCC_PLLQ_VALUE(PLLQ)); + + RCC->PLLCFGR = PLLM | (PLLN << 6) | (((PLLP >> 1) -1) << 16) | (RCC_PLLSource) | + (PLLQ << 24); +} + +/** + * @brief Enables or disables the main PLL. + * @note After enabling the main PLL, the application software should wait on + * PLLRDY flag to be set indicating that PLL clock is stable and can + * be used as system clock source. + * @note The main PLL can not be disabled if it is used as system clock source + * @note The main PLL is disabled by hardware when entering STOP and STANDBY modes. + * @param NewState: new state of the main PLL. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLLCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the PLLI2S clock multiplication and division factors. + * + * @note This function must be used only when the PLLI2S is disabled. + * @note PLLI2S clock source is common with the main PLL (configured in + * RCC_PLLConfig function ) + * + * @param PLLI2SN: specifies the multiplication factor for PLLI2S VCO output clock + * This parameter must be a number between 192 and 432. + * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO + * output frequency is between 192 and 432 MHz. + * + * @param PLLI2SR: specifies the division factor for I2S clock + * This parameter must be a number between 2 and 7. + * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz + * on the I2S clock frequency. + * + * @retval None + */ +void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SR) +{ + /* Check the parameters */ + assert_param(IS_RCC_PLLI2SN_VALUE(PLLI2SN)); + assert_param(IS_RCC_PLLI2SR_VALUE(PLLI2SR)); + + RCC->PLLI2SCFGR = (PLLI2SN << 6) | (PLLI2SR << 28); +} + +/** + * @brief Enables or disables the PLLI2S. + * @note The PLLI2S is disabled by hardware when entering STOP and STANDBY modes. + * @param NewState: new state of the PLLI2S. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLLI2SCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_PLLI2SON_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the Clock Security System. + * @note If a failure is detected on the HSE oscillator clock, this oscillator + * is automatically disabled and an interrupt is generated to inform the + * software about the failure (Clock Security System Interrupt, CSSI), + * allowing the MCU to perform rescue operations. The CSSI is linked to + * the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector. + * @param NewState: new state of the Clock Security System. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_ClockSecuritySystemCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState; +} + +/** + * @brief Selects the clock source to output on MCO1 pin(PA8). + * @note PA8 should be configured in alternate function mode. + * @param RCC_MCO1Source: specifies the clock source to output. + * This parameter can be one of the following values: + * @arg RCC_MCO1Source_HSI: HSI clock selected as MCO1 source + * @arg RCC_MCO1Source_LSE: LSE clock selected as MCO1 source + * @arg RCC_MCO1Source_HSE: HSE clock selected as MCO1 source + * @arg RCC_MCO1Source_PLLCLK: main PLL clock selected as MCO1 source + * @param RCC_MCO1Div: specifies the MCO1 prescaler. + * This parameter can be one of the following values: + * @arg RCC_MCO1Div_1: no division applied to MCO1 clock + * @arg RCC_MCO1Div_2: division by 2 applied to MCO1 clock + * @arg RCC_MCO1Div_3: division by 3 applied to MCO1 clock + * @arg RCC_MCO1Div_4: division by 4 applied to MCO1 clock + * @arg RCC_MCO1Div_5: division by 5 applied to MCO1 clock + * @retval None + */ +void RCC_MCO1Config(uint32_t RCC_MCO1Source, uint32_t RCC_MCO1Div) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_MCO1SOURCE(RCC_MCO1Source)); + assert_param(IS_RCC_MCO1DIV(RCC_MCO1Div)); + + tmpreg = RCC->CFGR; + + /* Clear MCO1[1:0] and MCO1PRE[2:0] bits */ + tmpreg &= CFGR_MCO1_RESET_MASK; + + /* Select MCO1 clock source and prescaler */ + tmpreg |= RCC_MCO1Source | RCC_MCO1Div; + + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Selects the clock source to output on MCO2 pin(PC9). + * @note PC9 should be configured in alternate function mode. + * @param RCC_MCO2Source: specifies the clock source to output. + * This parameter can be one of the following values: + * @arg RCC_MCO2Source_SYSCLK: System clock (SYSCLK) selected as MCO2 source + * @arg RCC_MCO2Source_PLLI2SCLK: PLLI2S clock selected as MCO2 source + * @arg RCC_MCO2Source_HSE: HSE clock selected as MCO2 source + * @arg RCC_MCO2Source_PLLCLK: main PLL clock selected as MCO2 source + * @param RCC_MCO2Div: specifies the MCO2 prescaler. + * This parameter can be one of the following values: + * @arg RCC_MCO2Div_1: no division applied to MCO2 clock + * @arg RCC_MCO2Div_2: division by 2 applied to MCO2 clock + * @arg RCC_MCO2Div_3: division by 3 applied to MCO2 clock + * @arg RCC_MCO2Div_4: division by 4 applied to MCO2 clock + * @arg RCC_MCO2Div_5: division by 5 applied to MCO2 clock + * @retval None + */ +void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_MCO2SOURCE(RCC_MCO2Source)); + assert_param(IS_RCC_MCO2DIV(RCC_MCO2Div)); + + tmpreg = RCC->CFGR; + + /* Clear MCO2 and MCO2PRE[2:0] bits */ + tmpreg &= CFGR_MCO2_RESET_MASK; + + /* Select MCO2 clock source and prescaler */ + tmpreg |= RCC_MCO2Source | RCC_MCO2Div; + + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @} + */ + +/** @defgroup RCC_Group2 System AHB and APB busses clocks configuration functions + * @brief System, AHB and APB busses clocks configuration functions + * +@verbatim + =============================================================================== + System, AHB and APB busses clocks configuration functions + =============================================================================== + + This section provide functions allowing to configure the System, AHB, APB1 and + APB2 busses clocks. + + 1. Several clock sources can be used to drive the System clock (SYSCLK): HSI, + HSE and PLL. + The AHB clock (HCLK) is derived from System clock through configurable prescaler + and used to clock the CPU, memory and peripherals mapped on AHB bus (DMA, GPIO...). + APB1 (PCLK1) and APB2 (PCLK2) clocks are derived from AHB clock through + configurable prescalers and used to clock the peripherals mapped on these busses. + You can use "RCC_GetClocksFreq()" function to retrieve the frequencies of these clocks. + +@note All the peripheral clocks are derived from the System clock (SYSCLK) except: + - I2S: the I2S clock can be derived either from a specific PLL (PLLI2S) or + from an external clock mapped on the I2S_CKIN pin. + You have to use RCC_I2SCLKConfig() function to configure this clock. + - RTC: the RTC clock can be derived either from the LSI, LSE or HSE clock + divided by 2 to 31. You have to use RCC_RTCCLKConfig() and RCC_RTCCLKCmd() + functions to configure this clock. + - USB OTG FS, SDIO and RTC: USB OTG FS require a frequency equal to 48 MHz + to work correctly, while the SDIO require a frequency equal or lower than + to 48. This clock is derived of the main PLL through PLLQ divider. + - IWDG clock which is always the LSI clock. + + 2. The maximum frequency of the SYSCLK and HCLK is 168 MHz, PCLK2 82 MHz and PCLK1 42 MHz. + Depending on the device voltage range, the maximum frequency should be + adapted accordingly: + +-------------------------------------------------------------------------------------+ + | Latency | HCLK clock frequency (MHz) | + | |---------------------------------------------------------------------| + | | voltage range | voltage range | voltage range | voltage range | + | | 2.7 V - 3.6 V | 2.4 V - 2.7 V | 2.1 V - 2.4 V | 1.8 V - 2.1 V | + |---------------|----------------|----------------|-----------------|-----------------| + |0WS(1CPU cycle)|0 < HCLK <= 30 |0 < HCLK <= 24 |0 < HCLK <= 18 |0 < HCLK <= 16 | + |---------------|----------------|----------------|-----------------|-----------------| + |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |18 < HCLK <= 36 |16 < HCLK <= 32 | + |---------------|----------------|----------------|-----------------|-----------------| + |2WS(3CPU cycle)|60 < HCLK <= 90 |48 < HCLK <= 72 |36 < HCLK <= 54 |32 < HCLK <= 48 | + |---------------|----------------|----------------|-----------------|-----------------| + |3WS(4CPU cycle)|90 < HCLK <= 120|72 < HCLK <= 96 |54 < HCLK <= 72 |48 < HCLK <= 64 | + |---------------|----------------|----------------|-----------------|-----------------| + |4WS(5CPU cycle)|120< HCLK <= 150|96 < HCLK <= 120|72 < HCLK <= 90 |64 < HCLK <= 80 | + |---------------|----------------|----------------|-----------------|-----------------| + |5WS(6CPU cycle)|120< HCLK <= 168|120< HCLK <= 144|90 < HCLK <= 108 |80 < HCLK <= 96 | + |---------------|----------------|----------------|-----------------|-----------------| + |6WS(7CPU cycle)| NA |144< HCLK <= 168|108 < HCLK <= 120|96 < HCLK <= 112 | + |---------------|----------------|----------------|-----------------|-----------------| + |7WS(8CPU cycle)| NA | NA |120 < HCLK <= 138|112 < HCLK <= 120| + +-------------------------------------------------------------------------------------+ + @note When VOS bit (in PWR_CR register) is reset to '0’, the maximum value of HCLK is 144 MHz. + You can use PWR_MainRegulatorModeConfig() function to set or reset this bit. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the system clock (SYSCLK). + * @note The HSI is used (enabled by hardware) as system clock source after + * startup from Reset, wake-up from STOP and STANDBY mode, or in case + * of failure of the HSE used directly or indirectly as system clock + * (if the Clock Security System CSS is enabled). + * @note A switch from one clock source to another occurs only if the target + * clock source is ready (clock stable after startup delay or PLL locked). + * If a clock source which is not yet ready is selected, the switch will + * occur when the clock source will be ready. + * You can use RCC_GetSYSCLKSource() function to know which clock is + * currently used as system clock source. + * @param RCC_SYSCLKSource: specifies the clock source used as system clock. + * This parameter can be one of the following values: + * @arg RCC_SYSCLKSource_HSI: HSI selected as system clock source + * @arg RCC_SYSCLKSource_HSE: HSE selected as system clock source + * @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock source + * @retval None + */ +void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource)); + + tmpreg = RCC->CFGR; + + /* Clear SW[1:0] bits */ + tmpreg &= ~RCC_CFGR_SW; + + /* Set SW[1:0] bits according to RCC_SYSCLKSource value */ + tmpreg |= RCC_SYSCLKSource; + + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Returns the clock source used as system clock. + * @param None + * @retval The clock source used as system clock. The returned value can be one + * of the following: + * - 0x00: HSI used as system clock + * - 0x04: HSE used as system clock + * - 0x08: PLL used as system clock + */ +uint8_t RCC_GetSYSCLKSource(void) +{ + return ((uint8_t)(RCC->CFGR & RCC_CFGR_SWS)); +} + +/** + * @brief Configures the AHB clock (HCLK). + * @note Depending on the device voltage range, the software has to set correctly + * these bits to ensure that HCLK not exceed the maximum allowed frequency + * (for more details refer to section above + * "CPU, AHB and APB busses clocks configuration functions") + * @param RCC_SYSCLK: defines the AHB clock divider. This clock is derived from + * the system clock (SYSCLK). + * This parameter can be one of the following values: + * @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK + * @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2 + * @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4 + * @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8 + * @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16 + * @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64 + * @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128 + * @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256 + * @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512 + * @retval None + */ +void RCC_HCLKConfig(uint32_t RCC_SYSCLK) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_HCLK(RCC_SYSCLK)); + + tmpreg = RCC->CFGR; + + /* Clear HPRE[3:0] bits */ + tmpreg &= ~RCC_CFGR_HPRE; + + /* Set HPRE[3:0] bits according to RCC_SYSCLK value */ + tmpreg |= RCC_SYSCLK; + + /* Store the new value */ + RCC->CFGR = tmpreg; +} + + +/** + * @brief Configures the Low Speed APB clock (PCLK1). + * @param RCC_HCLK: defines the APB1 clock divider. This clock is derived from + * the AHB clock (HCLK). + * This parameter can be one of the following values: + * @arg RCC_HCLK_Div1: APB1 clock = HCLK + * @arg RCC_HCLK_Div2: APB1 clock = HCLK/2 + * @arg RCC_HCLK_Div4: APB1 clock = HCLK/4 + * @arg RCC_HCLK_Div8: APB1 clock = HCLK/8 + * @arg RCC_HCLK_Div16: APB1 clock = HCLK/16 + * @retval None + */ +void RCC_PCLK1Config(uint32_t RCC_HCLK) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PCLK(RCC_HCLK)); + + tmpreg = RCC->CFGR; + + /* Clear PPRE1[2:0] bits */ + tmpreg &= ~RCC_CFGR_PPRE1; + + /* Set PPRE1[2:0] bits according to RCC_HCLK value */ + tmpreg |= RCC_HCLK; + + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Configures the High Speed APB clock (PCLK2). + * @param RCC_HCLK: defines the APB2 clock divider. This clock is derived from + * the AHB clock (HCLK). + * This parameter can be one of the following values: + * @arg RCC_HCLK_Div1: APB2 clock = HCLK + * @arg RCC_HCLK_Div2: APB2 clock = HCLK/2 + * @arg RCC_HCLK_Div4: APB2 clock = HCLK/4 + * @arg RCC_HCLK_Div8: APB2 clock = HCLK/8 + * @arg RCC_HCLK_Div16: APB2 clock = HCLK/16 + * @retval None + */ +void RCC_PCLK2Config(uint32_t RCC_HCLK) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PCLK(RCC_HCLK)); + + tmpreg = RCC->CFGR; + + /* Clear PPRE2[2:0] bits */ + tmpreg &= ~RCC_CFGR_PPRE2; + + /* Set PPRE2[2:0] bits according to RCC_HCLK value */ + tmpreg |= RCC_HCLK << 3; + + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Returns the frequencies of different on chip clocks; SYSCLK, HCLK, + * PCLK1 and PCLK2. + * + * @note The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*) + * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**) + * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * @note (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * @note (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value + * 25 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * @note The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @param RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold + * the clocks frequencies. + * + * @note This function can be used by the user application to compute the + * baudrate for the communication peripherals or configure other parameters. + * @note Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function + * must be called to update the structure's field. Otherwise, any + * configuration based on this function will be incorrect. + * + * @retval None + */ +void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) +{ + uint32_t tmp = 0, presc = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* HSI used as system clock source */ + RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock source */ + RCC_Clocks->SYSCLK_Frequency = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock source */ + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SYSCLK = PLL_VCO / PLLP + */ + pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22; + pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; + + if (pllsource != 0) + { + /* HSE used as PLL clock source */ + pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + } + else + { + /* HSI used as PLL clock source */ + pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + } + + pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; + RCC_Clocks->SYSCLK_Frequency = pllvco/pllp; + break; + default: + RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; + break; + } + /* Compute HCLK, PCLK1 and PCLK2 clocks frequencies ------------------------*/ + + /* Get HCLK prescaler */ + tmp = RCC->CFGR & RCC_CFGR_HPRE; + tmp = tmp >> 4; + presc = APBAHBPrescTable[tmp]; + /* HCLK clock frequency */ + RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc; + + /* Get PCLK1 prescaler */ + tmp = RCC->CFGR & RCC_CFGR_PPRE1; + tmp = tmp >> 10; + presc = APBAHBPrescTable[tmp]; + /* PCLK1 clock frequency */ + RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc; + + /* Get PCLK2 prescaler */ + tmp = RCC->CFGR & RCC_CFGR_PPRE2; + tmp = tmp >> 13; + presc = APBAHBPrescTable[tmp]; + /* PCLK2 clock frequency */ + RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc; +} + +/** + * @} + */ + +/** @defgroup RCC_Group3 Peripheral clocks configuration functions + * @brief Peripheral clocks configuration functions + * +@verbatim + =============================================================================== + Peripheral clocks configuration functions + =============================================================================== + + This section provide functions allowing to configure the Peripheral clocks. + + 1. The RTC clock which is derived from the LSI, LSE or HSE clock divided by 2 to 31. + + 2. After restart from Reset or wakeup from STANDBY, all peripherals are off + except internal SRAM, Flash and JTAG. Before to start using a peripheral you + have to enable its interface clock. You can do this using RCC_AHBPeriphClockCmd() + , RCC_APB2PeriphClockCmd() and RCC_APB1PeriphClockCmd() functions. + + 3. To reset the peripherals configuration (to the default state after device reset) + you can use RCC_AHBPeriphResetCmd(), RCC_APB2PeriphResetCmd() and + RCC_APB1PeriphResetCmd() functions. + + 4. To further reduce power consumption in SLEEP mode the peripheral clocks can + be disabled prior to executing the WFI or WFE instructions. You can do this + using RCC_AHBPeriphClockLPModeCmd(), RCC_APB2PeriphClockLPModeCmd() and + RCC_APB1PeriphClockLPModeCmd() functions. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the RTC clock (RTCCLK). + * @note As the RTC clock configuration bits are in the Backup domain and write + * access is denied to this domain after reset, you have to enable write + * access using PWR_BackupAccessCmd(ENABLE) function before to configure + * the RTC clock source (to be done once after reset). + * @note Once the RTC clock is configured it can't be changed unless the + * Backup domain is reset using RCC_BackupResetCmd() function, or by + * a Power On Reset (POR). + * + * @param RCC_RTCCLKSource: specifies the RTC clock source. + * This parameter can be one of the following values: + * @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock + * @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock + * @arg RCC_RTCCLKSource_HSE_Divx: HSE clock divided by x selected + * as RTC clock, where x:[2,31] + * + * @note If the LSE or LSI is used as RTC clock source, the RTC continues to + * work in STOP and STANDBY modes, and can be used as wakeup source. + * However, when the HSE clock is used as RTC clock source, the RTC + * cannot be used in STOP and STANDBY modes. + * @note The maximum input clock frequency for RTC is 1MHz (when using HSE as + * RTC clock source). + * + * @retval None + */ +void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource)); + + if ((RCC_RTCCLKSource & 0x00000300) == 0x00000300) + { /* If HSE is selected as RTC clock source, configure HSE division factor for RTC clock */ + tmpreg = RCC->CFGR; + + /* Clear RTCPRE[4:0] bits */ + tmpreg &= ~RCC_CFGR_RTCPRE; + + /* Configure HSE division factor for RTC clock */ + tmpreg |= (RCC_RTCCLKSource & 0xFFFFCFF); + + /* Store the new value */ + RCC->CFGR = tmpreg; + } + + /* Select the RTC clock source */ + RCC->BDCR |= (RCC_RTCCLKSource & 0x00000FFF); +} + +/** + * @brief Enables or disables the RTC clock. + * @note This function must be used only after the RTC clock source was selected + * using the RCC_RTCCLKConfig function. + * @param NewState: new state of the RTC clock. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_RTCCLKCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState; +} + +/** + * @brief Forces or releases the Backup domain reset. + * @note This function resets the RTC peripheral (including the backup registers) + * and the RTC clock source selection in RCC_CSR register. + * @note The BKPSRAM is not affected by this reset. + * @param NewState: new state of the Backup domain reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_BackupResetCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the I2S clock source (I2SCLK). + * @note This function must be called before enabling the I2S APB clock. + * @param RCC_I2SCLKSource: specifies the I2S clock source. + * This parameter can be one of the following values: + * @arg RCC_I2S2CLKSource_PLLI2S: PLLI2S clock used as I2S clock source + * @arg RCC_I2S2CLKSource_Ext: External clock mapped on the I2S_CKIN pin + * used as I2S clock source + * @retval None + */ +void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_I2SCLK_SOURCE(RCC_I2SCLKSource)); + + *(__IO uint32_t *) CFGR_I2SSRC_BB = RCC_I2SCLKSource; +} + +/** + * @brief Enables or disables the AHB1 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @param RCC_AHBPeriph: specifies the AHB1 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_AHB1Periph_GPIOA: GPIOA clock + * @arg RCC_AHB1Periph_GPIOB: GPIOB clock + * @arg RCC_AHB1Periph_GPIOC: GPIOC clock + * @arg RCC_AHB1Periph_GPIOD: GPIOD clock + * @arg RCC_AHB1Periph_GPIOE: GPIOE clock + * @arg RCC_AHB1Periph_GPIOF: GPIOF clock + * @arg RCC_AHB1Periph_GPIOG: GPIOG clock + * @arg RCC_AHB1Periph_GPIOG: GPIOG clock + * @arg RCC_AHB1Periph_GPIOI: GPIOI clock + * @arg RCC_AHB1Periph_CRC: CRC clock + * @arg RCC_AHB1Periph_BKPSRAM: BKPSRAM interface clock + * @arg RCC_AHB1Periph_CCMDATARAMEN CCM data RAM interface clock + * @arg RCC_AHB1Periph_DMA1: DMA1 clock + * @arg RCC_AHB1Periph_DMA2: DMA2 clock + * @arg RCC_AHB1Periph_ETH_MAC: Ethernet MAC clock + * @arg RCC_AHB1Periph_ETH_MAC_Tx: Ethernet Transmission clock + * @arg RCC_AHB1Periph_ETH_MAC_Rx: Ethernet Reception clock + * @arg RCC_AHB1Periph_ETH_MAC_PTP: Ethernet PTP clock + * @arg RCC_AHB1Periph_OTG_HS: USB OTG HS clock + * @arg RCC_AHB1Periph_OTG_HS_ULPI: USB OTG HS ULPI clock + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHB1PeriphClockCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB1_CLOCK_PERIPH(RCC_AHB1Periph)); + + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->AHB1ENR |= RCC_AHB1Periph; + } + else + { + RCC->AHB1ENR &= ~RCC_AHB1Periph; + } +} + +/** + * @brief Enables or disables the AHB2 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @param RCC_AHBPeriph: specifies the AHB2 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_AHB2Periph_DCMI: DCMI clock + * @arg RCC_AHB2Periph_CRYP: CRYP clock + * @arg RCC_AHB2Periph_HASH: HASH clock + * @arg RCC_AHB2Periph_RNG: RNG clock + * @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB2_PERIPH(RCC_AHB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHB2ENR |= RCC_AHB2Periph; + } + else + { + RCC->AHB2ENR &= ~RCC_AHB2Periph; + } +} + +/** + * @brief Enables or disables the AHB3 peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @param RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock. + * This parameter must be: RCC_AHB3Periph_FSMC + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHB3PeriphClockCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB3_PERIPH(RCC_AHB3Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHB3ENR |= RCC_AHB3Periph; + } + else + { + RCC->AHB3ENR &= ~RCC_AHB3Periph; + } +} + +/** + * @brief Enables or disables the Low Speed APB (APB1) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @param RCC_APB1Periph: specifies the APB1 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2: TIM2 clock + * @arg RCC_APB1Periph_TIM3: TIM3 clock + * @arg RCC_APB1Periph_TIM4: TIM4 clock + * @arg RCC_APB1Periph_TIM5: TIM5 clock + * @arg RCC_APB1Periph_TIM6: TIM6 clock + * @arg RCC_APB1Periph_TIM7: TIM7 clock + * @arg RCC_APB1Periph_TIM12: TIM12 clock + * @arg RCC_APB1Periph_TIM13: TIM13 clock + * @arg RCC_APB1Periph_TIM14: TIM14 clock + * @arg RCC_APB1Periph_WWDG: WWDG clock + * @arg RCC_APB1Periph_SPI2: SPI2 clock + * @arg RCC_APB1Periph_SPI3: SPI3 clock + * @arg RCC_APB1Periph_USART2: USART2 clock + * @arg RCC_APB1Periph_USART3: USART3 clock + * @arg RCC_APB1Periph_UART4: UART4 clock + * @arg RCC_APB1Periph_UART5: UART5 clock + * @arg RCC_APB1Periph_I2C1: I2C1 clock + * @arg RCC_APB1Periph_I2C2: I2C2 clock + * @arg RCC_APB1Periph_I2C3: I2C3 clock + * @arg RCC_APB1Periph_CAN1: CAN1 clock + * @arg RCC_APB1Periph_CAN2: CAN2 clock + * @arg RCC_APB1Periph_PWR: PWR clock + * @arg RCC_APB1Periph_DAC: DAC clock + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->APB1ENR |= RCC_APB1Periph; + } + else + { + RCC->APB1ENR &= ~RCC_APB1Periph; + } +} + +/** + * @brief Enables or disables the High Speed APB (APB2) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @param RCC_APB2Periph: specifies the APB2 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_TIM1: TIM1 clock + * @arg RCC_APB2Periph_TIM8: TIM8 clock + * @arg RCC_APB2Periph_USART1: USART1 clock + * @arg RCC_APB2Periph_USART6: USART6 clock + * @arg RCC_APB2Periph_ADC1: ADC1 clock + * @arg RCC_APB2Periph_ADC2: ADC2 clock + * @arg RCC_APB2Periph_ADC3: ADC3 clock + * @arg RCC_APB2Periph_SDIO: SDIO clock + * @arg RCC_APB2Periph_SPI1: SPI1 clock + * @arg RCC_APB2Periph_SYSCFG: SYSCFG clock + * @arg RCC_APB2Periph_TIM9: TIM9 clock + * @arg RCC_APB2Periph_TIM10: TIM10 clock + * @arg RCC_APB2Periph_TIM11: TIM11 clock + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->APB2ENR |= RCC_APB2Periph; + } + else + { + RCC->APB2ENR &= ~RCC_APB2Periph; + } +} + +/** + * @brief Forces or releases AHB1 peripheral reset. + * @param RCC_AHB1Periph: specifies the AHB1 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_AHB1Periph_GPIOA: GPIOA clock + * @arg RCC_AHB1Periph_GPIOB: GPIOB clock + * @arg RCC_AHB1Periph_GPIOC: GPIOC clock + * @arg RCC_AHB1Periph_GPIOD: GPIOD clock + * @arg RCC_AHB1Periph_GPIOE: GPIOE clock + * @arg RCC_AHB1Periph_GPIOF: GPIOF clock + * @arg RCC_AHB1Periph_GPIOG: GPIOG clock + * @arg RCC_AHB1Periph_GPIOG: GPIOG clock + * @arg RCC_AHB1Periph_GPIOI: GPIOI clock + * @arg RCC_AHB1Periph_CRC: CRC clock + * @arg RCC_AHB1Periph_DMA1: DMA1 clock + * @arg RCC_AHB1Periph_DMA2: DMA2 clock + * @arg RCC_AHB1Periph_ETH_MAC: Ethernet MAC clock + * @arg RCC_AHB1Periph_OTG_HS: USB OTG HS clock + * + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHB1PeriphResetCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB1_RESET_PERIPH(RCC_AHB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHB1RSTR |= RCC_AHB1Periph; + } + else + { + RCC->AHB1RSTR &= ~RCC_AHB1Periph; + } +} + +/** + * @brief Forces or releases AHB2 peripheral reset. + * @param RCC_AHB2Periph: specifies the AHB2 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_AHB2Periph_DCMI: DCMI clock + * @arg RCC_AHB2Periph_CRYP: CRYP clock + * @arg RCC_AHB2Periph_HASH: HASH clock + * @arg RCC_AHB2Periph_RNG: RNG clock + * @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHB2PeriphResetCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB2_PERIPH(RCC_AHB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHB2RSTR |= RCC_AHB2Periph; + } + else + { + RCC->AHB2RSTR &= ~RCC_AHB2Periph; + } +} + +/** + * @brief Forces or releases AHB3 peripheral reset. + * @param RCC_AHB3Periph: specifies the AHB3 peripheral to reset. + * This parameter must be: RCC_AHB3Periph_FSMC + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHB3PeriphResetCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB3_PERIPH(RCC_AHB3Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHB3RSTR |= RCC_AHB3Periph; + } + else + { + RCC->AHB3RSTR &= ~RCC_AHB3Periph; + } +} + +/** + * @brief Forces or releases Low Speed APB (APB1) peripheral reset. + * @param RCC_APB1Periph: specifies the APB1 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2: TIM2 clock + * @arg RCC_APB1Periph_TIM3: TIM3 clock + * @arg RCC_APB1Periph_TIM4: TIM4 clock + * @arg RCC_APB1Periph_TIM5: TIM5 clock + * @arg RCC_APB1Periph_TIM6: TIM6 clock + * @arg RCC_APB1Periph_TIM7: TIM7 clock + * @arg RCC_APB1Periph_TIM12: TIM12 clock + * @arg RCC_APB1Periph_TIM13: TIM13 clock + * @arg RCC_APB1Periph_TIM14: TIM14 clock + * @arg RCC_APB1Periph_WWDG: WWDG clock + * @arg RCC_APB1Periph_SPI2: SPI2 clock + * @arg RCC_APB1Periph_SPI3: SPI3 clock + * @arg RCC_APB1Periph_USART2: USART2 clock + * @arg RCC_APB1Periph_USART3: USART3 clock + * @arg RCC_APB1Periph_UART4: UART4 clock + * @arg RCC_APB1Periph_UART5: UART5 clock + * @arg RCC_APB1Periph_I2C1: I2C1 clock + * @arg RCC_APB1Periph_I2C2: I2C2 clock + * @arg RCC_APB1Periph_I2C3: I2C3 clock + * @arg RCC_APB1Periph_CAN1: CAN1 clock + * @arg RCC_APB1Periph_CAN2: CAN2 clock + * @arg RCC_APB1Periph_PWR: PWR clock + * @arg RCC_APB1Periph_DAC: DAC clock + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB1RSTR |= RCC_APB1Periph; + } + else + { + RCC->APB1RSTR &= ~RCC_APB1Periph; + } +} + +/** + * @brief Forces or releases High Speed APB (APB2) peripheral reset. + * @param RCC_APB2Periph: specifies the APB2 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_TIM1: TIM1 clock + * @arg RCC_APB2Periph_TIM8: TIM8 clock + * @arg RCC_APB2Periph_USART1: USART1 clock + * @arg RCC_APB2Periph_USART6: USART6 clock + * @arg RCC_APB2Periph_ADC1: ADC1 clock + * @arg RCC_APB2Periph_ADC2: ADC2 clock + * @arg RCC_APB2Periph_ADC3: ADC3 clock + * @arg RCC_APB2Periph_SDIO: SDIO clock + * @arg RCC_APB2Periph_SPI1: SPI1 clock + * @arg RCC_APB2Periph_SYSCFG: SYSCFG clock + * @arg RCC_APB2Periph_TIM9: TIM9 clock + * @arg RCC_APB2Periph_TIM10: TIM10 clock + * @arg RCC_APB2Periph_TIM11: TIM11 clock + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_RESET_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB2RSTR |= RCC_APB2Periph; + } + else + { + RCC->APB2RSTR &= ~RCC_APB2Periph; + } +} + +/** + * @brief Enables or disables the AHB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @param RCC_AHBPeriph: specifies the AHB1 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_AHB1Periph_GPIOA: GPIOA clock + * @arg RCC_AHB1Periph_GPIOB: GPIOB clock + * @arg RCC_AHB1Periph_GPIOC: GPIOC clock + * @arg RCC_AHB1Periph_GPIOD: GPIOD clock + * @arg RCC_AHB1Periph_GPIOE: GPIOE clock + * @arg RCC_AHB1Periph_GPIOF: GPIOF clock + * @arg RCC_AHB1Periph_GPIOG: GPIOG clock + * @arg RCC_AHB1Periph_GPIOG: GPIOG clock + * @arg RCC_AHB1Periph_GPIOI: GPIOI clock + * @arg RCC_AHB1Periph_CRC: CRC clock + * @arg RCC_AHB1Periph_BKPSRAM: BKPSRAM interface clock + * @arg RCC_AHB1Periph_DMA1: DMA1 clock + * @arg RCC_AHB1Periph_DMA2: DMA2 clock + * @arg RCC_AHB1Periph_ETH_MAC: Ethernet MAC clock + * @arg RCC_AHB1Periph_ETH_MAC_Tx: Ethernet Transmission clock + * @arg RCC_AHB1Periph_ETH_MAC_Rx: Ethernet Reception clock + * @arg RCC_AHB1Periph_ETH_MAC_PTP: Ethernet PTP clock + * @arg RCC_AHB1Periph_OTG_HS: USB OTG HS clock + * @arg RCC_AHB1Periph_OTG_HS_ULPI: USB OTG HS ULPI clock + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHB1PeriphClockLPModeCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB1_LPMODE_PERIPH(RCC_AHB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->AHB1LPENR |= RCC_AHB1Periph; + } + else + { + RCC->AHB1LPENR &= ~RCC_AHB1Periph; + } +} + +/** + * @brief Enables or disables the AHB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @param RCC_AHBPeriph: specifies the AHB2 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_AHB2Periph_DCMI: DCMI clock + * @arg RCC_AHB2Periph_CRYP: CRYP clock + * @arg RCC_AHB2Periph_HASH: HASH clock + * @arg RCC_AHB2Periph_RNG: RNG clock + * @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB2_PERIPH(RCC_AHB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->AHB2LPENR |= RCC_AHB2Periph; + } + else + { + RCC->AHB2LPENR &= ~RCC_AHB2Periph; + } +} + +/** + * @brief Enables or disables the AHB3 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @param RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock. + * This parameter must be: RCC_AHB3Periph_FSMC + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHB3PeriphClockLPModeCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB3_PERIPH(RCC_AHB3Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->AHB3LPENR |= RCC_AHB3Periph; + } + else + { + RCC->AHB3LPENR &= ~RCC_AHB3Periph; + } +} + +/** + * @brief Enables or disables the APB1 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @param RCC_APB1Periph: specifies the APB1 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2: TIM2 clock + * @arg RCC_APB1Periph_TIM3: TIM3 clock + * @arg RCC_APB1Periph_TIM4: TIM4 clock + * @arg RCC_APB1Periph_TIM5: TIM5 clock + * @arg RCC_APB1Periph_TIM6: TIM6 clock + * @arg RCC_APB1Periph_TIM7: TIM7 clock + * @arg RCC_APB1Periph_TIM12: TIM12 clock + * @arg RCC_APB1Periph_TIM13: TIM13 clock + * @arg RCC_APB1Periph_TIM14: TIM14 clock + * @arg RCC_APB1Periph_WWDG: WWDG clock + * @arg RCC_APB1Periph_SPI2: SPI2 clock + * @arg RCC_APB1Periph_SPI3: SPI3 clock + * @arg RCC_APB1Periph_USART2: USART2 clock + * @arg RCC_APB1Periph_USART3: USART3 clock + * @arg RCC_APB1Periph_UART4: UART4 clock + * @arg RCC_APB1Periph_UART5: UART5 clock + * @arg RCC_APB1Periph_I2C1: I2C1 clock + * @arg RCC_APB1Periph_I2C2: I2C2 clock + * @arg RCC_APB1Periph_I2C3: I2C3 clock + * @arg RCC_APB1Periph_CAN1: CAN1 clock + * @arg RCC_APB1Periph_CAN2: CAN2 clock + * @arg RCC_APB1Periph_PWR: PWR clock + * @arg RCC_APB1Periph_DAC: DAC clock + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphClockLPModeCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB1LPENR |= RCC_APB1Periph; + } + else + { + RCC->APB1LPENR &= ~RCC_APB1Periph; + } +} + +/** + * @brief Enables or disables the APB2 peripheral clock during Low Power (Sleep) mode. + * @note Peripheral clock gating in SLEEP mode can be used to further reduce + * power consumption. + * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. + * @note By default, all peripheral clocks are enabled during SLEEP mode. + * @param RCC_APB2Periph: specifies the APB2 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_TIM1: TIM1 clock + * @arg RCC_APB2Periph_TIM8: TIM8 clock + * @arg RCC_APB2Periph_USART1: USART1 clock + * @arg RCC_APB2Periph_USART6: USART6 clock + * @arg RCC_APB2Periph_ADC1: ADC1 clock + * @arg RCC_APB2Periph_ADC2: ADC2 clock + * @arg RCC_APB2Periph_ADC3: ADC3 clock + * @arg RCC_APB2Periph_SDIO: SDIO clock + * @arg RCC_APB2Periph_SPI1: SPI1 clock + * @arg RCC_APB2Periph_SYSCFG: SYSCFG clock + * @arg RCC_APB2Periph_TIM9: TIM9 clock + * @arg RCC_APB2Periph_TIM10: TIM10 clock + * @arg RCC_APB2Periph_TIM11: TIM11 clock + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphClockLPModeCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB2LPENR |= RCC_APB2Periph; + } + else + { + RCC->APB2LPENR &= ~RCC_APB2Periph; + } +} + +/** + * @} + */ + +/** @defgroup RCC_Group4 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified RCC interrupts. + * @param RCC_IT: specifies the RCC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: main PLL ready interrupt + * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt + * @param NewState: new state of the specified RCC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_IT(RCC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Perform Byte access to RCC_CIR[14:8] bits to enable the selected interrupts */ + *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT; + } + else + { + /* Perform Byte access to RCC_CIR[14:8] bits to disable the selected interrupts */ + *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT; + } +} + +/** + * @brief Checks whether the specified RCC flag is set or not. + * @param RCC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready + * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready + * @arg RCC_FLAG_PLLRDY: main PLL clock ready + * @arg RCC_FLAG_PLLI2SRDY: PLLI2S clock ready + * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready + * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready + * @arg RCC_FLAG_BORRST: POR/PDR or BOR reset + * @arg RCC_FLAG_PINRST: Pin reset + * @arg RCC_FLAG_PORRST: POR/PDR reset + * @arg RCC_FLAG_SFTRST: Software reset + * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset + * @arg RCC_FLAG_WWDGRST: Window Watchdog reset + * @arg RCC_FLAG_LPWRRST: Low Power reset + * @retval The new state of RCC_FLAG (SET or RESET). + */ +FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG) +{ + uint32_t tmp = 0; + uint32_t statusreg = 0; + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_RCC_FLAG(RCC_FLAG)); + + /* Get the RCC register index */ + tmp = RCC_FLAG >> 5; + if (tmp == 1) /* The flag to check is in CR register */ + { + statusreg = RCC->CR; + } + else if (tmp == 2) /* The flag to check is in BDCR register */ + { + statusreg = RCC->BDCR; + } + else /* The flag to check is in CSR register */ + { + statusreg = RCC->CSR; + } + + /* Get the flag position */ + tmp = RCC_FLAG & FLAG_MASK; + if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the RCC reset flags. + * The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, + * RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST + * @param None + * @retval None + */ +void RCC_ClearFlag(void) +{ + /* Set RMVF bit to clear the reset flags */ + RCC->CSR |= RCC_CSR_RMVF; +} + +/** + * @brief Checks whether the specified RCC interrupt has occurred or not. + * @param RCC_IT: specifies the RCC interrupt source to check. + * This parameter can be one of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: main PLL ready interrupt + * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * @retval The new state of RCC_IT (SET or RESET). + */ +ITStatus RCC_GetITStatus(uint8_t RCC_IT) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_RCC_GET_IT(RCC_IT)); + + /* Check the status of the specified RCC interrupt */ + if ((RCC->CIR & RCC_IT) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the RCC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the RCC's interrupt pending bits. + * @param RCC_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: main PLL ready interrupt + * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * @retval None + */ +void RCC_ClearITPendingBit(uint8_t RCC_IT) +{ + /* Check the parameters */ + assert_param(IS_RCC_CLEAR_IT(RCC_IT)); + + /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt + pending bits */ + *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rng.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rng.c new file mode 100644 index 000000000..9f0ba059f --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rng.c @@ -0,0 +1,399 @@ +/** + ****************************************************************************** + * @file stm32f4xx_rng.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Random Number Generator (RNG) peripheral: + * - Initialization and Configuration + * - Get 32 bit Random number + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * 1. Enable The RNG controller clock using + * RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_RNG, ENABLE) function. + * + * 2. Activate the RNG peripheral using RNG_Cmd() function. + * + * 3. Wait until the 32 bit Random number Generator contains a valid + * random data (using polling/interrupt mode). For more details, + * refer to "Interrupts and flags management functions" module + * description. + * + * 4. Get the 32 bit Random number using RNG_GetRandomNumber() function + * + * 5. To get another 32 bit Random number, go to step 3. + * + * + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_rng.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup RNG + * @brief RNG driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup RNG_Private_Functions + * @{ + */ + +/** @defgroup RNG_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + This section provides functions allowing to + - Initialize the RNG peripheral + - Enable or disable the RNG peripheral + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the RNG peripheral registers to their default reset values. + * @param None + * @retval None + */ +void RNG_DeInit(void) +{ + /* Enable RNG reset state */ + RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_RNG, ENABLE); + + /* Release RNG from reset state */ + RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_RNG, DISABLE); +} + +/** + * @brief Enables or disables the RNG peripheral. + * @param NewState: new state of the RNG peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RNG_Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the RNG */ + RNG->CR |= RNG_CR_RNGEN; + } + else + { + /* Disable the RNG */ + RNG->CR &= ~RNG_CR_RNGEN; + } +} +/** + * @} + */ + +/** @defgroup RNG_Group2 Get 32 bit Random number function + * @brief Get 32 bit Random number function + * + +@verbatim + =============================================================================== + Get 32 bit Random number function + =============================================================================== + This section provides a function allowing to get the 32 bit Random number + + @note Before to call this function you have to wait till DRDY flag is set, + using RNG_GetFlagStatus(RNG_FLAG_DRDY) function. + +@endverbatim + * @{ + */ + + +/** + * @brief Returns a 32-bit random number. + * + * @note Before to call this function you have to wait till DRDY (data ready) + * flag is set, using RNG_GetFlagStatus(RNG_FLAG_DRDY) function. + * @note Each time the the Random number data is read (using RNG_GetRandomNumber() + * function), the RNG_FLAG_DRDY flag is automatically cleared. + * @note In the case of a seed error, the generation of random numbers is + * interrupted for as long as the SECS bit is '1'. If a number is + * available in the RNG_DR register, it must not be used because it may + * not have enough entropy. In this case, it is recommended to clear the + * SEIS bit(using RNG_ClearFlag(RNG_FLAG_SECS) function), then disable + * and enable the RNG peripheral (using RNG_Cmd() function) to + * reinitialize and restart the RNG. + * @note In the case of a clock error, the RNG is no more able to generate + * random numbers because the PLL48CLK clock is not correct. User have + * to check that the clock controller is correctly configured to provide + * the RNG clock and clear the CEIS bit (using RNG_ClearFlag(RNG_FLAG_CECS) + * function) . The clock error has no impact on the previously generated + * random numbers, and the RNG_DR register contents can be used. + * + * @param None + * @retval 32-bit random number. + */ +uint32_t RNG_GetRandomNumber(void) +{ + /* Return the 32 bit random number from the DR register */ + return RNG->DR; +} + + +/** + * @} + */ + +/** @defgroup RNG_Group3 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + + This section provides functions allowing to configure the RNG Interrupts and + to get the status and clear flags and Interrupts pending bits. + + The RNG provides 3 Interrupts sources and 3 Flags: + + Flags : + ---------- + 1. RNG_FLAG_DRDY : In the case of the RNG_DR register contains valid + random data. it is cleared by reading the valid data + (using RNG_GetRandomNumber() function). + + 2. RNG_FLAG_CECS : In the case of a seed error detection. + + 3. RNG_FLAG_SECS : In the case of a clock error detection. + + + Interrupts : + ------------ + if enabled, an RNG interrupt is pending : + + 1. In the case of the RNG_DR register contains valid random data. + This interrupt source is cleared once the RNG_DR register has been read + (using RNG_GetRandomNumber() function) until a new valid value is + computed. + + or + 2. In the case of a seed error : One of the following faulty sequences has + been detected: + - More than 64 consecutive bits at the same value (0 or 1) + - More than 32 consecutive alternance of 0 and 1 (0101010101...01) + This interrupt source is cleared using RNG_ClearITPendingBit(RNG_IT_SEI) + function. + + or + 3. In the case of a clock error : the PLL48CLK (RNG peripheral clock source) + was not correctly detected (fPLL48CLK< fHCLK/16). + This interrupt source is cleared using RNG_ClearITPendingBit(RNG_IT_CEI) + function. + @note In this case, User have to check that the clock controller is + correctly configured to provide the RNG clock. + + Managing the RNG controller events : + ------------------------------------ + The user should identify which mode will be used in his application to manage + the RNG controller events: Polling mode or Interrupt mode. + + 1. In the Polling Mode it is advised to use the following functions: + - RNG_GetFlagStatus() : to check if flags events occur. + - RNG_ClearFlag() : to clear the flags events. + + @note RNG_FLAG_DRDY can not be cleared by RNG_ClearFlag(). it is cleared only + by reading the Random number data. + + 2. In the Interrupt Mode it is advised to use the following functions: + - RNG_ITConfig() : to enable or disable the interrupt source. + - RNG_GetITStatus() : to check if Interrupt occurs. + - RNG_ClearITPendingBit() : to clear the Interrupt pending Bit + (corresponding Flag). + + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the RNG interrupt. + * @note The RNG provides 3 interrupt sources, + * - Computed data is ready event (DRDY), and + * - Seed error Interrupt (SEI) and + * - Clock error Interrupt (CEI), + * all these interrupts sources are enabled by setting the IE bit in + * CR register. However, each interrupt have its specific status bit + * (see RNG_GetITStatus() function) and clear bit except the DRDY event + * (see RNG_ClearITPendingBit() function). + * @param NewState: new state of the RNG interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RNG_ITConfig(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the RNG interrupt */ + RNG->CR |= RNG_CR_IE; + } + else + { + /* Disable the RNG interrupt */ + RNG->CR &= ~RNG_CR_IE; + } +} + +/** + * @brief Checks whether the specified RNG flag is set or not. + * @param RNG_FLAG: specifies the RNG flag to check. + * This parameter can be one of the following values: + * @arg RNG_FLAG_DRDY: Data Ready flag. + * @arg RNG_FLAG_CECS: Clock Error Current flag. + * @arg RNG_FLAG_SECS: Seed Error Current flag. + * @retval The new state of RNG_FLAG (SET or RESET). + */ +FlagStatus RNG_GetFlagStatus(uint8_t RNG_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RNG_GET_FLAG(RNG_FLAG)); + + /* Check the status of the specified RNG flag */ + if ((RNG->SR & RNG_FLAG) != (uint8_t)RESET) + { + /* RNG_FLAG is set */ + bitstatus = SET; + } + else + { + /* RNG_FLAG is reset */ + bitstatus = RESET; + } + /* Return the RNG_FLAG status */ + return bitstatus; +} + + +/** + * @brief Clears the RNG flags. + * @param RNG_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg RNG_FLAG_CECS: Clock Error Current flag. + * @arg RNG_FLAG_SECS: Seed Error Current flag. + * @note RNG_FLAG_DRDY can not be cleared by RNG_ClearFlag() function. + * This flag is cleared only by reading the Random number data (using + * RNG_GetRandomNumber() function). + * @retval None + */ +void RNG_ClearFlag(uint8_t RNG_FLAG) +{ + /* Check the parameters */ + assert_param(IS_RNG_CLEAR_FLAG(RNG_FLAG)); + /* Clear the selected RNG flags */ + RNG->SR = ~(uint32_t)(((uint32_t)RNG_FLAG) << 4); +} + +/** + * @brief Checks whether the specified RNG interrupt has occurred or not. + * @param RNG_IT: specifies the RNG interrupt source to check. + * This parameter can be one of the following values: + * @arg RNG_IT_CEI: Clock Error Interrupt. + * @arg RNG_IT_SEI: Seed Error Interrupt. + * @retval The new state of RNG_IT (SET or RESET). + */ +ITStatus RNG_GetITStatus(uint8_t RNG_IT) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RNG_GET_IT(RNG_IT)); + + /* Check the status of the specified RNG interrupt */ + if ((RNG->SR & RNG_IT) != (uint8_t)RESET) + { + /* RNG_IT is set */ + bitstatus = SET; + } + else + { + /* RNG_IT is reset */ + bitstatus = RESET; + } + /* Return the RNG_IT status */ + return bitstatus; +} + + +/** + * @brief Clears the RNG interrupt pending bit(s). + * @param RNG_IT: specifies the RNG interrupt pending bit(s) to clear. + * This parameter can be any combination of the following values: + * @arg RNG_IT_CEI: Clock Error Interrupt. + * @arg RNG_IT_SEI: Seed Error Interrupt. + * @retval None + */ +void RNG_ClearITPendingBit(uint8_t RNG_IT) +{ + /* Check the parameters */ + assert_param(IS_RNG_IT(RNG_IT)); + + /* Clear the selected RNG interrupt pending bit */ + RNG->SR = (uint8_t)~RNG_IT; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + + +/** + * @} + */ + + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rtc.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rtc.c new file mode 100644 index 000000000..159f0f37b --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rtc.c @@ -0,0 +1,2732 @@ +/** + ****************************************************************************** + * @file stm32f4xx_rtc.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Real-Time Clock (RTC) peripheral: + * - Initialization + * - Calendar (Time and Date) configuration + * - Alarms (Alarm A and Alarm B) configuration + * - WakeUp Timer configuration + * - Daylight Saving configuration + * - Output pin Configuration + * - Coarse digital Calibration configuration + * - Smooth digital Calibration configuration + * - TimeStamp configuration + * - Tampers configuration + * - Backup Data Registers configuration + * - Shift control synchronisation + * - RTC Tamper and TimeStamp Pins Selection and Output Type Config configuration + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * Backup Domain Operating Condition + * =================================================================== + * The real-time clock (RTC), the RTC backup registers, and the backup + * SRAM (BKP SRAM) can be powered from the VBAT voltage when the main + * VDD supply is powered off. + * To retain the content of the RTC backup registers, backup SRAM, + * and supply the RTC when VDD is turned off, VBAT pin can be connected + * to an optional standby voltage supplied by a battery or by another + * source. + * + * To allow the RTC to operate even when the main digital supply (VDD) + * is turned off, the VBAT pin powers the following blocks: + * 1 - The RTC + * 2 - The LSE oscillator + * 3 - The backup SRAM when the low power backup regulator is enabled + * 4 - PC13 to PC15 I/Os, plus PI8 I/O (when available) + * + * When the backup domain is supplied by VDD (analog switch connected + * to VDD), the following functions are available: + * 1 - PC14 and PC15 can be used as either GPIO or LSE pins + * 2 - PC13 can be used as a GPIO or as the RTC_AF1 pin + * 3 - PI8 can be used as a GPIO or as the RTC_AF2 pin + * + * When the backup domain is supplied by VBAT (analog switch connected + * to VBAT because VDD is not present), the following functions are available: + * 1 - PC14 and PC15 can be used as LSE pins only + * 2 - PC13 can be used as the RTC_AF1 pin + * 3 - PI8 can be used as the RTC_AF2 pin + * + * =================================================================== + * Backup Domain Reset + * =================================================================== + * The backup domain reset sets all RTC registers and the RCC_BDCR + * register to their reset values. The BKPSRAM is not affected by this + * reset. The only way of resetting the BKPSRAM is through the Flash + * interface by requesting a protection level change from 1 to 0. + * A backup domain reset is generated when one of the following events + * occurs: + * 1 - Software reset, triggered by setting the BDRST bit in the + * RCC Backup domain control register (RCC_BDCR). You can use the + * RCC_BackupResetCmd(). + * 2 - VDD or VBAT power on, if both supplies have previously been + * powered off. + * + * =================================================================== + * Backup Domain Access + * =================================================================== + * After reset, the backup domain (RTC registers, RTC backup data + * registers and backup SRAM) is protected against possible unwanted + * write accesses. + * To enable access to the RTC Domain and RTC registers, proceed as follows: + * - Enable the Power Controller (PWR) APB1 interface clock using the + * RCC_APB1PeriphClockCmd() function. + * - Enable access to RTC domain using the PWR_BackupAccessCmd() function. + * - Select the RTC clock source using the RCC_RTCCLKConfig() function. + * - Enable RTC Clock using the RCC_RTCCLKCmd() function. + * + * =================================================================== + * RTC Driver: how to use it + * =================================================================== + * - Enable the RTC domain access (see description in the section above) + * - Configure the RTC Prescaler (Asynchronous and Synchronous) and + * RTC hour format using the RTC_Init() function. + * + * Time and Date configuration + * =========================== + * - To configure the RTC Calendar (Time and Date) use the RTC_SetTime() + * and RTC_SetDate() functions. + * - To read the RTC Calendar, use the RTC_GetTime() and RTC_GetDate() + * functions. + * - Use the RTC_DayLightSavingConfig() function to add or sub one + * hour to the RTC Calendar. + * + * Alarm configuration + * =================== + * - To configure the RTC Alarm use the RTC_SetAlarm() function. + * - Enable the selected RTC Alarm using the RTC_AlarmCmd() function + * - To read the RTC Alarm, use the RTC_GetAlarm() function. + * - To read the RTC alarm SubSecond, use the RTC_GetAlarmSubSecond() function. + * + * RTC Wakeup configuration + * ======================== + * - Configure the RTC Wakeup Clock source use the RTC_WakeUpClockConfig() + * function. + * - Configure the RTC WakeUp Counter using the RTC_SetWakeUpCounter() + * function + * - Enable the RTC WakeUp using the RTC_WakeUpCmd() function + * - To read the RTC WakeUp Counter register, use the RTC_GetWakeUpCounter() + * function. + * + * Outputs configuration + * ===================== + * The RTC has 2 different outputs: + * - AFO_ALARM: this output is used to manage the RTC Alarm A, Alarm B + * and WaKeUp signals. + * To output the selected RTC signal on RTC_AF1 pin, use the + * RTC_OutputConfig() function. + * - AFO_CALIB: this output is 512Hz signal or 1Hz . + * To output the RTC Clock on RTC_AF1 pin, use the RTC_CalibOutputCmd() + * function. + * + * Smooth digital Calibration configuration + * ================================= + * - Configure the RTC Original Digital Calibration Value and the corresponding + * calibration cycle period (32s,16s and 8s) using the RTC_SmoothCalibConfig() + * function. + * + * Coarse digital Calibration configuration + * ================================= + * - Configure the RTC Coarse Calibration Value and the corresponding + * sign using the RTC_CoarseCalibConfig() function. + * - Enable the RTC Coarse Calibration using the RTC_CoarseCalibCmd() + * function + * + * TimeStamp configuration + * ======================= + * - Configure the RTC_AF1 trigger and enables the RTC TimeStamp + * using the RTC_TimeStampCmd() function. + * - To read the RTC TimeStamp Time and Date register, use the + * RTC_GetTimeStamp() function. + * - To read the RTC TimeStamp SubSecond register, use the + * RTC_GetTimeStampSubSecond() function. + * - The TAMPER1 alternate function can be mapped either to RTC_AF1(PC13) + * or RTC_AF2 (PI8) depending on the value of TAMP1INSEL bit in + * RTC_TAFCR register. You can use the RTC_TamperPinSelection() + * function to select the corresponding pin. + * + * Tamper configuration + * ==================== + * - Enable the RTC Tamper using the RTC_TamperCmd() function. + * - Configure the Tamper filter count using RTC_TamperFilterConfig() + * function. + * - Configure the RTC Tamper trigger Edge or Level according to the Tamper + * filter (if equal to 0 Edge else Level) value using the RTC_TamperConfig() function. + * - Configure the Tamper sampling frequency using RTC_TamperSamplingFreqConfig() + * function. + * - Configure the Tamper precharge or discharge duration using + * RTC_TamperPinsPrechargeDuration() function. + * - Enable the Tamper Pull-UP using RTC_TamperPullUpDisableCmd() function. + * - Enable the Time stamp on Tamper detection event using + * RTC_TSOnTamperDetecCmd() function. + * - The TIMESTAMP alternate function can be mapped to either RTC_AF1 + * or RTC_AF2 depending on the value of the TSINSEL bit in the + * RTC_TAFCR register. You can use the RTC_TimeStampPinSelection() + * function to select the corresponding pin. + * + * Backup Data Registers configuration + * =================================== + * - To write to the RTC Backup Data registers, use the RTC_WriteBackupRegister() + * function. + * - To read the RTC Backup Data registers, use the RTC_ReadBackupRegister() + * function. + * + * =================================================================== + * RTC and low power modes + * =================================================================== + * The MCU can be woken up from a low power mode by an RTC alternate + * function. + * The RTC alternate functions are the RTC alarms (Alarm A and Alarm B), + * RTC wakeup, RTC tamper event detection and RTC time stamp event detection. + * These RTC alternate functions can wake up the system from the Stop + * and Standby lowpower modes. + * The system can also wake up from low power modes without depending + * on an external interrupt (Auto-wakeup mode), by using the RTC alarm + * or the RTC wakeup events. + * The RTC provides a programmable time base for waking up from the + * Stop or Standby mode at regular intervals. + * Wakeup from STOP and Standby modes is possible only when the RTC + * clock source is LSE or LSI. + * + * =================================================================== + * Selection of RTC_AF1 alternate functions + * =================================================================== + * The RTC_AF1 pin (PC13) can be used for the following purposes: + * - AFO_ALARM output + * - AFO_CALIB output + * - AFI_TAMPER + * - AFI_TIMESTAMP + * + * +-------------------------------------------------------------------------------------------------------------+ + * | Pin |AFO_ALARM |AFO_CALIB |AFI_TAMPER |AFI_TIMESTAMP | TAMP1INSEL | TSINSEL |ALARMOUTTYPE | + * | configuration | ENABLED | ENABLED | ENABLED | ENABLED |TAMPER1 pin |TIMESTAMP pin | AFO_ALARM | + * | and function | | | | | selection | selection |Configuration | + * |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------| + * | Alarm out | | | | | Don't | Don't | | + * | output OD | 1 |Don't care|Don't care | Don't care | care | care | 0 | + * |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------| + * | Alarm out | | | | | Don't | Don't | | + * | output PP | 1 |Don't care|Don't care | Don't care | care | care | 1 | + * |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------| + * | Calibration out | | | | | Don't | Don't | | + * | output PP | 0 | 1 |Don't care | Don't care | care | care | Don't care | + * |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------| + * | TAMPER input | | | | | | Don't | | + * | floating | 0 | 0 | 1 | 0 | 0 | care | Don't care | + * |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------| + * | TIMESTAMP and | | | | | | | | + * | TAMPER input | 0 | 0 | 1 | 1 | 0 | 0 | Don't care | + * | floating | | | | | | | | + * |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------| + * | TIMESTAMP input | | | | | Don't | | | + * | floating | 0 | 0 | 0 | 1 | care | 0 | Don't care | + * |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------| + * | Standard GPIO | 0 | 0 | 0 | 0 | Don't care | Don't care | Don't care | + * +-------------------------------------------------------------------------------------------------------------+ + * + * + * =================================================================== + * Selection of RTC_AF2 alternate functions + * =================================================================== + * The RTC_AF2 pin (PI8) can be used for the following purposes: + * - AFI_TAMPER + * - AFI_TIMESTAMP + * + * +---------------------------------------------------------------------------------------+ + * | Pin |AFI_TAMPER |AFI_TIMESTAMP | TAMP1INSEL | TSINSEL |ALARMOUTTYPE | + * | configuration | ENABLED | ENABLED |TAMPER1 pin |TIMESTAMP pin | AFO_ALARM | + * | and function | | | selection | selection |Configuration | + * |-----------------|-----------|--------------|------------|--------------|--------------| + * | TAMPER input | | | | Don't | | + * | floating | 1 | 0 | 1 | care | Don't care | + * |-----------------|-----------|--------------|------------|--------------|--------------| + * | TIMESTAMP and | | | | | | + * | TAMPER input | 1 | 1 | 1 | 1 | Don't care | + * | floating | | | | | | + * |-----------------|-----------|--------------|------------|--------------|--------------| + * | TIMESTAMP input | | | Don't | | | + * | floating | 0 | 1 | care | 1 | Don't care | + * |-----------------|-----------|--------------|------------|--------------|--------------| + * | Standard GPIO | 0 | 0 | Don't care | Don't care | Don't care | + * +---------------------------------------------------------------------------------------+ + * + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_rtc.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup RTC + * @brief RTC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* Masks Definition */ +#define RTC_TR_RESERVED_MASK ((uint32_t)0x007F7F7F) +#define RTC_DR_RESERVED_MASK ((uint32_t)0x00FFFF3F) +#define RTC_INIT_MASK ((uint32_t)0xFFFFFFFF) +#define RTC_RSF_MASK ((uint32_t)0xFFFFFF5F) +#define RTC_FLAGS_MASK ((uint32_t)(RTC_FLAG_TSOVF | RTC_FLAG_TSF | RTC_FLAG_WUTF | \ + RTC_FLAG_ALRBF | RTC_FLAG_ALRAF | RTC_FLAG_INITF | \ + RTC_FLAG_RSF | RTC_FLAG_INITS | RTC_FLAG_WUTWF | \ + RTC_FLAG_ALRBWF | RTC_FLAG_ALRAWF | RTC_FLAG_TAMP1F )) + +#define INITMODE_TIMEOUT ((uint32_t) 0x00010000) +#define SYNCHRO_TIMEOUT ((uint32_t) 0x00020000) +#define RECALPF_TIMEOUT ((uint32_t) 0x00020000) +#define SHPF_TIMEOUT ((uint32_t) 0x00001000) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static uint8_t RTC_ByteToBcd2(uint8_t Value); +static uint8_t RTC_Bcd2ToByte(uint8_t Value); + +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup RTC_Private_Functions + * @{ + */ + +/** @defgroup RTC_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + + This section provide functions allowing to initialize and configure the RTC + Prescaler (Synchronous and Asynchronous), RTC Hour format, disable RTC registers + Write protection, enter and exit the RTC initialization mode, RTC registers + synchronization check and reference clock detection enable. + + 1. The RTC Prescaler is programmed to generate the RTC 1Hz time base. It is + split into 2 programmable prescalers to minimize power consumption. + - A 7-bit asynchronous prescaler and A 13-bit synchronous prescaler. + - When both prescalers are used, it is recommended to configure the asynchronous + prescaler to a high value to minimize consumption. + + 2. All RTC registers are Write protected. Writing to the RTC registers + is enabled by writing a key into the Write Protection register, RTC_WPR. + + 3. To Configure the RTC Calendar, user application should enter initialization + mode. In this mode, the calendar counter is stopped and its value can be + updated. When the initialization sequence is complete, the calendar restarts + counting after 4 RTCCLK cycles. + + 4. To read the calendar through the shadow registers after Calendar initialization, + calendar update or after wakeup from low power modes the software must first + clear the RSF flag. The software must then wait until it is set again before + reading the calendar, which means that the calendar registers have been + correctly copied into the RTC_TR and RTC_DR shadow registers. + The RTC_WaitForSynchro() function implements the above software sequence + (RSF clear and RSF check). + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the RTC registers to their default reset values. + * @note This function doesn't reset the RTC Clock source and RTC Backup Data + * registers. + * @param None + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC registers are deinitialized + * - ERROR: RTC registers are not deinitialized + */ +ErrorStatus RTC_DeInit(void) +{ + __IO uint32_t wutcounter = 0x00; + uint32_t wutwfstatus = 0x00; + ErrorStatus status = ERROR; + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + /* Reset TR, DR and CR registers */ + RTC->TR = (uint32_t)0x00000000; + RTC->DR = (uint32_t)0x00002101; + /* Reset All CR bits except CR[2:0] */ + RTC->CR &= (uint32_t)0x00000007; + + /* Wait till RTC WUTWF flag is set and if Time out is reached exit */ + do + { + wutwfstatus = RTC->ISR & RTC_ISR_WUTWF; + wutcounter++; + } while((wutcounter != INITMODE_TIMEOUT) && (wutwfstatus == 0x00)); + + if ((RTC->ISR & RTC_ISR_WUTWF) == RESET) + { + status = ERROR; + } + else + { + /* Reset all RTC CR register bits */ + RTC->CR &= (uint32_t)0x00000000; + RTC->WUTR = (uint32_t)0x0000FFFF; + RTC->PRER = (uint32_t)0x007F00FF; + RTC->CALIBR = (uint32_t)0x00000000; + RTC->ALRMAR = (uint32_t)0x00000000; + RTC->ALRMBR = (uint32_t)0x00000000; + + /* Reset ISR register and exit initialization mode */ + RTC->ISR = (uint32_t)0x00000000; + + /* Reset Tamper and alternate functions configuration register */ + RTC->TAFCR = 0x00000000; + + if(RTC_WaitForSynchro() == ERROR) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Initializes the RTC registers according to the specified parameters + * in RTC_InitStruct. + * @param RTC_InitStruct: pointer to a RTC_InitTypeDef structure that contains + * the configuration information for the RTC peripheral. + * @note The RTC Prescaler register is write protected and can be written in + * initialization mode only. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC registers are initialized + * - ERROR: RTC registers are not initialized + */ +ErrorStatus RTC_Init(RTC_InitTypeDef* RTC_InitStruct) +{ + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_HOUR_FORMAT(RTC_InitStruct->RTC_HourFormat)); + assert_param(IS_RTC_ASYNCH_PREDIV(RTC_InitStruct->RTC_AsynchPrediv)); + assert_param(IS_RTC_SYNCH_PREDIV(RTC_InitStruct->RTC_SynchPrediv)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + /* Clear RTC CR FMT Bit */ + RTC->CR &= ((uint32_t)~(RTC_CR_FMT)); + /* Set RTC_CR register */ + RTC->CR |= ((uint32_t)(RTC_InitStruct->RTC_HourFormat)); + + /* Configure the RTC PRER */ + RTC->PRER = (uint32_t)(RTC_InitStruct->RTC_SynchPrediv); + RTC->PRER |= (uint32_t)(RTC_InitStruct->RTC_AsynchPrediv << 16); + + /* Exit Initialization mode */ + RTC_ExitInitMode(); + + status = SUCCESS; + } + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Fills each RTC_InitStruct member with its default value. + * @param RTC_InitStruct: pointer to a RTC_InitTypeDef structure which will be + * initialized. + * @retval None + */ +void RTC_StructInit(RTC_InitTypeDef* RTC_InitStruct) +{ + /* Initialize the RTC_HourFormat member */ + RTC_InitStruct->RTC_HourFormat = RTC_HourFormat_24; + + /* Initialize the RTC_AsynchPrediv member */ + RTC_InitStruct->RTC_AsynchPrediv = (uint32_t)0x7F; + + /* Initialize the RTC_SynchPrediv member */ + RTC_InitStruct->RTC_SynchPrediv = (uint32_t)0xFF; +} + +/** + * @brief Enables or disables the RTC registers write protection. + * @note All the RTC registers are write protected except for RTC_ISR[13:8], + * RTC_TAFCR and RTC_BKPxR. + * @note Writing a wrong key reactivates the write protection. + * @note The protection mechanism is not affected by system reset. + * @param NewState: new state of the write protection. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_WriteProtectionCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + } + else + { + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + } +} + +/** + * @brief Enters the RTC Initialization mode. + * @note The RTC Initialization mode is write protected, use the + * RTC_WriteProtectionCmd(DISABLE) before calling this function. + * @param None + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC is in Init mode + * - ERROR: RTC is not in Init mode + */ +ErrorStatus RTC_EnterInitMode(void) +{ + __IO uint32_t initcounter = 0x00; + ErrorStatus status = ERROR; + uint32_t initstatus = 0x00; + + /* Check if the Initialization mode is set */ + if ((RTC->ISR & RTC_ISR_INITF) == (uint32_t)RESET) + { + /* Set the Initialization mode */ + RTC->ISR = (uint32_t)RTC_INIT_MASK; + + /* Wait till RTC is in INIT state and if Time out is reached exit */ + do + { + initstatus = RTC->ISR & RTC_ISR_INITF; + initcounter++; + } while((initcounter != INITMODE_TIMEOUT) && (initstatus == 0x00)); + + if ((RTC->ISR & RTC_ISR_INITF) != RESET) + { + status = SUCCESS; + } + else + { + status = ERROR; + } + } + else + { + status = SUCCESS; + } + + return (status); +} + +/** + * @brief Exits the RTC Initialization mode. + * @note When the initialization sequence is complete, the calendar restarts + * counting after 4 RTCCLK cycles. + * @note The RTC Initialization mode is write protected, use the + * RTC_WriteProtectionCmd(DISABLE) before calling this function. + * @param None + * @retval None + */ +void RTC_ExitInitMode(void) +{ + /* Exit Initialization mode */ + RTC->ISR &= (uint32_t)~RTC_ISR_INIT; +} + +/** + * @brief Waits until the RTC Time and Date registers (RTC_TR and RTC_DR) are + * synchronized with RTC APB clock. + * @note The RTC Resynchronization mode is write protected, use the + * RTC_WriteProtectionCmd(DISABLE) before calling this function. + * @note To read the calendar through the shadow registers after Calendar + * initialization, calendar update or after wakeup from low power modes + * the software must first clear the RSF flag. + * The software must then wait until it is set again before reading + * the calendar, which means that the calendar registers have been + * correctly copied into the RTC_TR and RTC_DR shadow registers. + * @param None + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC registers are synchronised + * - ERROR: RTC registers are not synchronised + */ +ErrorStatus RTC_WaitForSynchro(void) +{ + __IO uint32_t synchrocounter = 0; + ErrorStatus status = ERROR; + uint32_t synchrostatus = 0x00; + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Clear RSF flag */ + RTC->ISR &= (uint32_t)RTC_RSF_MASK; + + /* Wait the registers to be synchronised */ + do + { + synchrostatus = RTC->ISR & RTC_ISR_RSF; + synchrocounter++; + } while((synchrocounter != SYNCHRO_TIMEOUT) && (synchrostatus == 0x00)); + + if ((RTC->ISR & RTC_ISR_RSF) != RESET) + { + status = SUCCESS; + } + else + { + status = ERROR; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return (status); +} + +/** + * @brief Enables or disables the RTC reference clock detection. + * @param NewState: new state of the RTC reference clock. + * This parameter can be: ENABLE or DISABLE. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC reference clock detection is enabled + * - ERROR: RTC reference clock detection is disabled + */ +ErrorStatus RTC_RefClockCmd(FunctionalState NewState) +{ + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + if (NewState != DISABLE) + { + /* Enable the RTC reference clock detection */ + RTC->CR |= RTC_CR_REFCKON; + } + else + { + /* Disable the RTC reference clock detection */ + RTC->CR &= ~RTC_CR_REFCKON; + } + /* Exit Initialization mode */ + RTC_ExitInitMode(); + + status = SUCCESS; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Enables or Disables the Bypass Shadow feature. + * @note When the Bypass Shadow is enabled the calendar value are taken + * directly from the Calendar counter. + * @param NewState: new state of the Bypass Shadow feature. + * This parameter can be: ENABLE or DISABLE. + * @retval None +*/ +void RTC_BypassShadowCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + if (NewState != DISABLE) + { + /* Set the BYPSHAD bit */ + RTC->CR |= (uint8_t)RTC_CR_BYPSHAD; + } + else + { + /* Reset the BYPSHAD bit */ + RTC->CR &= (uint8_t)~RTC_CR_BYPSHAD; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @} + */ + +/** @defgroup RTC_Group2 Time and Date configuration functions + * @brief Time and Date configuration functions + * +@verbatim + =============================================================================== + Time and Date configuration functions + =============================================================================== + + This section provide functions allowing to program and read the RTC Calendar + (Time and Date). + +@endverbatim + * @{ + */ + +/** + * @brief Set the RTC current time. + * @param RTC_Format: specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_TimeStruct: pointer to a RTC_TimeTypeDef structure that contains + * the time configuration information for the RTC. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Time register is configured + * - ERROR: RTC Time register is not configured + */ +ErrorStatus RTC_SetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct) +{ + uint32_t tmpreg = 0; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + + if (RTC_Format == RTC_Format_BIN) + { + if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + assert_param(IS_RTC_HOUR12(RTC_TimeStruct->RTC_Hours)); + assert_param(IS_RTC_H12(RTC_TimeStruct->RTC_H12)); + } + else + { + RTC_TimeStruct->RTC_H12 = 0x00; + assert_param(IS_RTC_HOUR24(RTC_TimeStruct->RTC_Hours)); + } + assert_param(IS_RTC_MINUTES(RTC_TimeStruct->RTC_Minutes)); + assert_param(IS_RTC_SECONDS(RTC_TimeStruct->RTC_Seconds)); + } + else + { + if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + tmpreg = RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Hours); + assert_param(IS_RTC_HOUR12(tmpreg)); + assert_param(IS_RTC_H12(RTC_TimeStruct->RTC_H12)); + } + else + { + RTC_TimeStruct->RTC_H12 = 0x00; + assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Hours))); + } + assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Minutes))); + assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Seconds))); + } + + /* Check the input parameters format */ + if (RTC_Format != RTC_Format_BIN) + { + tmpreg = (((uint32_t)(RTC_TimeStruct->RTC_Hours) << 16) | \ + ((uint32_t)(RTC_TimeStruct->RTC_Minutes) << 8) | \ + ((uint32_t)RTC_TimeStruct->RTC_Seconds) | \ + ((uint32_t)(RTC_TimeStruct->RTC_H12) << 16)); + } + else + { + tmpreg = (uint32_t)(((uint32_t)RTC_ByteToBcd2(RTC_TimeStruct->RTC_Hours) << 16) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_TimeStruct->RTC_Minutes) << 8) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_TimeStruct->RTC_Seconds)) | \ + (((uint32_t)RTC_TimeStruct->RTC_H12) << 16)); + } + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + /* Set the RTC_TR register */ + RTC->TR = (uint32_t)(tmpreg & RTC_TR_RESERVED_MASK); + + /* Exit Initialization mode */ + RTC_ExitInitMode(); + + if(RTC_WaitForSynchro() == ERROR) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + + } + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Fills each RTC_TimeStruct member with its default value + * (Time = 00h:00min:00sec). + * @param RTC_TimeStruct: pointer to a RTC_TimeTypeDef structure which will be + * initialized. + * @retval None + */ +void RTC_TimeStructInit(RTC_TimeTypeDef* RTC_TimeStruct) +{ + /* Time = 00h:00min:00sec */ + RTC_TimeStruct->RTC_H12 = RTC_H12_AM; + RTC_TimeStruct->RTC_Hours = 0; + RTC_TimeStruct->RTC_Minutes = 0; + RTC_TimeStruct->RTC_Seconds = 0; +} + +/** + * @brief Get the RTC current Time. + * @param RTC_Format: specifies the format of the returned parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_TimeStruct: pointer to a RTC_TimeTypeDef structure that will + * contain the returned current time configuration. + * @retval None + */ +void RTC_GetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + + /* Get the RTC_TR register */ + tmpreg = (uint32_t)(RTC->TR & RTC_TR_RESERVED_MASK); + + /* Fill the structure fields with the read parameters */ + RTC_TimeStruct->RTC_Hours = (uint8_t)((tmpreg & (RTC_TR_HT | RTC_TR_HU)) >> 16); + RTC_TimeStruct->RTC_Minutes = (uint8_t)((tmpreg & (RTC_TR_MNT | RTC_TR_MNU)) >>8); + RTC_TimeStruct->RTC_Seconds = (uint8_t)(tmpreg & (RTC_TR_ST | RTC_TR_SU)); + RTC_TimeStruct->RTC_H12 = (uint8_t)((tmpreg & (RTC_TR_PM)) >> 16); + + /* Check the input parameters format */ + if (RTC_Format == RTC_Format_BIN) + { + /* Convert the structure parameters to Binary format */ + RTC_TimeStruct->RTC_Hours = (uint8_t)RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Hours); + RTC_TimeStruct->RTC_Minutes = (uint8_t)RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Minutes); + RTC_TimeStruct->RTC_Seconds = (uint8_t)RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Seconds); + } +} + +/** + * @brief Gets the RTC current Calendar Subseconds value. + * @note This function freeze the Time and Date registers after reading the + * SSR register. + * @param None + * @retval RTC current Calendar Subseconds value. + */ +uint32_t RTC_GetSubSecond(void) +{ + uint32_t tmpreg = 0; + + /* Get subseconds values from the correspondent registers*/ + tmpreg = (uint32_t)(RTC->SSR); + + /* Read DR register to unfroze calendar registers */ + (void) (RTC->DR); + + return (tmpreg); +} + +/** + * @brief Set the RTC current date. + * @param RTC_Format: specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_DateStruct: pointer to a RTC_DateTypeDef structure that contains + * the date configuration information for the RTC. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Date register is configured + * - ERROR: RTC Date register is not configured + */ +ErrorStatus RTC_SetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct) +{ + uint32_t tmpreg = 0; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + + if ((RTC_Format == RTC_Format_BIN) && ((RTC_DateStruct->RTC_Month & 0x10) == 0x10)) + { + RTC_DateStruct->RTC_Month = (RTC_DateStruct->RTC_Month & (uint32_t)~(0x10)) + 0x0A; + } + if (RTC_Format == RTC_Format_BIN) + { + assert_param(IS_RTC_YEAR(RTC_DateStruct->RTC_Year)); + assert_param(IS_RTC_MONTH(RTC_DateStruct->RTC_Month)); + assert_param(IS_RTC_DATE(RTC_DateStruct->RTC_Date)); + } + else + { + assert_param(IS_RTC_YEAR(RTC_Bcd2ToByte(RTC_DateStruct->RTC_Year))); + tmpreg = RTC_Bcd2ToByte(RTC_DateStruct->RTC_Month); + assert_param(IS_RTC_MONTH(tmpreg)); + tmpreg = RTC_Bcd2ToByte(RTC_DateStruct->RTC_Date); + assert_param(IS_RTC_DATE(tmpreg)); + } + assert_param(IS_RTC_WEEKDAY(RTC_DateStruct->RTC_WeekDay)); + + /* Check the input parameters format */ + if (RTC_Format != RTC_Format_BIN) + { + tmpreg = ((((uint32_t)RTC_DateStruct->RTC_Year) << 16) | \ + (((uint32_t)RTC_DateStruct->RTC_Month) << 8) | \ + ((uint32_t)RTC_DateStruct->RTC_Date) | \ + (((uint32_t)RTC_DateStruct->RTC_WeekDay) << 13)); + } + else + { + tmpreg = (((uint32_t)RTC_ByteToBcd2(RTC_DateStruct->RTC_Year) << 16) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_DateStruct->RTC_Month) << 8) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_DateStruct->RTC_Date)) | \ + ((uint32_t)RTC_DateStruct->RTC_WeekDay << 13)); + } + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + /* Set the RTC_DR register */ + RTC->DR = (uint32_t)(tmpreg & RTC_DR_RESERVED_MASK); + + /* Exit Initialization mode */ + RTC_ExitInitMode(); + + if(RTC_WaitForSynchro() == ERROR) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Fills each RTC_DateStruct member with its default value + * (Monday, January 01 xx00). + * @param RTC_DateStruct: pointer to a RTC_DateTypeDef structure which will be + * initialized. + * @retval None + */ +void RTC_DateStructInit(RTC_DateTypeDef* RTC_DateStruct) +{ + /* Monday, January 01 xx00 */ + RTC_DateStruct->RTC_WeekDay = RTC_Weekday_Monday; + RTC_DateStruct->RTC_Date = 1; + RTC_DateStruct->RTC_Month = RTC_Month_January; + RTC_DateStruct->RTC_Year = 0; +} + +/** + * @brief Get the RTC current date. + * @param RTC_Format: specifies the format of the returned parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_DateStruct: pointer to a RTC_DateTypeDef structure that will + * contain the returned current date configuration. + * @retval None + */ +void RTC_GetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + + /* Get the RTC_TR register */ + tmpreg = (uint32_t)(RTC->DR & RTC_DR_RESERVED_MASK); + + /* Fill the structure fields with the read parameters */ + RTC_DateStruct->RTC_Year = (uint8_t)((tmpreg & (RTC_DR_YT | RTC_DR_YU)) >> 16); + RTC_DateStruct->RTC_Month = (uint8_t)((tmpreg & (RTC_DR_MT | RTC_DR_MU)) >> 8); + RTC_DateStruct->RTC_Date = (uint8_t)(tmpreg & (RTC_DR_DT | RTC_DR_DU)); + RTC_DateStruct->RTC_WeekDay = (uint8_t)((tmpreg & (RTC_DR_WDU)) >> 13); + + /* Check the input parameters format */ + if (RTC_Format == RTC_Format_BIN) + { + /* Convert the structure parameters to Binary format */ + RTC_DateStruct->RTC_Year = (uint8_t)RTC_Bcd2ToByte(RTC_DateStruct->RTC_Year); + RTC_DateStruct->RTC_Month = (uint8_t)RTC_Bcd2ToByte(RTC_DateStruct->RTC_Month); + RTC_DateStruct->RTC_Date = (uint8_t)RTC_Bcd2ToByte(RTC_DateStruct->RTC_Date); + } +} + +/** + * @} + */ + +/** @defgroup RTC_Group3 Alarms configuration functions + * @brief Alarms (Alarm A and Alarm B) configuration functions + * +@verbatim + =============================================================================== + Alarms (Alarm A and Alarm B) configuration functions + =============================================================================== + + This section provide functions allowing to program and read the RTC Alarms. + +@endverbatim + * @{ + */ + +/** + * @brief Set the specified RTC Alarm. + * @note The Alarm register can only be written when the corresponding Alarm + * is disabled (Use the RTC_AlarmCmd(DISABLE)). + * @param RTC_Format: specifies the format of the returned parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_Alarm: specifies the alarm to be configured. + * This parameter can be one of the following values: + * @arg RTC_Alarm_A: to select Alarm A + * @arg RTC_Alarm_B: to select Alarm B + * @param RTC_AlarmStruct: pointer to a RTC_AlarmTypeDef structure that + * contains the alarm configuration parameters. + * @retval None + */ +void RTC_SetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + assert_param(IS_RTC_ALARM(RTC_Alarm)); + assert_param(IS_ALARM_MASK(RTC_AlarmStruct->RTC_AlarmMask)); + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_SEL(RTC_AlarmStruct->RTC_AlarmDateWeekDaySel)); + + if (RTC_Format == RTC_Format_BIN) + { + if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + assert_param(IS_RTC_HOUR12(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours)); + assert_param(IS_RTC_H12(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12)); + } + else + { + RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = 0x00; + assert_param(IS_RTC_HOUR24(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours)); + } + assert_param(IS_RTC_MINUTES(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes)); + assert_param(IS_RTC_SECONDS(RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds)); + + if(RTC_AlarmStruct->RTC_AlarmDateWeekDaySel == RTC_AlarmDateWeekDaySel_Date) + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(RTC_AlarmStruct->RTC_AlarmDateWeekDay)); + } + else + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(RTC_AlarmStruct->RTC_AlarmDateWeekDay)); + } + } + else + { + if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + tmpreg = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours); + assert_param(IS_RTC_HOUR12(tmpreg)); + assert_param(IS_RTC_H12(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12)); + } + else + { + RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = 0x00; + assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours))); + } + + assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes))); + assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds))); + + if(RTC_AlarmStruct->RTC_AlarmDateWeekDaySel == RTC_AlarmDateWeekDaySel_Date) + { + tmpreg = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmDateWeekDay); + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(tmpreg)); + } + else + { + tmpreg = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmDateWeekDay); + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(tmpreg)); + } + } + + /* Check the input parameters format */ + if (RTC_Format != RTC_Format_BIN) + { + tmpreg = (((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours) << 16) | \ + ((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes) << 8) | \ + ((uint32_t)RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds) | \ + ((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12) << 16) | \ + ((uint32_t)(RTC_AlarmStruct->RTC_AlarmDateWeekDay) << 24) | \ + ((uint32_t)RTC_AlarmStruct->RTC_AlarmDateWeekDaySel) | \ + ((uint32_t)RTC_AlarmStruct->RTC_AlarmMask)); + } + else + { + tmpreg = (((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours) << 16) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes) << 8) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds)) | \ + ((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12) << 16) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmDateWeekDay) << 24) | \ + ((uint32_t)RTC_AlarmStruct->RTC_AlarmDateWeekDaySel) | \ + ((uint32_t)RTC_AlarmStruct->RTC_AlarmMask)); + } + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Configure the Alarm register */ + if (RTC_Alarm == RTC_Alarm_A) + { + RTC->ALRMAR = (uint32_t)tmpreg; + } + else + { + RTC->ALRMBR = (uint32_t)tmpreg; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Fills each RTC_AlarmStruct member with its default value + * (Time = 00h:00mn:00sec / Date = 1st day of the month/Mask = + * all fields are masked). + * @param RTC_AlarmStruct: pointer to a @ref RTC_AlarmTypeDef structure which + * will be initialized. + * @retval None + */ +void RTC_AlarmStructInit(RTC_AlarmTypeDef* RTC_AlarmStruct) +{ + /* Alarm Time Settings : Time = 00h:00mn:00sec */ + RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = RTC_H12_AM; + RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours = 0; + RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes = 0; + RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds = 0; + + /* Alarm Date Settings : Date = 1st day of the month */ + RTC_AlarmStruct->RTC_AlarmDateWeekDaySel = RTC_AlarmDateWeekDaySel_Date; + RTC_AlarmStruct->RTC_AlarmDateWeekDay = 1; + + /* Alarm Masks Settings : Mask = all fields are not masked */ + RTC_AlarmStruct->RTC_AlarmMask = RTC_AlarmMask_None; +} + +/** + * @brief Get the RTC Alarm value and masks. + * @param RTC_Format: specifies the format of the output parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_Alarm: specifies the alarm to be read. + * This parameter can be one of the following values: + * @arg RTC_Alarm_A: to select Alarm A + * @arg RTC_Alarm_B: to select Alarm B + * @param RTC_AlarmStruct: pointer to a RTC_AlarmTypeDef structure that will + * contains the output alarm configuration values. + * @retval None + */ +void RTC_GetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + assert_param(IS_RTC_ALARM(RTC_Alarm)); + + /* Get the RTC_ALRMxR register */ + if (RTC_Alarm == RTC_Alarm_A) + { + tmpreg = (uint32_t)(RTC->ALRMAR); + } + else + { + tmpreg = (uint32_t)(RTC->ALRMBR); + } + + /* Fill the structure with the read parameters */ + RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours = (uint32_t)((tmpreg & (RTC_ALRMAR_HT | \ + RTC_ALRMAR_HU)) >> 16); + RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes = (uint32_t)((tmpreg & (RTC_ALRMAR_MNT | \ + RTC_ALRMAR_MNU)) >> 8); + RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds = (uint32_t)(tmpreg & (RTC_ALRMAR_ST | \ + RTC_ALRMAR_SU)); + RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = (uint32_t)((tmpreg & RTC_ALRMAR_PM) >> 16); + RTC_AlarmStruct->RTC_AlarmDateWeekDay = (uint32_t)((tmpreg & (RTC_ALRMAR_DT | RTC_ALRMAR_DU)) >> 24); + RTC_AlarmStruct->RTC_AlarmDateWeekDaySel = (uint32_t)(tmpreg & RTC_ALRMAR_WDSEL); + RTC_AlarmStruct->RTC_AlarmMask = (uint32_t)(tmpreg & RTC_AlarmMask_All); + + if (RTC_Format == RTC_Format_BIN) + { + RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours = RTC_Bcd2ToByte(RTC_AlarmStruct-> \ + RTC_AlarmTime.RTC_Hours); + RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes = RTC_Bcd2ToByte(RTC_AlarmStruct-> \ + RTC_AlarmTime.RTC_Minutes); + RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds = RTC_Bcd2ToByte(RTC_AlarmStruct-> \ + RTC_AlarmTime.RTC_Seconds); + RTC_AlarmStruct->RTC_AlarmDateWeekDay = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmDateWeekDay); + } +} + +/** + * @brief Enables or disables the specified RTC Alarm. + * @param RTC_Alarm: specifies the alarm to be configured. + * This parameter can be any combination of the following values: + * @arg RTC_Alarm_A: to select Alarm A + * @arg RTC_Alarm_B: to select Alarm B + * @param NewState: new state of the specified alarm. + * This parameter can be: ENABLE or DISABLE. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Alarm is enabled/disabled + * - ERROR: RTC Alarm is not enabled/disabled + */ +ErrorStatus RTC_AlarmCmd(uint32_t RTC_Alarm, FunctionalState NewState) +{ + __IO uint32_t alarmcounter = 0x00; + uint32_t alarmstatus = 0x00; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_CMD_ALARM(RTC_Alarm)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Configure the Alarm state */ + if (NewState != DISABLE) + { + RTC->CR |= (uint32_t)RTC_Alarm; + + status = SUCCESS; + } + else + { + /* Disable the Alarm in RTC_CR register */ + RTC->CR &= (uint32_t)~RTC_Alarm; + + /* Wait till RTC ALRxWF flag is set and if Time out is reached exit */ + do + { + alarmstatus = RTC->ISR & (RTC_Alarm >> 8); + alarmcounter++; + } while((alarmcounter != INITMODE_TIMEOUT) && (alarmstatus == 0x00)); + + if ((RTC->ISR & (RTC_Alarm >> 8)) == RESET) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Configure the RTC AlarmA/B Subseconds value and mask.* + * @note This function is performed only when the Alarm is disabled. + * @param RTC_Alarm: specifies the alarm to be configured. + * This parameter can be one of the following values: + * @arg RTC_Alarm_A: to select Alarm A + * @arg RTC_Alarm_B: to select Alarm B + * @param RTC_AlarmSubSecondValue: specifies the Subseconds value. + * This parameter can be a value from 0 to 0x00007FFF. + * @param RTC_AlarmSubSecondMask: specifies the Subseconds Mask. + * This parameter can be any combination of the following values: + * @arg RTC_AlarmSubSecondMask_All : All Alarm SS fields are masked. + * There is no comparison on sub seconds for Alarm. + * @arg RTC_AlarmSubSecondMask_SS14_1 : SS[14:1] are don't care in Alarm comparison. + * Only SS[0] is compared + * @arg RTC_AlarmSubSecondMask_SS14_2 : SS[14:2] are don't care in Alarm comparison. + * Only SS[1:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_3 : SS[14:3] are don't care in Alarm comparison. + * Only SS[2:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_4 : SS[14:4] are don't care in Alarm comparison. + * Only SS[3:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_5 : SS[14:5] are don't care in Alarm comparison. + * Only SS[4:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_6 : SS[14:6] are don't care in Alarm comparison. + * Only SS[5:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_7 : SS[14:7] are don't care in Alarm comparison. + * Only SS[6:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_8 : SS[14:8] are don't care in Alarm comparison. + * Only SS[7:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_9 : SS[14:9] are don't care in Alarm comparison. + * Only SS[8:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_10: SS[14:10] are don't care in Alarm comparison. + * Only SS[9:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_11: SS[14:11] are don't care in Alarm comparison. + * Only SS[10:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_12: SS[14:12] are don't care in Alarm comparison. + * Only SS[11:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_13: SS[14:13] are don't care in Alarm comparison. + * Only SS[12:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14 : SS[14] is don't care in Alarm comparison. + * Only SS[13:0] are compared + * @arg RTC_AlarmSubSecondMask_None : SS[14:0] are compared and must match + * to activate alarm + * @retval None + */ +void RTC_AlarmSubSecondConfig(uint32_t RTC_Alarm, uint32_t RTC_AlarmSubSecondValue, uint32_t RTC_AlarmSubSecondMask) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_ALARM(RTC_Alarm)); + assert_param(IS_RTC_ALARM_SUB_SECOND_VALUE(RTC_AlarmSubSecondValue)); + assert_param(IS_RTC_ALARM_SUB_SECOND_MASK(RTC_AlarmSubSecondMask)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Configure the Alarm A or Alarm B SubSecond registers */ + tmpreg = (uint32_t) (uint32_t)(RTC_AlarmSubSecondValue) | (uint32_t)(RTC_AlarmSubSecondMask); + + if (RTC_Alarm == RTC_Alarm_A) + { + /* Configure the AlarmA SubSecond register */ + RTC->ALRMASSR = tmpreg; + } + else + { + /* Configure the Alarm B SubSecond register */ + RTC->ALRMBSSR = tmpreg; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + +} + +/** + * @brief Gets the RTC Alarm Subseconds value. + * @param RTC_Alarm: specifies the alarm to be read. + * This parameter can be one of the following values: + * @arg RTC_Alarm_A: to select Alarm A + * @arg RTC_Alarm_B: to select Alarm B + * @param None + * @retval RTC Alarm Subseconds value. + */ +uint32_t RTC_GetAlarmSubSecond(uint32_t RTC_Alarm) +{ + uint32_t tmpreg = 0; + + /* Get the RTC_ALRMxR register */ + if (RTC_Alarm == RTC_Alarm_A) + { + tmpreg = (uint32_t)((RTC->ALRMASSR) & RTC_ALRMASSR_SS); + } + else + { + tmpreg = (uint32_t)((RTC->ALRMBSSR) & RTC_ALRMBSSR_SS); + } + + return (tmpreg); +} + +/** + * @} + */ + +/** @defgroup RTC_Group4 WakeUp Timer configuration functions + * @brief WakeUp Timer configuration functions + * +@verbatim + =============================================================================== + WakeUp Timer configuration functions + =============================================================================== + + This section provide functions allowing to program and read the RTC WakeUp. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the RTC Wakeup clock source. + * @note The WakeUp Clock source can only be changed when the RTC WakeUp + * is disabled (Use the RTC_WakeUpCmd(DISABLE)). + * @param RTC_WakeUpClock: Wakeup Clock source. + * This parameter can be one of the following values: + * @arg RTC_WakeUpClock_RTCCLK_Div16: RTC Wakeup Counter Clock = RTCCLK/16 + * @arg RTC_WakeUpClock_RTCCLK_Div8: RTC Wakeup Counter Clock = RTCCLK/8 + * @arg RTC_WakeUpClock_RTCCLK_Div4: RTC Wakeup Counter Clock = RTCCLK/4 + * @arg RTC_WakeUpClock_RTCCLK_Div2: RTC Wakeup Counter Clock = RTCCLK/2 + * @arg RTC_WakeUpClock_CK_SPRE_16bits: RTC Wakeup Counter Clock = CK_SPRE + * @arg RTC_WakeUpClock_CK_SPRE_17bits: RTC Wakeup Counter Clock = CK_SPRE + * @retval None + */ +void RTC_WakeUpClockConfig(uint32_t RTC_WakeUpClock) +{ + /* Check the parameters */ + assert_param(IS_RTC_WAKEUP_CLOCK(RTC_WakeUpClock)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Clear the Wakeup Timer clock source bits in CR register */ + RTC->CR &= (uint32_t)~RTC_CR_WUCKSEL; + + /* Configure the clock source */ + RTC->CR |= (uint32_t)RTC_WakeUpClock; + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Configures the RTC Wakeup counter. + * @note The RTC WakeUp counter can only be written when the RTC WakeUp + * is disabled (Use the RTC_WakeUpCmd(DISABLE)). + * @param RTC_WakeUpCounter: specifies the WakeUp counter. + * This parameter can be a value from 0x0000 to 0xFFFF. + * @retval None + */ +void RTC_SetWakeUpCounter(uint32_t RTC_WakeUpCounter) +{ + /* Check the parameters */ + assert_param(IS_RTC_WAKEUP_COUNTER(RTC_WakeUpCounter)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Configure the Wakeup Timer counter */ + RTC->WUTR = (uint32_t)RTC_WakeUpCounter; + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Returns the RTC WakeUp timer counter value. + * @param None + * @retval The RTC WakeUp Counter value. + */ +uint32_t RTC_GetWakeUpCounter(void) +{ + /* Get the counter value */ + return ((uint32_t)(RTC->WUTR & RTC_WUTR_WUT)); +} + +/** + * @brief Enables or Disables the RTC WakeUp timer. + * @param NewState: new state of the WakeUp timer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +ErrorStatus RTC_WakeUpCmd(FunctionalState NewState) +{ + __IO uint32_t wutcounter = 0x00; + uint32_t wutwfstatus = 0x00; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + if (NewState != DISABLE) + { + /* Enable the Wakeup Timer */ + RTC->CR |= (uint32_t)RTC_CR_WUTE; + status = SUCCESS; + } + else + { + /* Disable the Wakeup Timer */ + RTC->CR &= (uint32_t)~RTC_CR_WUTE; + /* Wait till RTC WUTWF flag is set and if Time out is reached exit */ + do + { + wutwfstatus = RTC->ISR & RTC_ISR_WUTWF; + wutcounter++; + } while((wutcounter != INITMODE_TIMEOUT) && (wutwfstatus == 0x00)); + + if ((RTC->ISR & RTC_ISR_WUTWF) == RESET) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @} + */ + +/** @defgroup RTC_Group5 Daylight Saving configuration functions + * @brief Daylight Saving configuration functions + * +@verbatim + =============================================================================== + Daylight Saving configuration functions + =============================================================================== + + This section provide functions allowing to configure the RTC DayLight Saving. + +@endverbatim + * @{ + */ + +/** + * @brief Adds or substract one hour from the current time. + * @param RTC_DayLightSaveOperation: the value of hour adjustment. + * This parameter can be one of the following values: + * @arg RTC_DayLightSaving_SUB1H: Substract one hour (winter time) + * @arg RTC_DayLightSaving_ADD1H: Add one hour (summer time) + * @param RTC_StoreOperation: Specifies the value to be written in the BCK bit + * in CR register to store the operation. + * This parameter can be one of the following values: + * @arg RTC_StoreOperation_Reset: BCK Bit Reset + * @arg RTC_StoreOperation_Set: BCK Bit Set + * @retval None + */ +void RTC_DayLightSavingConfig(uint32_t RTC_DayLightSaving, uint32_t RTC_StoreOperation) +{ + /* Check the parameters */ + assert_param(IS_RTC_DAYLIGHT_SAVING(RTC_DayLightSaving)); + assert_param(IS_RTC_STORE_OPERATION(RTC_StoreOperation)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Clear the bits to be configured */ + RTC->CR &= (uint32_t)~(RTC_CR_BCK); + + /* Configure the RTC_CR register */ + RTC->CR |= (uint32_t)(RTC_DayLightSaving | RTC_StoreOperation); + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Returns the RTC Day Light Saving stored operation. + * @param None + * @retval RTC Day Light Saving stored operation. + * - RTC_StoreOperation_Reset + * - RTC_StoreOperation_Set + */ +uint32_t RTC_GetStoreOperation(void) +{ + return (RTC->CR & RTC_CR_BCK); +} + +/** + * @} + */ + +/** @defgroup RTC_Group6 Output pin Configuration function + * @brief Output pin Configuration function + * +@verbatim + =============================================================================== + Output pin Configuration function + =============================================================================== + + This section provide functions allowing to configure the RTC Output source. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the RTC output source (AFO_ALARM). + * @param RTC_Output: Specifies which signal will be routed to the RTC output. + * This parameter can be one of the following values: + * @arg RTC_Output_Disable: No output selected + * @arg RTC_Output_AlarmA: signal of AlarmA mapped to output + * @arg RTC_Output_AlarmB: signal of AlarmB mapped to output + * @arg RTC_Output_WakeUp: signal of WakeUp mapped to output + * @param RTC_OutputPolarity: Specifies the polarity of the output signal. + * This parameter can be one of the following: + * @arg RTC_OutputPolarity_High: The output pin is high when the + * ALRAF/ALRBF/WUTF is high (depending on OSEL) + * @arg RTC_OutputPolarity_Low: The output pin is low when the + * ALRAF/ALRBF/WUTF is high (depending on OSEL) + * @retval None + */ +void RTC_OutputConfig(uint32_t RTC_Output, uint32_t RTC_OutputPolarity) +{ + /* Check the parameters */ + assert_param(IS_RTC_OUTPUT(RTC_Output)); + assert_param(IS_RTC_OUTPUT_POL(RTC_OutputPolarity)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Clear the bits to be configured */ + RTC->CR &= (uint32_t)~(RTC_CR_OSEL | RTC_CR_POL); + + /* Configure the output selection and polarity */ + RTC->CR |= (uint32_t)(RTC_Output | RTC_OutputPolarity); + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @} + */ + +/** @defgroup RTC_Group7 Digital Calibration configuration functions + * @brief Coarse Calibration configuration functions + * +@verbatim + =============================================================================== + Digital Calibration configuration functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the Coarse calibration parameters. + * @param RTC_CalibSign: specifies the sign of the coarse calibration value. + * This parameter can be one of the following values: + * @arg RTC_CalibSign_Positive: The value sign is positive + * @arg RTC_CalibSign_Negative: The value sign is negative + * @param Value: value of coarse calibration expressed in ppm (coded on 5 bits). + * + * @note This Calibration value should be between 0 and 63 when using negative + * sign with a 2-ppm step. + * + * @note This Calibration value should be between 0 and 126 when using positive + * sign with a 4-ppm step. + * + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Coarse calibration are initialized + * - ERROR: RTC Coarse calibration are not initialized + */ +ErrorStatus RTC_CoarseCalibConfig(uint32_t RTC_CalibSign, uint32_t Value) +{ + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_CALIB_SIGN(RTC_CalibSign)); + assert_param(IS_RTC_CALIB_VALUE(Value)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + /* Set the coarse calibration value */ + RTC->CALIBR = (uint32_t)(RTC_CalibSign | Value); + /* Exit Initialization mode */ + RTC_ExitInitMode(); + + status = SUCCESS; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Enables or disables the Coarse calibration process. + * @param NewState: new state of the Coarse calibration. + * This parameter can be: ENABLE or DISABLE. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Coarse calibration are enabled/disabled + * - ERROR: RTC Coarse calibration are not enabled/disabled + */ +ErrorStatus RTC_CoarseCalibCmd(FunctionalState NewState) +{ + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + if (NewState != DISABLE) + { + /* Enable the Coarse Calibration */ + RTC->CR |= (uint32_t)RTC_CR_DCE; + } + else + { + /* Disable the Coarse Calibration */ + RTC->CR &= (uint32_t)~RTC_CR_DCE; + } + /* Exit Initialization mode */ + RTC_ExitInitMode(); + + status = SUCCESS; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Enables or disables the RTC clock to be output through the relative pin. + * @param NewState: new state of the digital calibration Output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_CalibOutputCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + if (NewState != DISABLE) + { + /* Enable the RTC clock output */ + RTC->CR |= (uint32_t)RTC_CR_COE; + } + else + { + /* Disable the RTC clock output */ + RTC->CR &= (uint32_t)~RTC_CR_COE; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Configure the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz). + * @param RTC_CalibOutput : Select the Calibration output Selection . + * This parameter can be one of the following values: + * @arg RTC_CalibOutput_512Hz: A signal has a regular waveform at 512Hz. + * @arg RTC_CalibOutput_1Hz : A signal has a regular waveform at 1Hz. + * @retval None +*/ +void RTC_CalibOutputConfig(uint32_t RTC_CalibOutput) +{ + /* Check the parameters */ + assert_param(IS_RTC_CALIB_OUTPUT(RTC_CalibOutput)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /*clear flags before config*/ + RTC->CR &= (uint32_t)~(RTC_CR_COSEL); + + /* Configure the RTC_CR register */ + RTC->CR |= (uint32_t)RTC_CalibOutput; + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Configures the Smooth Calibration Settings. + * @param RTC_SmoothCalibPeriod : Select the Smooth Calibration Period. + * This parameter can be can be one of the following values: + * @arg RTC_SmoothCalibPeriod_32sec : The smooth calibration periode is 32s. + * @arg RTC_SmoothCalibPeriod_16sec : The smooth calibration periode is 16s. + * @arg RTC_SmoothCalibPeriod_8sec : The smooth calibartion periode is 8s. + * @param RTC_SmoothCalibPlusPulses : Select to Set or reset the CALP bit. + * This parameter can be one of the following values: + * @arg RTC_SmoothCalibPlusPulses_Set : Add one RTCCLK puls every 2**11 pulses. + * @arg RTC_SmoothCalibPlusPulses_Reset: No RTCCLK pulses are added. + * @param RTC_SmouthCalibMinusPulsesValue: Select the value of CALM[8:0] bits. + * This parameter can be one any value from 0 to 0x000001FF. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Calib registers are configured + * - ERROR: RTC Calib registers are not configured +*/ +ErrorStatus RTC_SmoothCalibConfig(uint32_t RTC_SmoothCalibPeriod, + uint32_t RTC_SmoothCalibPlusPulses, + uint32_t RTC_SmouthCalibMinusPulsesValue) +{ + ErrorStatus status = ERROR; + uint32_t recalpfcount = 0; + + /* Check the parameters */ + assert_param(IS_RTC_SMOOTH_CALIB_PERIOD(RTC_SmoothCalibPeriod)); + assert_param(IS_RTC_SMOOTH_CALIB_PLUS(RTC_SmoothCalibPlusPulses)); + assert_param(IS_RTC_SMOOTH_CALIB_MINUS(RTC_SmouthCalibMinusPulsesValue)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* check if a calibration is pending*/ + if ((RTC->ISR & RTC_ISR_RECALPF) != RESET) + { + /* wait until the Calibration is completed*/ + while (((RTC->ISR & RTC_ISR_RECALPF) != RESET) && (recalpfcount != RECALPF_TIMEOUT)) + { + recalpfcount++; + } + } + + /* check if the calibration pending is completed or if there is no calibration operation at all*/ + if ((RTC->ISR & RTC_ISR_RECALPF) == RESET) + { + /* Configure the Smooth calibration settings */ + RTC->CALR = (uint32_t)((uint32_t)RTC_SmoothCalibPeriod | (uint32_t)RTC_SmoothCalibPlusPulses | (uint32_t)RTC_SmouthCalibMinusPulsesValue); + + status = SUCCESS; + } + else + { + status = ERROR; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return (ErrorStatus)(status); +} + +/** + * @} + */ + + +/** @defgroup RTC_Group8 TimeStamp configuration functions + * @brief TimeStamp configuration functions + * +@verbatim + =============================================================================== + TimeStamp configuration functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or Disables the RTC TimeStamp functionality with the + * specified time stamp pin stimulating edge. + * @param RTC_TimeStampEdge: Specifies the pin edge on which the TimeStamp is + * activated. + * This parameter can be one of the following: + * @arg RTC_TimeStampEdge_Rising: the Time stamp event occurs on the rising + * edge of the related pin. + * @arg RTC_TimeStampEdge_Falling: the Time stamp event occurs on the + * falling edge of the related pin. + * @param NewState: new state of the TimeStamp. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_TimeStampCmd(uint32_t RTC_TimeStampEdge, FunctionalState NewState) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_TIMESTAMP_EDGE(RTC_TimeStampEdge)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Get the RTC_CR register and clear the bits to be configured */ + tmpreg = (uint32_t)(RTC->CR & (uint32_t)~(RTC_CR_TSEDGE | RTC_CR_TSE)); + + /* Get the new configuration */ + if (NewState != DISABLE) + { + tmpreg |= (uint32_t)(RTC_TimeStampEdge | RTC_CR_TSE); + } + else + { + tmpreg |= (uint32_t)(RTC_TimeStampEdge); + } + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Configure the Time Stamp TSEDGE and Enable bits */ + RTC->CR = (uint32_t)tmpreg; + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Get the RTC TimeStamp value and masks. + * @param RTC_Format: specifies the format of the output parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_StampTimeStruct: pointer to a RTC_TimeTypeDef structure that will + * contains the TimeStamp time values. + * @param RTC_StampDateStruct: pointer to a RTC_DateTypeDef structure that will + * contains the TimeStamp date values. + * @retval None + */ +void RTC_GetTimeStamp(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_StampTimeStruct, + RTC_DateTypeDef* RTC_StampDateStruct) +{ + uint32_t tmptime = 0, tmpdate = 0; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + + /* Get the TimeStamp time and date registers values */ + tmptime = (uint32_t)(RTC->TSTR & RTC_TR_RESERVED_MASK); + tmpdate = (uint32_t)(RTC->TSDR & RTC_DR_RESERVED_MASK); + + /* Fill the Time structure fields with the read parameters */ + RTC_StampTimeStruct->RTC_Hours = (uint8_t)((tmptime & (RTC_TR_HT | RTC_TR_HU)) >> 16); + RTC_StampTimeStruct->RTC_Minutes = (uint8_t)((tmptime & (RTC_TR_MNT | RTC_TR_MNU)) >> 8); + RTC_StampTimeStruct->RTC_Seconds = (uint8_t)(tmptime & (RTC_TR_ST | RTC_TR_SU)); + RTC_StampTimeStruct->RTC_H12 = (uint8_t)((tmptime & (RTC_TR_PM)) >> 16); + + /* Fill the Date structure fields with the read parameters */ + RTC_StampDateStruct->RTC_Year = 0; + RTC_StampDateStruct->RTC_Month = (uint8_t)((tmpdate & (RTC_DR_MT | RTC_DR_MU)) >> 8); + RTC_StampDateStruct->RTC_Date = (uint8_t)(tmpdate & (RTC_DR_DT | RTC_DR_DU)); + RTC_StampDateStruct->RTC_WeekDay = (uint8_t)((tmpdate & (RTC_DR_WDU)) >> 13); + + /* Check the input parameters format */ + if (RTC_Format == RTC_Format_BIN) + { + /* Convert the Time structure parameters to Binary format */ + RTC_StampTimeStruct->RTC_Hours = (uint8_t)RTC_Bcd2ToByte(RTC_StampTimeStruct->RTC_Hours); + RTC_StampTimeStruct->RTC_Minutes = (uint8_t)RTC_Bcd2ToByte(RTC_StampTimeStruct->RTC_Minutes); + RTC_StampTimeStruct->RTC_Seconds = (uint8_t)RTC_Bcd2ToByte(RTC_StampTimeStruct->RTC_Seconds); + + /* Convert the Date structure parameters to Binary format */ + RTC_StampDateStruct->RTC_Month = (uint8_t)RTC_Bcd2ToByte(RTC_StampDateStruct->RTC_Month); + RTC_StampDateStruct->RTC_Date = (uint8_t)RTC_Bcd2ToByte(RTC_StampDateStruct->RTC_Date); + RTC_StampDateStruct->RTC_WeekDay = (uint8_t)RTC_Bcd2ToByte(RTC_StampDateStruct->RTC_WeekDay); + } +} + +/** + * @brief Get the RTC timestamp Subseconds value. + * @param None + * @retval RTC current timestamp Subseconds value. + */ +uint32_t RTC_GetTimeStampSubSecond(void) +{ + /* Get timestamp subseconds values from the correspondent registers */ + return (uint32_t)(RTC->TSSSR); +} + +/** + * @} + */ + +/** @defgroup RTC_Group9 Tampers configuration functions + * @brief Tampers configuration functions + * +@verbatim + =============================================================================== + Tampers configuration functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the select Tamper pin edge. + * @param RTC_Tamper: Selected tamper pin. + * This parameter can be RTC_Tamper_1. + * @param RTC_TamperTrigger: Specifies the trigger on the tamper pin that + * stimulates tamper event. + * This parameter can be one of the following values: + * @arg RTC_TamperTrigger_RisingEdge: Rising Edge of the tamper pin causes tamper event. + * @arg RTC_TamperTrigger_FallingEdge: Falling Edge of the tamper pin causes tamper event. + * @arg RTC_TamperTrigger_LowLevel: Low Level of the tamper pin causes tamper event. + * @arg RTC_TamperTrigger_HighLevel: High Level of the tamper pin causes tamper event. + * @retval None + */ +void RTC_TamperTriggerConfig(uint32_t RTC_Tamper, uint32_t RTC_TamperTrigger) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER(RTC_Tamper)); + assert_param(IS_RTC_TAMPER_TRIGGER(RTC_TamperTrigger)); + + if (RTC_TamperTrigger == RTC_TamperTrigger_RisingEdge) + { + /* Configure the RTC_TAFCR register */ + RTC->TAFCR &= (uint32_t)((uint32_t)~(RTC_Tamper << 1)); + } + else + { + /* Configure the RTC_TAFCR register */ + RTC->TAFCR |= (uint32_t)(RTC_Tamper << 1); + } +} + +/** + * @brief Enables or Disables the Tamper detection. + * @param RTC_Tamper: Selected tamper pin. + * This parameter can be RTC_Tamper_1. + * @param NewState: new state of the tamper pin. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_TamperCmd(uint32_t RTC_Tamper, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER(RTC_Tamper)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected Tamper pin */ + RTC->TAFCR |= (uint32_t)RTC_Tamper; + } + else + { + /* Disable the selected Tamper pin */ + RTC->TAFCR &= (uint32_t)~RTC_Tamper; + } +} + +/** + * @brief Configures the Tampers Filter. + * @param RTC_TamperFilter: Specifies the tampers filter. + * This parameter can be one of the following values: + * @arg RTC_TamperFilter_Disable: Tamper filter is disabled. + * @arg RTC_TamperFilter_2Sample: Tamper is activated after 2 consecutive + * samples at the active level + * @arg RTC_TamperFilter_4Sample: Tamper is activated after 4 consecutive + * samples at the active level + * @arg RTC_TamperFilter_8Sample: Tamper is activated after 8 consecutive + * samples at the active level + * @retval None + */ +void RTC_TamperFilterConfig(uint32_t RTC_TamperFilter) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER_FILTER(RTC_TamperFilter)); + + /* Clear TAMPFLT[1:0] bits in the RTC_TAFCR register */ + RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPFLT); + + /* Configure the RTC_TAFCR register */ + RTC->TAFCR |= (uint32_t)RTC_TamperFilter; +} + +/** + * @brief Configures the Tampers Sampling Frequency. + * @param RTC_TamperSamplingFreq: Specifies the tampers Sampling Frequency. + * This parameter can be one of the following values: + * @arg RTC_TamperSamplingFreq_RTCCLK_Div32768: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 32768 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div16384: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 16384 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div8192: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 8192 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div4096: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 4096 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div2048: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 2048 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div1024: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 1024 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div512: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 512 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div256: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 256 + * @retval None + */ +void RTC_TamperSamplingFreqConfig(uint32_t RTC_TamperSamplingFreq) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER_SAMPLING_FREQ(RTC_TamperSamplingFreq)); + + /* Clear TAMPFREQ[2:0] bits in the RTC_TAFCR register */ + RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPFREQ); + + /* Configure the RTC_TAFCR register */ + RTC->TAFCR |= (uint32_t)RTC_TamperSamplingFreq; +} + +/** + * @brief Configures the Tampers Pins input Precharge Duration. + * @param RTC_TamperPrechargeDuration: Specifies the Tampers Pins input + * Precharge Duration. + * This parameter can be one of the following values: + * @arg RTC_TamperPrechargeDuration_1RTCCLK: Tamper pins are pre-charged before sampling during 1 RTCCLK cycle + * @arg RTC_TamperPrechargeDuration_2RTCCLK: Tamper pins are pre-charged before sampling during 2 RTCCLK cycle + * @arg RTC_TamperPrechargeDuration_4RTCCLK: Tamper pins are pre-charged before sampling during 4 RTCCLK cycle + * @arg RTC_TamperPrechargeDuration_8RTCCLK: Tamper pins are pre-charged before sampling during 8 RTCCLK cycle + * @retval None + */ +void RTC_TamperPinsPrechargeDuration(uint32_t RTC_TamperPrechargeDuration) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER_PRECHARGE_DURATION(RTC_TamperPrechargeDuration)); + + /* Clear TAMPPRCH[1:0] bits in the RTC_TAFCR register */ + RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPPRCH); + + /* Configure the RTC_TAFCR register */ + RTC->TAFCR |= (uint32_t)RTC_TamperPrechargeDuration; +} + +/** + * @brief Enables or Disables the TimeStamp on Tamper Detection Event. + * @note The timestamp is valid even the TSE bit in tamper control register + * is reset. + * @param NewState: new state of the timestamp on tamper event. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_TimeStampOnTamperDetectionCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Save timestamp on tamper detection event */ + RTC->TAFCR |= (uint32_t)RTC_TAFCR_TAMPTS; + } + else + { + /* Tamper detection does not cause a timestamp to be saved */ + RTC->TAFCR &= (uint32_t)~RTC_TAFCR_TAMPTS; + } +} + +/** + * @brief Enables or Disables the Precharge of Tamper pin. + * @param NewState: new state of tamper pull up. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_TamperPullUpCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable precharge of the selected Tamper pin */ + RTC->TAFCR &= (uint32_t)~RTC_TAFCR_TAMPPUDIS; + } + else + { + /* Disable precharge of the selected Tamper pin */ + RTC->TAFCR |= (uint32_t)RTC_TAFCR_TAMPPUDIS; + } +} + +/** + * @} + */ + +/** @defgroup RTC_Group10 Backup Data Registers configuration functions + * @brief Backup Data Registers configuration functions + * +@verbatim + =============================================================================== + Backup Data Registers configuration functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Writes a data in a specified RTC Backup data register. + * @param RTC_BKP_DR: RTC Backup data Register number. + * This parameter can be: RTC_BKP_DRx where x can be from 0 to 19 to + * specify the register. + * @param Data: Data to be written in the specified RTC Backup data register. + * @retval None + */ +void RTC_WriteBackupRegister(uint32_t RTC_BKP_DR, uint32_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_RTC_BKP(RTC_BKP_DR)); + + tmp = RTC_BASE + 0x50; + tmp += (RTC_BKP_DR * 4); + + /* Write the specified register */ + *(__IO uint32_t *)tmp = (uint32_t)Data; +} + +/** + * @brief Reads data from the specified RTC Backup data Register. + * @param RTC_BKP_DR: RTC Backup data Register number. + * This parameter can be: RTC_BKP_DRx where x can be from 0 to 19 to + * specify the register. + * @retval None + */ +uint32_t RTC_ReadBackupRegister(uint32_t RTC_BKP_DR) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_RTC_BKP(RTC_BKP_DR)); + + tmp = RTC_BASE + 0x50; + tmp += (RTC_BKP_DR * 4); + + /* Read the specified register */ + return (*(__IO uint32_t *)tmp); +} + +/** + * @} + */ + +/** @defgroup RTC_Group11 RTC Tamper and TimeStamp Pins Selection and Output Type Config configuration functions + * @brief RTC Tamper and TimeStamp Pins Selection and Output Type Config + * configuration functions + * +@verbatim + =============================================================================== + RTC Tamper and TimeStamp Pins Selection and Output Type Config configuration + functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Selects the RTC Tamper Pin. + * @param RTC_TamperPin: specifies the RTC Tamper Pin. + * This parameter can be one of the following values: + * @arg RTC_TamperPin_PC13: PC13 is selected as RTC Tamper Pin. + * @arg RTC_TamperPin_PI8: PI8 is selected as RTC Tamper Pin. + * @retval None + */ +void RTC_TamperPinSelection(uint32_t RTC_TamperPin) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER_PIN(RTC_TamperPin)); + + RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPINSEL); + RTC->TAFCR |= (uint32_t)(RTC_TamperPin); +} + +/** + * @brief Selects the RTC TimeStamp Pin. + * @param RTC_TimeStampPin: specifies the RTC TimeStamp Pin. + * This parameter can be one of the following values: + * @arg RTC_TimeStampPin_PC13: PC13 is selected as RTC TimeStamp Pin. + * @arg RTC_TimeStampPin_PI8: PI8 is selected as RTC TimeStamp Pin. + * @retval None + */ +void RTC_TimeStampPinSelection(uint32_t RTC_TimeStampPin) +{ + /* Check the parameters */ + assert_param(IS_RTC_TIMESTAMP_PIN(RTC_TimeStampPin)); + + RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TSINSEL); + RTC->TAFCR |= (uint32_t)(RTC_TimeStampPin); +} + +/** + * @brief Configures the RTC Output Pin mode. + * @param RTC_OutputType: specifies the RTC Output (PC13) pin mode. + * This parameter can be one of the following values: + * @arg RTC_OutputType_OpenDrain: RTC Output (PC13) is configured in + * Open Drain mode. + * @arg RTC_OutputType_PushPull: RTC Output (PC13) is configured in + * Push Pull mode. + * @retval None + */ +void RTC_OutputTypeConfig(uint32_t RTC_OutputType) +{ + /* Check the parameters */ + assert_param(IS_RTC_OUTPUT_TYPE(RTC_OutputType)); + + RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_ALARMOUTTYPE); + RTC->TAFCR |= (uint32_t)(RTC_OutputType); +} + +/** + * @} + */ + +/** @defgroup RTC_Group12 Shift control synchronisation functions + * @brief Shift control synchronisation functions + * +@verbatim + =============================================================================== + Shift control synchronisation functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the Synchronization Shift Control Settings. + * @note When REFCKON is set, firmware must not write to Shift control register + * @param RTC_ShiftAdd1S : Select to add or not 1 second to the time Calendar. + * This parameter can be one of the following values : + * @arg RTC_ShiftAdd1S_Set : Add one second to the clock calendar. + * @arg RTC_ShiftAdd1S_Reset: No effect. + * @param RTC_ShiftSubFS: Select the number of Second Fractions to Substitute. + * This parameter can be one any value from 0 to 0x7FFF. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Shift registers are configured + * - ERROR: RTC Shift registers are not configured +*/ +ErrorStatus RTC_SynchroShiftConfig(uint32_t RTC_ShiftAdd1S, uint32_t RTC_ShiftSubFS) +{ + ErrorStatus status = ERROR; + uint32_t shpfcount = 0; + + /* Check the parameters */ + assert_param(IS_RTC_SHIFT_ADD1S(RTC_ShiftAdd1S)); + assert_param(IS_RTC_SHIFT_SUBFS(RTC_ShiftSubFS)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Check if a Shift is pending*/ + if ((RTC->ISR & RTC_ISR_SHPF) != RESET) + { + /* Wait until the shift is completed*/ + while (((RTC->ISR & RTC_ISR_SHPF) != RESET) && (shpfcount != SHPF_TIMEOUT)) + { + shpfcount++; + } + } + + /* Check if the Shift pending is completed or if there is no Shift operation at all*/ + if ((RTC->ISR & RTC_ISR_SHPF) == RESET) + { + /* check if the reference clock detection is disabled */ + if((RTC->CR & RTC_CR_REFCKON) == RESET) + { + /* Configure the Shift settings */ + RTC->SHIFTR = (uint32_t)(uint32_t)(RTC_ShiftSubFS) | (uint32_t)(RTC_ShiftAdd1S); + + if(RTC_WaitForSynchro() == ERROR) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + else + { + status = ERROR; + } + } + else + { + status = ERROR; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return (ErrorStatus)(status); +} + +/** + * @} + */ + +/** @defgroup RTC_Group13 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + All RTC interrupts are connected to the EXTI controller. + + - To enable the RTC Alarm interrupt, the following sequence is required: + - Configure and enable the EXTI Line 17 in interrupt mode and select the rising + edge sensitivity using the EXTI_Init() function. + - Configure and enable the RTC_Alarm IRQ channel in the NVIC using the NVIC_Init() + function. + - Configure the RTC to generate RTC alarms (Alarm A and/or Alarm B) using + the RTC_SetAlarm() and RTC_AlarmCmd() functions. + + - To enable the RTC Wakeup interrupt, the following sequence is required: + - Configure and enable the EXTI Line 22 in interrupt mode and select the rising + edge sensitivity using the EXTI_Init() function. + - Configure and enable the RTC_WKUP IRQ channel in the NVIC using the NVIC_Init() + function. + - Configure the RTC to generate the RTC wakeup timer event using the + RTC_WakeUpClockConfig(), RTC_SetWakeUpCounter() and RTC_WakeUpCmd() functions. + + - To enable the RTC Tamper interrupt, the following sequence is required: + - Configure and enable the EXTI Line 21 in interrupt mode and select the rising + edge sensitivity using the EXTI_Init() function. + - Configure and enable the TAMP_STAMP IRQ channel in the NVIC using the NVIC_Init() + function. + - Configure the RTC to detect the RTC tamper event using the + RTC_TamperTriggerConfig() and RTC_TamperCmd() functions. + + - To enable the RTC TimeStamp interrupt, the following sequence is required: + - Configure and enable the EXTI Line 21 in interrupt mode and select the rising + edge sensitivity using the EXTI_Init() function. + - Configure and enable the TAMP_STAMP IRQ channel in the NVIC using the NVIC_Init() + function. + - Configure the RTC to detect the RTC time-stamp event using the + RTC_TimeStampCmd() functions. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified RTC interrupts. + * @param RTC_IT: specifies the RTC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg RTC_IT_TS: Time Stamp interrupt mask + * @arg RTC_IT_WUT: WakeUp Timer interrupt mask + * @arg RTC_IT_ALRB: Alarm B interrupt mask + * @arg RTC_IT_ALRA: Alarm A interrupt mask + * @arg RTC_IT_TAMP: Tamper event interrupt mask + * @param NewState: new state of the specified RTC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_ITConfig(uint32_t RTC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RTC_CONFIG_IT(RTC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + if (NewState != DISABLE) + { + /* Configure the Interrupts in the RTC_CR register */ + RTC->CR |= (uint32_t)(RTC_IT & ~RTC_TAFCR_TAMPIE); + /* Configure the Tamper Interrupt in the RTC_TAFCR */ + RTC->TAFCR |= (uint32_t)(RTC_IT & RTC_TAFCR_TAMPIE); + } + else + { + /* Configure the Interrupts in the RTC_CR register */ + RTC->CR &= (uint32_t)~(RTC_IT & (uint32_t)~RTC_TAFCR_TAMPIE); + /* Configure the Tamper Interrupt in the RTC_TAFCR */ + RTC->TAFCR &= (uint32_t)~(RTC_IT & RTC_TAFCR_TAMPIE); + } + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Checks whether the specified RTC flag is set or not. + * @param RTC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg RTC_FLAG_TAMP1F: Tamper 1 event flag + * @arg RTC_FLAG_TSOVF: Time Stamp OverFlow flag + * @arg RTC_FLAG_TSF: Time Stamp event flag + * @arg RTC_FLAG_WUTF: WakeUp Timer flag + * @arg RTC_FLAG_ALRBF: Alarm B flag + * @arg RTC_FLAG_ALRAF: Alarm A flag + * @arg RTC_FLAG_INITF: Initialization mode flag + * @arg RTC_FLAG_RSF: Registers Synchronized flag + * @arg RTC_FLAG_INITS: Registers Configured flag + * @arg RTC_FLAG_WUTWF: WakeUp Timer Write flag + * @arg RTC_FLAG_ALRBWF: Alarm B Write flag + * @arg RTC_FLAG_ALRAWF: Alarm A write flag + * @retval The new state of RTC_FLAG (SET or RESET). + */ +FlagStatus RTC_GetFlagStatus(uint32_t RTC_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_GET_FLAG(RTC_FLAG)); + + /* Get all the flags */ + tmpreg = (uint32_t)(RTC->ISR & RTC_FLAGS_MASK); + + /* Return the status of the flag */ + if ((tmpreg & RTC_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the RTC's pending flags. + * @param RTC_FLAG: specifies the RTC flag to clear. + * This parameter can be any combination of the following values: + * @arg RTC_FLAG_TAMP1F: Tamper 1 event flag + * @arg RTC_FLAG_TSOVF: Time Stamp Overflow flag + * @arg RTC_FLAG_TSF: Time Stamp event flag + * @arg RTC_FLAG_WUTF: WakeUp Timer flag + * @arg RTC_FLAG_ALRBF: Alarm B flag + * @arg RTC_FLAG_ALRAF: Alarm A flag + * @arg RTC_FLAG_RSF: Registers Synchronized flag + * @retval None + */ +void RTC_ClearFlag(uint32_t RTC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG)); + + /* Clear the Flags in the RTC_ISR register */ + RTC->ISR = (uint32_t)((uint32_t)(~((RTC_FLAG | RTC_ISR_INIT)& 0x0000FFFF) | (uint32_t)(RTC->ISR & RTC_ISR_INIT))); +} + +/** + * @brief Checks whether the specified RTC interrupt has occurred or not. + * @param RTC_IT: specifies the RTC interrupt source to check. + * This parameter can be one of the following values: + * @arg RTC_IT_TS: Time Stamp interrupt + * @arg RTC_IT_WUT: WakeUp Timer interrupt + * @arg RTC_IT_ALRB: Alarm B interrupt + * @arg RTC_IT_ALRA: Alarm A interrupt + * @arg RTC_IT_TAMP1: Tamper 1 event interrupt + * @retval The new state of RTC_IT (SET or RESET). + */ +ITStatus RTC_GetITStatus(uint32_t RTC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpreg = 0, enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_RTC_GET_IT(RTC_IT)); + + /* Get the TAMPER Interrupt enable bit and pending bit */ + tmpreg = (uint32_t)(RTC->TAFCR & (RTC_TAFCR_TAMPIE)); + + /* Get the Interrupt enable Status */ + enablestatus = (uint32_t)((RTC->CR & RTC_IT) | (tmpreg & (RTC_IT >> 15))); + + /* Get the Interrupt pending bit */ + tmpreg = (uint32_t)((RTC->ISR & (uint32_t)(RTC_IT >> 4))); + + /* Get the status of the Interrupt */ + if ((enablestatus != (uint32_t)RESET) && ((tmpreg & 0x0000FFFF) != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the RTC's interrupt pending bits. + * @param RTC_IT: specifies the RTC interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg RTC_IT_TS: Time Stamp interrupt + * @arg RTC_IT_WUT: WakeUp Timer interrupt + * @arg RTC_IT_ALRB: Alarm B interrupt + * @arg RTC_IT_ALRA: Alarm A interrupt + * @arg RTC_IT_TAMP1: Tamper 1 event interrupt + * @retval None + */ +void RTC_ClearITPendingBit(uint32_t RTC_IT) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_CLEAR_IT(RTC_IT)); + + /* Get the RTC_ISR Interrupt pending bits mask */ + tmpreg = (uint32_t)(RTC_IT >> 4); + + /* Clear the interrupt pending bits in the RTC_ISR register */ + RTC->ISR = (uint32_t)((uint32_t)(~((tmpreg | RTC_ISR_INIT)& 0x0000FFFF) | (uint32_t)(RTC->ISR & RTC_ISR_INIT))); +} + +/** + * @} + */ + +/** + * @brief Converts a 2 digit decimal to BCD format. + * @param Value: Byte to be converted. + * @retval Converted byte + */ +static uint8_t RTC_ByteToBcd2(uint8_t Value) +{ + uint8_t bcdhigh = 0; + + while (Value >= 10) + { + bcdhigh++; + Value -= 10; + } + + return ((uint8_t)(bcdhigh << 4) | Value); +} + +/** + * @brief Convert from 2 digit BCD to Binary. + * @param Value: BCD value to be converted. + * @retval Converted word + */ +static uint8_t RTC_Bcd2ToByte(uint8_t Value) +{ + uint8_t tmp = 0; + tmp = ((uint8_t)(Value & (uint8_t)0xF0) >> (uint8_t)0x4) * 10; + return (tmp + (Value & (uint8_t)0x0F)); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sdio.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sdio.c new file mode 100644 index 000000000..24a6c5ef2 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sdio.c @@ -0,0 +1,1004 @@ +/** + ****************************************************************************** + * @file stm32f4xx_sdio.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Secure digital input/output interface (SDIO) + * peripheral: + * - Initialization and Configuration + * - Command path state machine (CPSM) management + * - Data path state machine (DPSM) management + * - SDIO IO Cards mode management + * - CE-ATA mode management + * - DMA transfers management + * - Interrupts and flags management + * + * @verbatim + * + * + * =================================================================== + * How to use this driver + * =================================================================== + * 1. The SDIO clock (SDIOCLK = 48 MHz) is coming from a specific output + * of PLL (PLL48CLK). Before to start working with SDIO peripheral + * make sure that the PLL is well configured. + * The SDIO peripheral uses two clock signals: + * - SDIO adapter clock (SDIOCLK = 48 MHz) + * - APB2 bus clock (PCLK2) + * PCLK2 and SDIO_CK clock frequencies must respect the following condition: + * Frequenc(PCLK2) >= (3 / 8 x Frequency(SDIO_CK)) + * + * 2. Enable peripheral clock using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SDIO, ENABLE). + * + * 3. According to the SDIO mode, enable the GPIO clocks using + * RCC_AHB1PeriphClockCmd() function. + * The I/O can be one of the following configurations: + * - 1-bit data length: SDIO_CMD, SDIO_CK and D0. + * - 4-bit data length: SDIO_CMD, SDIO_CK and D[3:0]. + * - 8-bit data length: SDIO_CMD, SDIO_CK and D[7:0]. + * + * 4. Peripheral's alternate function: + * - Connect the pin to the desired peripherals' Alternate + * Function (AF) using GPIO_PinAFConfig() function + * - Configure the desired pin in alternate function by: + * GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF + * - Select the type, pull-up/pull-down and output speed via + * GPIO_PuPd, GPIO_OType and GPIO_Speed members + * - Call GPIO_Init() function + * + * 5. Program the Clock Edge, Clock Bypass, Clock Power Save, Bus Wide, + * hardware, flow control and the Clock Divider using the SDIO_Init() + * function. + * + * 6. Enable the Power ON State using the SDIO_SetPowerState(SDIO_PowerState_ON) + * function. + * + * 7. Enable the clock using the SDIO_ClockCmd() function. + * + * 8. Enable the NVIC and the corresponding interrupt using the function + * SDIO_ITConfig() if you need to use interrupt mode. + * + * 9. When using the DMA mode + * - Configure the DMA using DMA_Init() function + * - Active the needed channel Request using SDIO_DMACmd() function + * + * 10. Enable the DMA using the DMA_Cmd() function, when using DMA mode. + * + * 11. To control the CPSM (Command Path State Machine) and send + * commands to the card use the SDIO_SendCommand(), + * SDIO_GetCommandResponse() and SDIO_GetResponse() functions. + * First, user has to fill the command structure (pointer to + * SDIO_CmdInitTypeDef) according to the selected command to be sent. + * The parameters that should be filled are: + * - Command Argument + * - Command Index + * - Command Response type + * - Command Wait + * - CPSM Status (Enable or Disable) + * + * To check if the command is well received, read the SDIO_CMDRESP + * register using the SDIO_GetCommandResponse(). + * The SDIO responses registers (SDIO_RESP1 to SDIO_RESP2), use the + * SDIO_GetResponse() function. + * + * 12. To control the DPSM (Data Path State Machine) and send/receive + * data to/from the card use the SDIO_DataConfig(), SDIO_GetDataCounter(), + * SDIO_ReadData(), SDIO_WriteData() and SDIO_GetFIFOCount() functions. + * + * Read Operations + * --------------- + * a) First, user has to fill the data structure (pointer to + * SDIO_DataInitTypeDef) according to the selected data type to + * be received. + * The parameters that should be filled are: + * - Data TimeOut + * - Data Length + * - Data Block size + * - Data Transfer direction: should be from card (To SDIO) + * - Data Transfer mode + * - DPSM Status (Enable or Disable) + * + * b) Configure the SDIO resources to receive the data from the card + * according to selected transfer mode (Refer to Step 8, 9 and 10). + * + * c) Send the selected Read command (refer to step 11). + * + * d) Use the SDIO flags/interrupts to check the transfer status. + * + * Write Operations + * --------------- + * a) First, user has to fill the data structure (pointer to + * SDIO_DataInitTypeDef) according to the selected data type to + * be received. + * The parameters that should be filled are: + * - Data TimeOut + * - Data Length + * - Data Block size + * - Data Transfer direction: should be to card (To CARD) + * - Data Transfer mode + * - DPSM Status (Enable or Disable) + * + * b) Configure the SDIO resources to send the data to the card + * according to selected transfer mode (Refer to Step 8, 9 and 10). + * + * c) Send the selected Write command (refer to step 11). + * + * d) Use the SDIO flags/interrupts to check the transfer status. + * + * + * @endverbatim + * + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_sdio.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup SDIO + * @brief SDIO driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* ------------ SDIO registers bit address in the alias region ----------- */ +#define SDIO_OFFSET (SDIO_BASE - PERIPH_BASE) + +/* --- CLKCR Register ---*/ +/* Alias word address of CLKEN bit */ +#define CLKCR_OFFSET (SDIO_OFFSET + 0x04) +#define CLKEN_BitNumber 0x08 +#define CLKCR_CLKEN_BB (PERIPH_BB_BASE + (CLKCR_OFFSET * 32) + (CLKEN_BitNumber * 4)) + +/* --- CMD Register ---*/ +/* Alias word address of SDIOSUSPEND bit */ +#define CMD_OFFSET (SDIO_OFFSET + 0x0C) +#define SDIOSUSPEND_BitNumber 0x0B +#define CMD_SDIOSUSPEND_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (SDIOSUSPEND_BitNumber * 4)) + +/* Alias word address of ENCMDCOMPL bit */ +#define ENCMDCOMPL_BitNumber 0x0C +#define CMD_ENCMDCOMPL_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ENCMDCOMPL_BitNumber * 4)) + +/* Alias word address of NIEN bit */ +#define NIEN_BitNumber 0x0D +#define CMD_NIEN_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (NIEN_BitNumber * 4)) + +/* Alias word address of ATACMD bit */ +#define ATACMD_BitNumber 0x0E +#define CMD_ATACMD_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ATACMD_BitNumber * 4)) + +/* --- DCTRL Register ---*/ +/* Alias word address of DMAEN bit */ +#define DCTRL_OFFSET (SDIO_OFFSET + 0x2C) +#define DMAEN_BitNumber 0x03 +#define DCTRL_DMAEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (DMAEN_BitNumber * 4)) + +/* Alias word address of RWSTART bit */ +#define RWSTART_BitNumber 0x08 +#define DCTRL_RWSTART_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTART_BitNumber * 4)) + +/* Alias word address of RWSTOP bit */ +#define RWSTOP_BitNumber 0x09 +#define DCTRL_RWSTOP_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTOP_BitNumber * 4)) + +/* Alias word address of RWMOD bit */ +#define RWMOD_BitNumber 0x0A +#define DCTRL_RWMOD_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWMOD_BitNumber * 4)) + +/* Alias word address of SDIOEN bit */ +#define SDIOEN_BitNumber 0x0B +#define DCTRL_SDIOEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (SDIOEN_BitNumber * 4)) + +/* ---------------------- SDIO registers bit mask ------------------------ */ +/* --- CLKCR Register ---*/ +/* CLKCR register clear mask */ +#define CLKCR_CLEAR_MASK ((uint32_t)0xFFFF8100) + +/* --- PWRCTRL Register ---*/ +/* SDIO PWRCTRL Mask */ +#define PWR_PWRCTRL_MASK ((uint32_t)0xFFFFFFFC) + +/* --- DCTRL Register ---*/ +/* SDIO DCTRL Clear Mask */ +#define DCTRL_CLEAR_MASK ((uint32_t)0xFFFFFF08) + +/* --- CMD Register ---*/ +/* CMD Register clear mask */ +#define CMD_CLEAR_MASK ((uint32_t)0xFFFFF800) + +/* SDIO RESP Registers Address */ +#define SDIO_RESP_ADDR ((uint32_t)(SDIO_BASE + 0x14)) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup SDIO_Private_Functions + * @{ + */ + +/** @defgroup SDIO_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the SDIO peripheral registers to their default reset values. + * @param None + * @retval None + */ +void SDIO_DeInit(void) +{ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SDIO, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SDIO, DISABLE); +} + +/** + * @brief Initializes the SDIO peripheral according to the specified + * parameters in the SDIO_InitStruct. + * @param SDIO_InitStruct : pointer to a SDIO_InitTypeDef structure + * that contains the configuration information for the SDIO peripheral. + * @retval None + */ +void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_CLOCK_EDGE(SDIO_InitStruct->SDIO_ClockEdge)); + assert_param(IS_SDIO_CLOCK_BYPASS(SDIO_InitStruct->SDIO_ClockBypass)); + assert_param(IS_SDIO_CLOCK_POWER_SAVE(SDIO_InitStruct->SDIO_ClockPowerSave)); + assert_param(IS_SDIO_BUS_WIDE(SDIO_InitStruct->SDIO_BusWide)); + assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(SDIO_InitStruct->SDIO_HardwareFlowControl)); + +/*---------------------------- SDIO CLKCR Configuration ------------------------*/ + /* Get the SDIO CLKCR value */ + tmpreg = SDIO->CLKCR; + + /* Clear CLKDIV, PWRSAV, BYPASS, WIDBUS, NEGEDGE, HWFC_EN bits */ + tmpreg &= CLKCR_CLEAR_MASK; + + /* Set CLKDIV bits according to SDIO_ClockDiv value */ + /* Set PWRSAV bit according to SDIO_ClockPowerSave value */ + /* Set BYPASS bit according to SDIO_ClockBypass value */ + /* Set WIDBUS bits according to SDIO_BusWide value */ + /* Set NEGEDGE bits according to SDIO_ClockEdge value */ + /* Set HWFC_EN bits according to SDIO_HardwareFlowControl value */ + tmpreg |= (SDIO_InitStruct->SDIO_ClockDiv | SDIO_InitStruct->SDIO_ClockPowerSave | + SDIO_InitStruct->SDIO_ClockBypass | SDIO_InitStruct->SDIO_BusWide | + SDIO_InitStruct->SDIO_ClockEdge | SDIO_InitStruct->SDIO_HardwareFlowControl); + + /* Write to SDIO CLKCR */ + SDIO->CLKCR = tmpreg; +} + +/** + * @brief Fills each SDIO_InitStruct member with its default value. + * @param SDIO_InitStruct: pointer to an SDIO_InitTypeDef structure which + * will be initialized. + * @retval None + */ +void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct) +{ + /* SDIO_InitStruct members default value */ + SDIO_InitStruct->SDIO_ClockDiv = 0x00; + SDIO_InitStruct->SDIO_ClockEdge = SDIO_ClockEdge_Rising; + SDIO_InitStruct->SDIO_ClockBypass = SDIO_ClockBypass_Disable; + SDIO_InitStruct->SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable; + SDIO_InitStruct->SDIO_BusWide = SDIO_BusWide_1b; + SDIO_InitStruct->SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable; +} + +/** + * @brief Enables or disables the SDIO Clock. + * @param NewState: new state of the SDIO Clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_ClockCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CLKCR_CLKEN_BB = (uint32_t)NewState; +} + +/** + * @brief Sets the power status of the controller. + * @param SDIO_PowerState: new state of the Power state. + * This parameter can be one of the following values: + * @arg SDIO_PowerState_OFF: SDIO Power OFF + * @arg SDIO_PowerState_ON: SDIO Power ON + * @retval None + */ +void SDIO_SetPowerState(uint32_t SDIO_PowerState) +{ + /* Check the parameters */ + assert_param(IS_SDIO_POWER_STATE(SDIO_PowerState)); + + SDIO->POWER = SDIO_PowerState; +} + +/** + * @brief Gets the power status of the controller. + * @param None + * @retval Power status of the controller. The returned value can be one of the + * following values: + * - 0x00: Power OFF + * - 0x02: Power UP + * - 0x03: Power ON + */ +uint32_t SDIO_GetPowerState(void) +{ + return (SDIO->POWER & (~PWR_PWRCTRL_MASK)); +} + +/** + * @} + */ + +/** @defgroup SDIO_Group2 Command path state machine (CPSM) management functions + * @brief Command path state machine (CPSM) management functions + * +@verbatim + =============================================================================== + Command path state machine (CPSM) management functions + =============================================================================== + + This section provide functions allowing to program and read the Command path + state machine (CPSM). + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the SDIO Command according to the specified + * parameters in the SDIO_CmdInitStruct and send the command. + * @param SDIO_CmdInitStruct : pointer to a SDIO_CmdInitTypeDef + * structure that contains the configuration information for the SDIO + * command. + * @retval None + */ +void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_CMD_INDEX(SDIO_CmdInitStruct->SDIO_CmdIndex)); + assert_param(IS_SDIO_RESPONSE(SDIO_CmdInitStruct->SDIO_Response)); + assert_param(IS_SDIO_WAIT(SDIO_CmdInitStruct->SDIO_Wait)); + assert_param(IS_SDIO_CPSM(SDIO_CmdInitStruct->SDIO_CPSM)); + +/*---------------------------- SDIO ARG Configuration ------------------------*/ + /* Set the SDIO Argument value */ + SDIO->ARG = SDIO_CmdInitStruct->SDIO_Argument; + +/*---------------------------- SDIO CMD Configuration ------------------------*/ + /* Get the SDIO CMD value */ + tmpreg = SDIO->CMD; + /* Clear CMDINDEX, WAITRESP, WAITINT, WAITPEND, CPSMEN bits */ + tmpreg &= CMD_CLEAR_MASK; + /* Set CMDINDEX bits according to SDIO_CmdIndex value */ + /* Set WAITRESP bits according to SDIO_Response value */ + /* Set WAITINT and WAITPEND bits according to SDIO_Wait value */ + /* Set CPSMEN bits according to SDIO_CPSM value */ + tmpreg |= (uint32_t)SDIO_CmdInitStruct->SDIO_CmdIndex | SDIO_CmdInitStruct->SDIO_Response + | SDIO_CmdInitStruct->SDIO_Wait | SDIO_CmdInitStruct->SDIO_CPSM; + + /* Write to SDIO CMD */ + SDIO->CMD = tmpreg; +} + +/** + * @brief Fills each SDIO_CmdInitStruct member with its default value. + * @param SDIO_CmdInitStruct: pointer to an SDIO_CmdInitTypeDef + * structure which will be initialized. + * @retval None + */ +void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct) +{ + /* SDIO_CmdInitStruct members default value */ + SDIO_CmdInitStruct->SDIO_Argument = 0x00; + SDIO_CmdInitStruct->SDIO_CmdIndex = 0x00; + SDIO_CmdInitStruct->SDIO_Response = SDIO_Response_No; + SDIO_CmdInitStruct->SDIO_Wait = SDIO_Wait_No; + SDIO_CmdInitStruct->SDIO_CPSM = SDIO_CPSM_Disable; +} + +/** + * @brief Returns command index of last command for which response received. + * @param None + * @retval Returns the command index of the last command response received. + */ +uint8_t SDIO_GetCommandResponse(void) +{ + return (uint8_t)(SDIO->RESPCMD); +} + +/** + * @brief Returns response received from the card for the last command. + * @param SDIO_RESP: Specifies the SDIO response register. + * This parameter can be one of the following values: + * @arg SDIO_RESP1: Response Register 1 + * @arg SDIO_RESP2: Response Register 2 + * @arg SDIO_RESP3: Response Register 3 + * @arg SDIO_RESP4: Response Register 4 + * @retval The Corresponding response register value. + */ +uint32_t SDIO_GetResponse(uint32_t SDIO_RESP) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_RESP(SDIO_RESP)); + + tmp = SDIO_RESP_ADDR + SDIO_RESP; + + return (*(__IO uint32_t *) tmp); +} + +/** + * @} + */ + +/** @defgroup SDIO_Group3 Data path state machine (DPSM) management functions + * @brief Data path state machine (DPSM) management functions + * +@verbatim + =============================================================================== + Data path state machine (DPSM) management functions + =============================================================================== + + This section provide functions allowing to program and read the Data path + state machine (DPSM). + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the SDIO data path according to the specified + * parameters in the SDIO_DataInitStruct. + * @param SDIO_DataInitStruct : pointer to a SDIO_DataInitTypeDef structure + * that contains the configuration information for the SDIO command. + * @retval None + */ +void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_DATA_LENGTH(SDIO_DataInitStruct->SDIO_DataLength)); + assert_param(IS_SDIO_BLOCK_SIZE(SDIO_DataInitStruct->SDIO_DataBlockSize)); + assert_param(IS_SDIO_TRANSFER_DIR(SDIO_DataInitStruct->SDIO_TransferDir)); + assert_param(IS_SDIO_TRANSFER_MODE(SDIO_DataInitStruct->SDIO_TransferMode)); + assert_param(IS_SDIO_DPSM(SDIO_DataInitStruct->SDIO_DPSM)); + +/*---------------------------- SDIO DTIMER Configuration ---------------------*/ + /* Set the SDIO Data TimeOut value */ + SDIO->DTIMER = SDIO_DataInitStruct->SDIO_DataTimeOut; + +/*---------------------------- SDIO DLEN Configuration -----------------------*/ + /* Set the SDIO DataLength value */ + SDIO->DLEN = SDIO_DataInitStruct->SDIO_DataLength; + +/*---------------------------- SDIO DCTRL Configuration ----------------------*/ + /* Get the SDIO DCTRL value */ + tmpreg = SDIO->DCTRL; + /* Clear DEN, DTMODE, DTDIR and DBCKSIZE bits */ + tmpreg &= DCTRL_CLEAR_MASK; + /* Set DEN bit according to SDIO_DPSM value */ + /* Set DTMODE bit according to SDIO_TransferMode value */ + /* Set DTDIR bit according to SDIO_TransferDir value */ + /* Set DBCKSIZE bits according to SDIO_DataBlockSize value */ + tmpreg |= (uint32_t)SDIO_DataInitStruct->SDIO_DataBlockSize | SDIO_DataInitStruct->SDIO_TransferDir + | SDIO_DataInitStruct->SDIO_TransferMode | SDIO_DataInitStruct->SDIO_DPSM; + + /* Write to SDIO DCTRL */ + SDIO->DCTRL = tmpreg; +} + +/** + * @brief Fills each SDIO_DataInitStruct member with its default value. + * @param SDIO_DataInitStruct: pointer to an SDIO_DataInitTypeDef structure + * which will be initialized. + * @retval None + */ +void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct) +{ + /* SDIO_DataInitStruct members default value */ + SDIO_DataInitStruct->SDIO_DataTimeOut = 0xFFFFFFFF; + SDIO_DataInitStruct->SDIO_DataLength = 0x00; + SDIO_DataInitStruct->SDIO_DataBlockSize = SDIO_DataBlockSize_1b; + SDIO_DataInitStruct->SDIO_TransferDir = SDIO_TransferDir_ToCard; + SDIO_DataInitStruct->SDIO_TransferMode = SDIO_TransferMode_Block; + SDIO_DataInitStruct->SDIO_DPSM = SDIO_DPSM_Disable; +} + +/** + * @brief Returns number of remaining data bytes to be transferred. + * @param None + * @retval Number of remaining data bytes to be transferred + */ +uint32_t SDIO_GetDataCounter(void) +{ + return SDIO->DCOUNT; +} + +/** + * @brief Read one data word from Rx FIFO. + * @param None + * @retval Data received + */ +uint32_t SDIO_ReadData(void) +{ + return SDIO->FIFO; +} + +/** + * @brief Write one data word to Tx FIFO. + * @param Data: 32-bit data word to write. + * @retval None + */ +void SDIO_WriteData(uint32_t Data) +{ + SDIO->FIFO = Data; +} + +/** + * @brief Returns the number of words left to be written to or read from FIFO. + * @param None + * @retval Remaining number of words. + */ +uint32_t SDIO_GetFIFOCount(void) +{ + return SDIO->FIFOCNT; +} + +/** + * @} + */ + +/** @defgroup SDIO_Group4 SDIO IO Cards mode management functions + * @brief SDIO IO Cards mode management functions + * +@verbatim + =============================================================================== + SDIO IO Cards mode management functions + =============================================================================== + + This section provide functions allowing to program and read the SDIO IO Cards. + +@endverbatim + * @{ + */ + +/** + * @brief Starts the SD I/O Read Wait operation. + * @param NewState: new state of the Start SDIO Read Wait operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_StartSDIOReadWait(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_RWSTART_BB = (uint32_t) NewState; +} + +/** + * @brief Stops the SD I/O Read Wait operation. + * @param NewState: new state of the Stop SDIO Read Wait operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_StopSDIOReadWait(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_RWSTOP_BB = (uint32_t) NewState; +} + +/** + * @brief Sets one of the two options of inserting read wait interval. + * @param SDIO_ReadWaitMode: SD I/O Read Wait operation mode. + * This parameter can be: + * @arg SDIO_ReadWaitMode_CLK: Read Wait control by stopping SDIOCLK + * @arg SDIO_ReadWaitMode_DATA2: Read Wait control using SDIO_DATA2 + * @retval None + */ +void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode) +{ + /* Check the parameters */ + assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode)); + + *(__IO uint32_t *) DCTRL_RWMOD_BB = SDIO_ReadWaitMode; +} + +/** + * @brief Enables or disables the SD I/O Mode Operation. + * @param NewState: new state of SDIO specific operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SetSDIOOperation(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_SDIOEN_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the SD I/O Mode suspend command sending. + * @param NewState: new state of the SD I/O Mode suspend command. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SendSDIOSuspendCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_SDIOSUSPEND_BB = (uint32_t)NewState; +} + +/** + * @} + */ + +/** @defgroup SDIO_Group5 CE-ATA mode management functions + * @brief CE-ATA mode management functions + * +@verbatim + =============================================================================== + CE-ATA mode management functions + =============================================================================== + + This section provide functions allowing to program and read the CE-ATA card. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the command completion signal. + * @param NewState: new state of command completion signal. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_CommandCompletionCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_ENCMDCOMPL_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the CE-ATA interrupt. + * @param NewState: new state of CE-ATA interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_CEATAITCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)((~((uint32_t)NewState)) & ((uint32_t)0x1)); +} + +/** + * @brief Sends CE-ATA command (CMD61). + * @param NewState: new state of CE-ATA command. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SendCEATACmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_ATACMD_BB = (uint32_t)NewState; +} + +/** + * @} + */ + +/** @defgroup SDIO_Group6 DMA transfers management functions + * @brief DMA transfers management functions + * +@verbatim + =============================================================================== + DMA transfers management functions + =============================================================================== + + This section provide functions allowing to program SDIO DMA transfer. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the SDIO DMA request. + * @param NewState: new state of the selected SDIO DMA request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_DMACmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_DMAEN_BB = (uint32_t)NewState; +} + +/** + * @} + */ + +/** @defgroup SDIO_Group7 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the SDIO interrupts. + * @param SDIO_IT: specifies the SDIO interrupt sources to be enabled or disabled. + * This parameter can be one or a combination of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt + * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt + * @arg SDIO_IT_TXACT: Data transmit in progress interrupt + * @arg SDIO_IT_RXACT: Data receive in progress interrupt + * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt + * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt + * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt + * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt + * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt + * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt + * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt + * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt + * @param NewState: new state of the specified SDIO interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SDIO_IT(SDIO_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the SDIO interrupts */ + SDIO->MASK |= SDIO_IT; + } + else + { + /* Disable the SDIO interrupts */ + SDIO->MASK &= ~SDIO_IT; + } +} + +/** + * @brief Checks whether the specified SDIO flag is set or not. + * @param SDIO_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) + * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) + * @arg SDIO_FLAG_CTIMEOUT: Command response timeout + * @arg SDIO_FLAG_DTIMEOUT: Data timeout + * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error + * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error + * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) + * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) + * @arg SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is zero) + * @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide bus mode. + * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) + * @arg SDIO_FLAG_CMDACT: Command transfer in progress + * @arg SDIO_FLAG_TXACT: Data transmit in progress + * @arg SDIO_FLAG_RXACT: Data receive in progress + * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty + * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full + * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full + * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full + * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty + * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty + * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO + * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO + * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received + * @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval The new state of SDIO_FLAG (SET or RESET). + */ +FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_SDIO_FLAG(SDIO_FLAG)); + + if ((SDIO->STA & SDIO_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the SDIO's pending flags. + * @param SDIO_FLAG: specifies the flag to clear. + * This parameter can be one or a combination of the following values: + * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) + * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) + * @arg SDIO_FLAG_CTIMEOUT: Command response timeout + * @arg SDIO_FLAG_DTIMEOUT: Data timeout + * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error + * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error + * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) + * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) + * @arg SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is zero) + * @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide bus mode + * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) + * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received + * @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval None + */ +void SDIO_ClearFlag(uint32_t SDIO_FLAG) +{ + /* Check the parameters */ + assert_param(IS_SDIO_CLEAR_FLAG(SDIO_FLAG)); + + SDIO->ICR = SDIO_FLAG; +} + +/** + * @brief Checks whether the specified SDIO interrupt has occurred or not. + * @param SDIO_IT: specifies the SDIO interrupt source to check. + * This parameter can be one of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt + * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt + * @arg SDIO_IT_TXACT: Data transmit in progress interrupt + * @arg SDIO_IT_RXACT: Data receive in progress interrupt + * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt + * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt + * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt + * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt + * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt + * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt + * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt + * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt + * @retval The new state of SDIO_IT (SET or RESET). + */ +ITStatus SDIO_GetITStatus(uint32_t SDIO_IT) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_SDIO_GET_IT(SDIO_IT)); + if ((SDIO->STA & SDIO_IT) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the SDIO's interrupt pending bits. + * @param SDIO_IT: specifies the interrupt pending bit to clear. + * This parameter can be one or a combination of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIO_DCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval None + */ +void SDIO_ClearITPendingBit(uint32_t SDIO_IT) +{ + /* Check the parameters */ + assert_param(IS_SDIO_CLEAR_IT(SDIO_IT)); + + SDIO->ICR = SDIO_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c new file mode 100644 index 000000000..d02193ea5 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c @@ -0,0 +1,1286 @@ +/** + ****************************************************************************** + * @file stm32f4xx_spi.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Serial peripheral interface (SPI): + * - Initialization and Configuration + * - Data transfers functions + * - Hardware CRC Calculation + * - DMA transfers management + * - Interrupts and flags management + * + * @verbatim + * + * + * =================================================================== + * How to use this driver + * =================================================================== + * + * 1. Enable peripheral clock using the following functions + * RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE) for SPI1 + * RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE) for SPI2 + * RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE) for SPI3. + * + * 2. Enable SCK, MOSI, MISO and NSS GPIO clocks using RCC_AHB1PeriphClockCmd() + * function. + * In I2S mode, if an external clock source is used then the I2S CKIN pin GPIO + * clock should also be enabled. + * + * 3. Peripherals alternate function: + * - Connect the pin to the desired peripherals' Alternate + * Function (AF) using GPIO_PinAFConfig() function + * - Configure the desired pin in alternate function by: + * GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF + * - Select the type, pull-up/pull-down and output speed via + * GPIO_PuPd, GPIO_OType and GPIO_Speed members + * - Call GPIO_Init() function + * In I2S mode, if an external clock source is used then the I2S CKIN pin + * should be also configured in Alternate function Push-pull pull-up mode. + * + * 4. Program the Polarity, Phase, First Data, Baud Rate Prescaler, Slave + * Management, Peripheral Mode and CRC Polynomial values using the SPI_Init() + * function. + * In I2S mode, program the Mode, Standard, Data Format, MCLK Output, Audio + * frequency and Polarity using I2S_Init() function. + * For I2S mode, make sure that either: + * - I2S PLL is configured using the functions RCC_I2SCLKConfig(RCC_I2S2CLKSource_PLLI2S), + * RCC_PLLI2SCmd(ENABLE) and RCC_GetFlagStatus(RCC_FLAG_PLLI2SRDY). + * or + * - External clock source is configured using the function + * RCC_I2SCLKConfig(RCC_I2S2CLKSource_Ext) and after setting correctly the define constant + * I2S_EXTERNAL_CLOCK_VAL in the stm32f4xx_conf.h file. + * + * 5. Enable the NVIC and the corresponding interrupt using the function + * SPI_ITConfig() if you need to use interrupt mode. + * + * 6. When using the DMA mode + * - Configure the DMA using DMA_Init() function + * - Active the needed channel Request using SPI_I2S_DMACmd() function + * + * 7. Enable the SPI using the SPI_Cmd() function or enable the I2S using + * I2S_Cmd(). + * + * 8. Enable the DMA using the DMA_Cmd() function when using DMA mode. + * + * 9. Optionally, you can enable/configure the following parameters without + * re-initialization (i.e there is no need to call again SPI_Init() function): + * - When bidirectional mode (SPI_Direction_1Line_Rx or SPI_Direction_1Line_Tx) + * is programmed as Data direction parameter using the SPI_Init() function + * it can be possible to switch between SPI_Direction_Tx or SPI_Direction_Rx + * using the SPI_BiDirectionalLineConfig() function. + * - When SPI_NSS_Soft is selected as Slave Select Management parameter + * using the SPI_Init() function it can be possible to manage the + * NSS internal signal using the SPI_NSSInternalSoftwareConfig() function. + * - Reconfigure the data size using the SPI_DataSizeConfig() function + * - Enable or disable the SS output using the SPI_SSOutputCmd() function + * + * 10. To use the CRC Hardware calculation feature refer to the Peripheral + * CRC hardware Calculation subsection. + * + * + * It is possible to use SPI in I2S full duplex mode, in this case, each SPI + * peripheral is able to manage sending and receiving data simultaneously + * using two data lines. Each SPI peripheral has an extended block called I2Sxext + * (ie. I2S2ext for SPI2 and I2S3ext for SPI3). + * The extension block is not a full SPI IP, it is used only as I2S slave to + * implement full duplex mode. The extension block uses the same clock sources + * as its master. + * To configure I2S full duplex you have to: + * + * 1. Configure SPIx in I2S mode (I2S_Init() function) as described above. + * + * 2. Call the I2S_FullDuplexConfig() function using the same strucutre passed to + * I2S_Init() function. + * + * 3. Call I2S_Cmd() for SPIx then for its extended block. + * + * 4. To configure interrupts or DMA requests and to get/clear flag status, + * use I2Sxext instance for the extension block. + * + * Functions that can be called with I2Sxext instances are: + * I2S_Cmd(), I2S_FullDuplexConfig(), SPI_I2S_ReceiveData(), SPI_I2S_SendData(), + * SPI_I2S_DMACmd(), SPI_I2S_ITConfig(), SPI_I2S_GetFlagStatus(), SPI_I2S_ClearFlag(), + * SPI_I2S_GetITStatus() and SPI_I2S_ClearITPendingBit(). + * + * Example: To use SPI3 in Full duplex mode (SPI3 is Master Tx, I2S3ext is Slave Rx): + * + * RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE); + * I2S_StructInit(&I2SInitStruct); + * I2SInitStruct.Mode = I2S_Mode_MasterTx; + * I2S_Init(SPI3, &I2SInitStruct); + * I2S_FullDuplexConfig(SPI3ext, &I2SInitStruct) + * I2S_Cmd(SPI3, ENABLE); + * I2S_Cmd(SPI3ext, ENABLE); + * ... + * while (SPI_I2S_GetFlagStatus(SPI2, SPI_FLAG_TXE) == RESET) + * {} + * SPI_I2S_SendData(SPI3, txdata[i]); + * ... + * while (SPI_I2S_GetFlagStatus(I2S3ext, SPI_FLAG_RXNE) == RESET) + * {} + * rxdata[i] = SPI_I2S_ReceiveData(I2S3ext); + * ... + * + * + * @note In I2S mode: if an external clock is used as source clock for the I2S, + * then the define I2S_EXTERNAL_CLOCK_VAL in file stm32f4xx_conf.h should + * be enabled and set to the value of the source clock frequency (in Hz). + * + * @note In SPI mode: To use the SPI TI mode, call the function SPI_TIModeCmd() + * just after calling the function SPI_Init(). + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_spi.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup SPI + * @brief SPI driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* SPI registers Masks */ +#define CR1_CLEAR_MASK ((uint16_t)0x3040) +#define I2SCFGR_CLEAR_MASK ((uint16_t)0xF040) + +/* RCC PLLs masks */ +#define PLLCFGR_PPLR_MASK ((uint32_t)0x70000000) +#define PLLCFGR_PPLN_MASK ((uint32_t)0x00007FC0) + +#define SPI_CR2_FRF ((uint16_t)0x0010) +#define SPI_SR_TIFRFE ((uint16_t)0x0100) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup SPI_Private_Functions + * @{ + */ + +/** @defgroup SPI_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + + This section provides a set of functions allowing to initialize the SPI Direction, + SPI Mode, SPI Data Size, SPI Polarity, SPI Phase, SPI NSS Management, SPI Baud + Rate Prescaler, SPI First Bit and SPI CRC Polynomial. + + The SPI_Init() function follows the SPI configuration procedures for Master mode + and Slave mode (details for these procedures are available in reference manual + (RM0090)). + +@endverbatim + * @{ + */ + +/** + * @brief Deinitialize the SPIx peripheral registers to their default reset values. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode. + * + * @note The extended I2S blocks (ie. I2S2ext and I2S3ext blocks) are deinitialized + * when the relative I2S peripheral is deinitialized (the extended block's clock + * is managed by the I2S peripheral clock). + * + * @retval None + */ +void SPI_I2S_DeInit(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + if (SPIx == SPI1) + { + /* Enable SPI1 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE); + /* Release SPI1 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE); + } + else if (SPIx == SPI2) + { + /* Enable SPI2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE); + /* Release SPI2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE); + } + else + { + if (SPIx == SPI3) + { + /* Enable SPI3 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE); + /* Release SPI3 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE); + } + } +} + +/** + * @brief Initializes the SPIx peripheral according to the specified + * parameters in the SPI_InitStruct. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure that + * contains the configuration information for the specified SPI peripheral. + * @retval None + */ +void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct) +{ + uint16_t tmpreg = 0; + + /* check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Check the SPI parameters */ + assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction)); + assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode)); + assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize)); + assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL)); + assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA)); + assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS)); + assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler)); + assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit)); + assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial)); + +/*---------------------------- SPIx CR1 Configuration ------------------------*/ + /* Get the SPIx CR1 value */ + tmpreg = SPIx->CR1; + /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */ + tmpreg &= CR1_CLEAR_MASK; + /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler + master/salve mode, CPOL and CPHA */ + /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */ + /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */ + /* Set LSBFirst bit according to SPI_FirstBit value */ + /* Set BR bits according to SPI_BaudRatePrescaler value */ + /* Set CPOL bit according to SPI_CPOL value */ + /* Set CPHA bit according to SPI_CPHA value */ + tmpreg |= (uint16_t)((uint32_t)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode | + SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL | + SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS | + SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit); + /* Write to SPIx CR1 */ + SPIx->CR1 = tmpreg; + + /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */ + SPIx->I2SCFGR &= (uint16_t)~((uint16_t)SPI_I2SCFGR_I2SMOD); +/*---------------------------- SPIx CRCPOLY Configuration --------------------*/ + /* Write to SPIx CRCPOLY */ + SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial; +} + +/** + * @brief Initializes the SPIx peripheral according to the specified + * parameters in the I2S_InitStruct. + * @param SPIx: where x can be 2 or 3 to select the SPI peripheral (configured in I2S mode). + * @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that + * contains the configuration information for the specified SPI peripheral + * configured in I2S mode. + * + * @note The function calculates the optimal prescaler needed to obtain the most + * accurate audio frequency (depending on the I2S clock source, the PLL values + * and the product configuration). But in case the prescaler value is greater + * than 511, the default value (0x02) will be configured instead. + * + * @note if an external clock is used as source clock for the I2S, then the define + * I2S_EXTERNAL_CLOCK_VAL in file stm32f4xx_conf.h should be enabled and set + * to the value of the the source clock frequency (in Hz). + * + * @retval None + */ +void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct) +{ + uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1; + uint32_t tmp = 0, i2sclk = 0; +#ifndef I2S_EXTERNAL_CLOCK_VAL + uint32_t pllm = 0, plln = 0, pllr = 0; +#endif /* I2S_EXTERNAL_CLOCK_VAL */ + + /* Check the I2S parameters */ + assert_param(IS_SPI_23_PERIPH(SPIx)); + assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode)); + assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard)); + assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat)); + assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput)); + assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq)); + assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL)); + +/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/ + /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ + SPIx->I2SCFGR &= I2SCFGR_CLEAR_MASK; + SPIx->I2SPR = 0x0002; + + /* Get the I2SCFGR register value */ + tmpreg = SPIx->I2SCFGR; + + /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/ + if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default) + { + i2sodd = (uint16_t)0; + i2sdiv = (uint16_t)2; + } + /* If the requested audio frequency is not the default, compute the prescaler */ + else + { + /* Check the frame length (For the Prescaler computing) *******************/ + if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b) + { + /* Packet length is 16 bits */ + packetlength = 1; + } + else + { + /* Packet length is 32 bits */ + packetlength = 2; + } + + /* Get I2S source Clock frequency ****************************************/ + + /* If an external I2S clock has to be used, this define should be set + in the project configuration or in the stm32f4xx_conf.h file */ + #ifdef I2S_EXTERNAL_CLOCK_VAL + /* Set external clock as I2S clock source */ + if ((RCC->CFGR & RCC_CFGR_I2SSRC) == 0) + { + RCC->CFGR |= (uint32_t)RCC_CFGR_I2SSRC; + } + + /* Set the I2S clock to the external clock value */ + i2sclk = I2S_EXTERNAL_CLOCK_VAL; + + #else /* There is no define for External I2S clock source */ + /* Set PLLI2S as I2S clock source */ + if ((RCC->CFGR & RCC_CFGR_I2SSRC) != 0) + { + RCC->CFGR &= ~(uint32_t)RCC_CFGR_I2SSRC; + } + + /* Get the PLLI2SN value */ + plln = (uint32_t)(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6) & \ + (RCC_PLLI2SCFGR_PLLI2SN >> 6)); + + /* Get the PLLI2SR value */ + pllr = (uint32_t)(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28) & \ + (RCC_PLLI2SCFGR_PLLI2SR >> 28)); + + /* Get the PLLM value */ + pllm = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM); + + /* Get the I2S source clock value */ + i2sclk = (uint32_t)(((HSE_VALUE / pllm) * plln) / pllr); + #endif /* I2S_EXTERNAL_CLOCK_VAL */ + + /* Compute the Real divider depending on the MCLK output state, with a floating point */ + if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable) + { + /* MCLK output is enabled */ + tmp = (uint16_t)(((((i2sclk / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5); + } + else + { + /* MCLK output is disabled */ + tmp = (uint16_t)(((((i2sclk / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5); + } + + /* Remove the flatting point */ + tmp = tmp / 10; + + /* Check the parity of the divider */ + i2sodd = (uint16_t)(tmp & (uint16_t)0x0001); + + /* Compute the i2sdiv prescaler */ + i2sdiv = (uint16_t)((tmp - i2sodd) / 2); + + /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */ + i2sodd = (uint16_t) (i2sodd << 8); + } + + /* Test if the divider is 1 or 0 or greater than 0xFF */ + if ((i2sdiv < 2) || (i2sdiv > 0xFF)) + { + /* Set the default values */ + i2sdiv = 2; + i2sodd = 0; + } + + /* Write to SPIx I2SPR register the computed value */ + SPIx->I2SPR = (uint16_t)((uint16_t)i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput)); + + /* Configure the I2S with the SPI_InitStruct values */ + tmpreg |= (uint16_t)((uint16_t)SPI_I2SCFGR_I2SMOD | (uint16_t)(I2S_InitStruct->I2S_Mode | \ + (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \ + (uint16_t)I2S_InitStruct->I2S_CPOL)))); + + /* Write to SPIx I2SCFGR */ + SPIx->I2SCFGR = tmpreg; +} + +/** + * @brief Fills each SPI_InitStruct member with its default value. + * @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure which will be initialized. + * @retval None + */ +void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct) +{ +/*--------------- Reset SPI init structure parameters values -----------------*/ + /* Initialize the SPI_Direction member */ + SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex; + /* initialize the SPI_Mode member */ + SPI_InitStruct->SPI_Mode = SPI_Mode_Slave; + /* initialize the SPI_DataSize member */ + SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b; + /* Initialize the SPI_CPOL member */ + SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low; + /* Initialize the SPI_CPHA member */ + SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge; + /* Initialize the SPI_NSS member */ + SPI_InitStruct->SPI_NSS = SPI_NSS_Hard; + /* Initialize the SPI_BaudRatePrescaler member */ + SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2; + /* Initialize the SPI_FirstBit member */ + SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB; + /* Initialize the SPI_CRCPolynomial member */ + SPI_InitStruct->SPI_CRCPolynomial = 7; +} + +/** + * @brief Fills each I2S_InitStruct member with its default value. + * @param I2S_InitStruct: pointer to a I2S_InitTypeDef structure which will be initialized. + * @retval None + */ +void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct) +{ +/*--------------- Reset I2S init structure parameters values -----------------*/ + /* Initialize the I2S_Mode member */ + I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx; + + /* Initialize the I2S_Standard member */ + I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips; + + /* Initialize the I2S_DataFormat member */ + I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b; + + /* Initialize the I2S_MCLKOutput member */ + I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable; + + /* Initialize the I2S_AudioFreq member */ + I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default; + + /* Initialize the I2S_CPOL member */ + I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low; +} + +/** + * @brief Enables or disables the specified SPI peripheral. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI peripheral */ + SPIx->CR1 |= SPI_CR1_SPE; + } + else + { + /* Disable the selected SPI peripheral */ + SPIx->CR1 &= (uint16_t)~((uint16_t)SPI_CR1_SPE); + } +} + +/** + * @brief Enables or disables the specified SPI peripheral (in I2S mode). + * @param SPIx: where x can be 2 or 3 to select the SPI peripheral (or I2Sxext + * for full duplex mode). + * @param NewState: new state of the SPIx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_23_PERIPH_EXT(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected SPI peripheral (in I2S mode) */ + SPIx->I2SCFGR |= SPI_I2SCFGR_I2SE; + } + else + { + /* Disable the selected SPI peripheral in I2S mode */ + SPIx->I2SCFGR &= (uint16_t)~((uint16_t)SPI_I2SCFGR_I2SE); + } +} + +/** + * @brief Configures the data size for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_DataSize: specifies the SPI data size. + * This parameter can be one of the following values: + * @arg SPI_DataSize_16b: Set data frame format to 16bit + * @arg SPI_DataSize_8b: Set data frame format to 8bit + * @retval None + */ +void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_DATASIZE(SPI_DataSize)); + /* Clear DFF bit */ + SPIx->CR1 &= (uint16_t)~SPI_DataSize_16b; + /* Set new DFF bit value */ + SPIx->CR1 |= SPI_DataSize; +} + +/** + * @brief Selects the data transfer direction in bidirectional mode for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_Direction: specifies the data transfer direction in bidirectional mode. + * This parameter can be one of the following values: + * @arg SPI_Direction_Tx: Selects Tx transmission direction + * @arg SPI_Direction_Rx: Selects Rx receive direction + * @retval None + */ +void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_DIRECTION(SPI_Direction)); + if (SPI_Direction == SPI_Direction_Tx) + { + /* Set the Tx only mode */ + SPIx->CR1 |= SPI_Direction_Tx; + } + else + { + /* Set the Rx only mode */ + SPIx->CR1 &= SPI_Direction_Rx; + } +} + +/** + * @brief Configures internally by software the NSS pin for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_NSSInternalSoft: specifies the SPI NSS internal state. + * This parameter can be one of the following values: + * @arg SPI_NSSInternalSoft_Set: Set NSS pin internally + * @arg SPI_NSSInternalSoft_Reset: Reset NSS pin internally + * @retval None + */ +void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft)); + if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset) + { + /* Set NSS pin internally by software */ + SPIx->CR1 |= SPI_NSSInternalSoft_Set; + } + else + { + /* Reset NSS pin internally by software */ + SPIx->CR1 &= SPI_NSSInternalSoft_Reset; + } +} + +/** + * @brief Enables or disables the SS output for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx SS output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI SS output */ + SPIx->CR2 |= (uint16_t)SPI_CR2_SSOE; + } + else + { + /* Disable the selected SPI SS output */ + SPIx->CR2 &= (uint16_t)~((uint16_t)SPI_CR2_SSOE); + } +} + +/** + * @brief Enables or disables the SPIx/I2Sx DMA interface. + * + * @note This function can be called only after the SPI_Init() function has + * been called. + * @note When TI mode is selected, the control bits SSM, SSI, CPOL and CPHA + * are not taken into consideration and are configured by hardware + * respectively to the TI mode requirements. + * + * @param SPIx: where x can be 1, 2 or 3 + * @param NewState: new state of the selected SPI TI communication mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_TIModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the TI mode for the selected SPI peripheral */ + SPIx->CR2 |= SPI_CR2_FRF; + } + else + { + /* Disable the TI mode for the selected SPI peripheral */ + SPIx->CR2 &= (uint16_t)~SPI_CR2_FRF; + } +} + +/** + * @brief Configures the full duplex mode for the I2Sx peripheral using its + * extension I2Sxext according to the specified parameters in the + * I2S_InitStruct. + * @param I2Sxext: where x can be 2 or 3 to select the I2S peripheral extension block. + * @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that + * contains the configuration information for the specified I2S peripheral + * extension. + * + * @note The structure pointed by I2S_InitStruct parameter should be the same + * used for the master I2S peripheral. In this case, if the master is + * configured as transmitter, the slave will be receiver and vice versa. + * Or you can force a different mode by modifying the field I2S_Mode to the + * value I2S_SlaveRx or I2S_SlaveTx indepedently of the master configuration. + * + * @note The I2S full duplex extension can be configured in slave mode only. + * + * @retval None + */ +void I2S_FullDuplexConfig(SPI_TypeDef* I2Sxext, I2S_InitTypeDef* I2S_InitStruct) +{ + uint16_t tmpreg = 0, tmp = 0; + + /* Check the I2S parameters */ + assert_param(IS_I2S_EXT_PERIPH(I2Sxext)); + assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode)); + assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard)); + assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat)); + assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL)); + +/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/ + /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ + I2Sxext->I2SCFGR &= I2SCFGR_CLEAR_MASK; + I2Sxext->I2SPR = 0x0002; + + /* Get the I2SCFGR register value */ + tmpreg = I2Sxext->I2SCFGR; + + /* Get the mode to be configured for the extended I2S */ + if ((I2S_InitStruct->I2S_Mode == I2S_Mode_MasterTx) || (I2S_InitStruct->I2S_Mode == I2S_Mode_SlaveTx)) + { + tmp = I2S_Mode_SlaveRx; + } + else + { + if ((I2S_InitStruct->I2S_Mode == I2S_Mode_MasterRx) || (I2S_InitStruct->I2S_Mode == I2S_Mode_SlaveRx)) + { + tmp = I2S_Mode_SlaveTx; + } + } + + + /* Configure the I2S with the SPI_InitStruct values */ + tmpreg |= (uint16_t)((uint16_t)SPI_I2SCFGR_I2SMOD | (uint16_t)(tmp | \ + (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \ + (uint16_t)I2S_InitStruct->I2S_CPOL)))); + + /* Write to SPIx I2SCFGR */ + I2Sxext->I2SCFGR = tmpreg; +} + +/** + * @} + */ + +/** @defgroup SPI_Group2 Data transfers functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + Data transfers functions + =============================================================================== + + This section provides a set of functions allowing to manage the SPI data transfers + + In reception, data are received and then stored into an internal Rx buffer while + In transmission, data are first stored into an internal Tx buffer before being + transmitted. + + The read access of the SPI_DR register can be done using the SPI_I2S_ReceiveData() + function and returns the Rx buffered value. Whereas a write access to the SPI_DR + can be done using SPI_I2S_SendData() function and stores the written data into + Tx buffer. + +@endverbatim + * @{ + */ + +/** + * @brief Returns the most recent received data by the SPIx/I2Sx peripheral. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @retval The value of the received data. + */ +uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + + /* Return the data in the DR register */ + return SPIx->DR; +} + +/** + * @brief Transmits a Data through the SPIx/I2Sx peripheral. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param Data: Data to be transmitted. + * @retval None + */ +void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + + /* Write in the DR register the data to be sent */ + SPIx->DR = Data; +} + +/** + * @} + */ + +/** @defgroup SPI_Group3 Hardware CRC Calculation functions + * @brief Hardware CRC Calculation functions + * +@verbatim + =============================================================================== + Hardware CRC Calculation functions + =============================================================================== + + This section provides a set of functions allowing to manage the SPI CRC hardware + calculation + + SPI communication using CRC is possible through the following procedure: + 1. Program the Data direction, Polarity, Phase, First Data, Baud Rate Prescaler, + Slave Management, Peripheral Mode and CRC Polynomial values using the SPI_Init() + function. + 2. Enable the CRC calculation using the SPI_CalculateCRC() function. + 3. Enable the SPI using the SPI_Cmd() function + 4. Before writing the last data to the TX buffer, set the CRCNext bit using the + SPI_TransmitCRC() function to indicate that after transmission of the last + data, the CRC should be transmitted. + 5. After transmitting the last data, the SPI transmits the CRC. The SPI_CR1_CRCNEXT + bit is reset. The CRC is also received and compared against the SPI_RXCRCR + value. + If the value does not match, the SPI_FLAG_CRCERR flag is set and an interrupt + can be generated when the SPI_I2S_IT_ERR interrupt is enabled. + +@note It is advised not to read the calculated CRC values during the communication. + +@note When the SPI is in slave mode, be careful to enable CRC calculation only + when the clock is stable, that is, when the clock is in the steady state. + If not, a wrong CRC calculation may be done. In fact, the CRC is sensitive + to the SCK slave input clock as soon as CRCEN is set, and this, whatever + the value of the SPE bit. + +@note With high bitrate frequencies, be careful when transmitting the CRC. + As the number of used CPU cycles has to be as low as possible in the CRC + transfer phase, it is forbidden to call software functions in the CRC + transmission sequence to avoid errors in the last data and CRC reception. + In fact, CRCNEXT bit has to be written before the end of the transmission/reception + of the last data. + +@note For high bit rate frequencies, it is advised to use the DMA mode to avoid the + degradation of the SPI speed performance due to CPU accesses impacting the + SPI bandwidth. + +@note When the STM32F4xx is configured as slave and the NSS hardware mode is + used, the NSS pin needs to be kept low between the data phase and the CRC + phase. + +@note When the SPI is configured in slave mode with the CRC feature enabled, CRC + calculation takes place even if a high level is applied on the NSS pin. + This may happen for example in case of a multi-slave environment where the + communication master addresses slaves alternately. + +@note Between a slave de-selection (high level on NSS) and a new slave selection + (low level on NSS), the CRC value should be cleared on both master and slave + sides in order to resynchronize the master and slave for their respective + CRC calculation. + +@note To clear the CRC, follow the procedure below: + 1. Disable SPI using the SPI_Cmd() function + 2. Disable the CRC calculation using the SPI_CalculateCRC() function. + 3. Enable the CRC calculation using the SPI_CalculateCRC() function. + 4. Enable SPI using the SPI_Cmd() function. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the CRC value calculation of the transferred bytes. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx CRC value calculation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI CRC calculation */ + SPIx->CR1 |= SPI_CR1_CRCEN; + } + else + { + /* Disable the selected SPI CRC calculation */ + SPIx->CR1 &= (uint16_t)~((uint16_t)SPI_CR1_CRCEN); + } +} + +/** + * @brief Transmit the SPIx CRC value. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval None + */ +void SPI_TransmitCRC(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Enable the selected SPI CRC transmission */ + SPIx->CR1 |= SPI_CR1_CRCNEXT; +} + +/** + * @brief Returns the transmit or the receive CRC register value for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_CRC: specifies the CRC register to be read. + * This parameter can be one of the following values: + * @arg SPI_CRC_Tx: Selects Tx CRC register + * @arg SPI_CRC_Rx: Selects Rx CRC register + * @retval The selected CRC register value.. + */ +uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC) +{ + uint16_t crcreg = 0; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_CRC(SPI_CRC)); + if (SPI_CRC != SPI_CRC_Rx) + { + /* Get the Tx CRC register */ + crcreg = SPIx->TXCRCR; + } + else + { + /* Get the Rx CRC register */ + crcreg = SPIx->RXCRCR; + } + /* Return the selected CRC register */ + return crcreg; +} + +/** + * @brief Returns the CRC Polynomial register value for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval The CRC Polynomial register value. + */ +uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Return the CRC polynomial register */ + return SPIx->CRCPR; +} + +/** + * @} + */ + +/** @defgroup SPI_Group4 DMA transfers management functions + * @brief DMA transfers management functions + * +@verbatim + =============================================================================== + DMA transfers management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the SPIx/I2Sx DMA interface. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_DMAReq: specifies the SPI DMA transfer request to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request + * @arg SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request + * @param NewState: new state of the selected SPI DMA transfer request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq)); + + if (NewState != DISABLE) + { + /* Enable the selected SPI DMA requests */ + SPIx->CR2 |= SPI_I2S_DMAReq; + } + else + { + /* Disable the selected SPI DMA requests */ + SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq; + } +} + +/** + * @} + */ + +/** @defgroup SPI_Group5 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + + This section provides a set of functions allowing to configure the SPI Interrupts + sources and check or clear the flags or pending bits status. + The user should identify which mode will be used in his application to manage + the communication: Polling mode, Interrupt mode or DMA mode. + + Polling Mode + ============= + In Polling Mode, the SPI/I2S communication can be managed by 9 flags: + 1. SPI_I2S_FLAG_TXE : to indicate the status of the transmit buffer register + 2. SPI_I2S_FLAG_RXNE : to indicate the status of the receive buffer register + 3. SPI_I2S_FLAG_BSY : to indicate the state of the communication layer of the SPI. + 4. SPI_FLAG_CRCERR : to indicate if a CRC Calculation error occur + 5. SPI_FLAG_MODF : to indicate if a Mode Fault error occur + 6. SPI_I2S_FLAG_OVR : to indicate if an Overrun error occur + 7. I2S_FLAG_TIFRFE: to indicate a Frame Format error occurs. + 8. I2S_FLAG_UDR: to indicate an Underrun error occurs. + 9. I2S_FLAG_CHSIDE: to indicate Channel Side. + +@note Do not use the BSY flag to handle each data transmission or reception. It is + better to use the TXE and RXNE flags instead. + + In this Mode it is advised to use the following functions: + - FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); + - void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); + + Interrupt Mode + =============== + In Interrupt Mode, the SPI communication can be managed by 3 interrupt sources + and 7 pending bits: + Pending Bits: + ------------- + 1. SPI_I2S_IT_TXE : to indicate the status of the transmit buffer register + 2. SPI_I2S_IT_RXNE : to indicate the status of the receive buffer register + 3. SPI_IT_CRCERR : to indicate if a CRC Calculation error occur (available in SPI mode only) + 4. SPI_IT_MODF : to indicate if a Mode Fault error occur (available in SPI mode only) + 5. SPI_I2S_IT_OVR : to indicate if an Overrun error occur + 6. I2S_IT_UDR : to indicate an Underrun Error occurs (available in I2S mode only). + 7. I2S_FLAG_TIFRFE : to indicate a Frame Format error occurs (available in TI mode only). + + Interrupt Source: + ----------------- + 1. SPI_I2S_IT_TXE: specifies the interrupt source for the Tx buffer empty + interrupt. + 2. SPI_I2S_IT_RXNE : specifies the interrupt source for the Rx buffer not + empty interrupt. + 3. SPI_I2S_IT_ERR : specifies the interrupt source for the errors interrupt. + + In this Mode it is advised to use the following functions: + - void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState); + - ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); + - void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); + + DMA Mode + ======== + In DMA Mode, the SPI communication can be managed by 2 DMA Channel requests: + 1. SPI_I2S_DMAReq_Tx: specifies the Tx buffer DMA transfer request + 2. SPI_I2S_DMAReq_Rx: specifies the Rx buffer DMA transfer request + + In this Mode it is advised to use the following function: + - void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState); + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified SPI/I2S interrupts. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_IT: specifies the SPI interrupt source to be enabled or disabled. + * This parameter can be one of the following values: + * @arg SPI_I2S_IT_TXE: Tx buffer empty interrupt mask + * @arg SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask + * @arg SPI_I2S_IT_ERR: Error interrupt mask + * @param NewState: new state of the specified SPI interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState) +{ + uint16_t itpos = 0, itmask = 0 ; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT)); + + /* Get the SPI IT index */ + itpos = SPI_I2S_IT >> 4; + + /* Set the IT mask */ + itmask = (uint16_t)1 << (uint16_t)itpos; + + if (NewState != DISABLE) + { + /* Enable the selected SPI interrupt */ + SPIx->CR2 |= itmask; + } + else + { + /* Disable the selected SPI interrupt */ + SPIx->CR2 &= (uint16_t)~itmask; + } +} + +/** + * @brief Checks whether the specified SPIx/I2Sx flag is set or not. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_FLAG: specifies the SPI flag to check. + * This parameter can be one of the following values: + * @arg SPI_I2S_FLAG_TXE: Transmit buffer empty flag. + * @arg SPI_I2S_FLAG_RXNE: Receive buffer not empty flag. + * @arg SPI_I2S_FLAG_BSY: Busy flag. + * @arg SPI_I2S_FLAG_OVR: Overrun flag. + * @arg SPI_FLAG_MODF: Mode Fault flag. + * @arg SPI_FLAG_CRCERR: CRC Error flag. + * @arg SPI_I2S_FLAG_TIFRFE: Format Error. + * @arg I2S_FLAG_UDR: Underrun Error flag. + * @arg I2S_FLAG_CHSIDE: Channel Side flag. + * @retval The new state of SPI_I2S_FLAG (SET or RESET). + */ +FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG)); + + /* Check the status of the specified SPI flag */ + if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET) + { + /* SPI_I2S_FLAG is set */ + bitstatus = SET; + } + else + { + /* SPI_I2S_FLAG is reset */ + bitstatus = RESET; + } + /* Return the SPI_I2S_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the SPIx CRC Error (CRCERR) flag. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_FLAG: specifies the SPI flag to clear. + * This function clears only CRCERR flag. + * @arg SPI_FLAG_CRCERR: CRC Error flag. + * + * @note OVR (OverRun error) flag is cleared by software sequence: a read + * operation to SPI_DR register (SPI_I2S_ReceiveData()) followed by a read + * operation to SPI_SR register (SPI_I2S_GetFlagStatus()). + * @note UDR (UnderRun error) flag is cleared by a read operation to + * SPI_SR register (SPI_I2S_GetFlagStatus()). + * @note MODF (Mode Fault) flag is cleared by software sequence: a read/write + * operation to SPI_SR register (SPI_I2S_GetFlagStatus()) followed by a + * write operation to SPI_CR1 register (SPI_Cmd() to enable the SPI). + * + * @retval None + */ +void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG)); + + /* Clear the selected SPI CRC Error (CRCERR) flag */ + SPIx->SR = (uint16_t)~SPI_I2S_FLAG; +} + +/** + * @brief Checks whether the specified SPIx/I2Sx interrupt has occurred or not. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_IT: specifies the SPI interrupt source to check. + * This parameter can be one of the following values: + * @arg SPI_I2S_IT_TXE: Transmit buffer empty interrupt. + * @arg SPI_I2S_IT_RXNE: Receive buffer not empty interrupt. + * @arg SPI_I2S_IT_OVR: Overrun interrupt. + * @arg SPI_IT_MODF: Mode Fault interrupt. + * @arg SPI_IT_CRCERR: CRC Error interrupt. + * @arg I2S_IT_UDR: Underrun interrupt. + * @arg SPI_I2S_IT_TIFRFE: Format Error interrupt. + * @retval The new state of SPI_I2S_IT (SET or RESET). + */ +ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itpos = 0, itmask = 0, enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT)); + + /* Get the SPI_I2S_IT index */ + itpos = 0x01 << (SPI_I2S_IT & 0x0F); + + /* Get the SPI_I2S_IT IT mask */ + itmask = SPI_I2S_IT >> 4; + + /* Set the IT mask */ + itmask = 0x01 << itmask; + + /* Get the SPI_I2S_IT enable bit status */ + enablestatus = (SPIx->CR2 & itmask) ; + + /* Check the status of the specified SPI interrupt */ + if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus) + { + /* SPI_I2S_IT is set */ + bitstatus = SET; + } + else + { + /* SPI_I2S_IT is reset */ + bitstatus = RESET; + } + /* Return the SPI_I2S_IT status */ + return bitstatus; +} + +/** + * @brief Clears the SPIx CRC Error (CRCERR) interrupt pending bit. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_IT: specifies the SPI interrupt pending bit to clear. + * This function clears only CRCERR interrupt pending bit. + * @arg SPI_IT_CRCERR: CRC Error interrupt. + * + * @note OVR (OverRun Error) interrupt pending bit is cleared by software + * sequence: a read operation to SPI_DR register (SPI_I2S_ReceiveData()) + * followed by a read operation to SPI_SR register (SPI_I2S_GetITStatus()). + * @note UDR (UnderRun Error) interrupt pending bit is cleared by a read + * operation to SPI_SR register (SPI_I2S_GetITStatus()). + * @note MODF (Mode Fault) interrupt pending bit is cleared by software sequence: + * a read/write operation to SPI_SR register (SPI_I2S_GetITStatus()) + * followed by a write operation to SPI_CR1 register (SPI_Cmd() to enable + * the SPI). + * @retval None + */ +void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) +{ + uint16_t itpos = 0; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT)); + + /* Get the SPI_I2S IT index */ + itpos = 0x01 << (SPI_I2S_IT & 0x0F); + + /* Clear the selected SPI CRC Error (CRCERR) interrupt pending bit */ + SPIx->SR = (uint16_t)~itpos; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_syscfg.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_syscfg.c new file mode 100644 index 000000000..2625cfee4 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_syscfg.c @@ -0,0 +1,197 @@ +/** + ****************************************************************************** + * @file stm32f4xx_syscfg.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the SYSCFG peripheral. + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * + * This driver provides functions for: + * + * 1. Remapping the memory accessible in the code area using SYSCFG_MemoryRemapConfig() + * + * 2. Manage the EXTI lines connection to the GPIOs using SYSCFG_EXTILineConfig() + * + * 3. Select the ETHERNET media interface (RMII/RII) using SYSCFG_ETH_MediaInterfaceConfig() + * + * @note SYSCFG APB clock must be enabled to get write access to SYSCFG registers, + * using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_syscfg.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup SYSCFG + * @brief SYSCFG driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* ------------ RCC registers bit address in the alias region ----------- */ +#define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE) +/* --- PMC Register ---*/ +/* Alias word address of MII_RMII_SEL bit */ +#define PMC_OFFSET (SYSCFG_OFFSET + 0x04) +#define MII_RMII_SEL_BitNumber ((uint8_t)0x17) +#define PMC_MII_RMII_SEL_BB (PERIPH_BB_BASE + (PMC_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4)) + +/* --- CMPCR Register ---*/ +/* Alias word address of CMP_PD bit */ +#define CMPCR_OFFSET (SYSCFG_OFFSET + 0x20) +#define CMP_PD_BitNumber ((uint8_t)0x00) +#define CMPCR_CMP_PD_BB (PERIPH_BB_BASE + (CMPCR_OFFSET * 32) + (CMP_PD_BitNumber * 4)) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup SYSCFG_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the Alternate Functions (remap and EXTI configuration) + * registers to their default reset values. + * @param None + * @retval None + */ +void SYSCFG_DeInit(void) +{ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SYSCFG, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SYSCFG, DISABLE); +} + +/** + * @brief Changes the mapping of the specified pin. + * @param SYSCFG_Memory: selects the memory remapping. + * This parameter can be one of the following values: + * @arg SYSCFG_MemoryRemap_Flash: Main Flash memory mapped at 0x00000000 + * @arg SYSCFG_MemoryRemap_SystemFlash: System Flash memory mapped at 0x00000000 + * @arg SYSCFG_MemoryRemap_FSMC: FSMC (Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 + * @arg SYSCFG_MemoryRemap_SRAM: Embedded SRAM (112kB) mapped at 0x00000000 + * @retval None + */ +void SYSCFG_MemoryRemapConfig(uint8_t SYSCFG_MemoryRemap) +{ + /* Check the parameters */ + assert_param(IS_SYSCFG_MEMORY_REMAP_CONFING(SYSCFG_MemoryRemap)); + + SYSCFG->MEMRMP = SYSCFG_MemoryRemap; +} + +/** + * @brief Selects the GPIO pin used as EXTI Line. + * @param EXTI_PortSourceGPIOx : selects the GPIO port to be used as source for + * EXTI lines where x can be (A..I). + * @param EXTI_PinSourcex: specifies the EXTI line to be configured. + * This parameter can be EXTI_PinSourcex where x can be (0..15, except + * for EXTI_PortSourceGPIOI x can be (0..11). + * @retval None + */ +void SYSCFG_EXTILineConfig(uint8_t EXTI_PortSourceGPIOx, uint8_t EXTI_PinSourcex) +{ + uint32_t tmp = 0x00; + + /* Check the parameters */ + assert_param(IS_EXTI_PORT_SOURCE(EXTI_PortSourceGPIOx)); + assert_param(IS_EXTI_PIN_SOURCE(EXTI_PinSourcex)); + + tmp = ((uint32_t)0x0F) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03)); + SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] &= ~tmp; + SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] |= (((uint32_t)EXTI_PortSourceGPIOx) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03))); +} + +/** + * @brief Selects the ETHERNET media interface + * @param SYSCFG_ETH_MediaInterface: specifies the Media Interface mode. + * This parameter can be one of the following values: + * @arg SYSCFG_ETH_MediaInterface_MII: MII mode selected + * @arg SYSCFG_ETH_MediaInterface_RMII: RMII mode selected + * @retval None + */ +void SYSCFG_ETH_MediaInterfaceConfig(uint32_t SYSCFG_ETH_MediaInterface) +{ + assert_param(IS_SYSCFG_ETH_MEDIA_INTERFACE(SYSCFG_ETH_MediaInterface)); + /* Configure MII_RMII selection bit */ + *(__IO uint32_t *) PMC_MII_RMII_SEL_BB = SYSCFG_ETH_MediaInterface; +} + +/** + * @brief Enables or disables the I/O Compensation Cell. + * @note The I/O compensation cell can be used only when the device supply + * voltage ranges from 2.4 to 3.6 V. + * @param NewState: new state of the I/O Compensation Cell. + * This parameter can be one of the following values: + * @arg ENABLE: I/O compensation cell enabled + * @arg DISABLE: I/O compensation cell power-down mode + * @retval None + */ +void SYSCFG_CompensationCellCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMPCR_CMP_PD_BB = (uint32_t)NewState; +} + +/** + * @brief Checks whether the I/O Compensation Cell ready flag is set or not. + * @param None + * @retval The new state of the I/O Compensation Cell ready flag (SET or RESET) + */ +FlagStatus SYSCFG_GetCompensationCellStatus(void) +{ + FlagStatus bitstatus = RESET; + + if ((SYSCFG->CMPCR & SYSCFG_CMPCR_READY ) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c new file mode 100644 index 000000000..6c640e738 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c @@ -0,0 +1,3352 @@ +/** + ****************************************************************************** + * @file stm32f4xx_tim.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the TIM peripheral: + * - TimeBase management + * - Output Compare management + * - Input Capture management + * - Advanced-control timers (TIM1 and TIM8) specific features + * - Interrupts, DMA and flags management + * - Clocks management + * - Synchronization management + * - Specific interface management + * - Specific remapping management + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * This driver provides functions to configure and program the TIM + * of all STM32F4xx devices. + * These functions are split in 9 groups: + * + * 1. TIM TimeBase management: this group includes all needed functions + * to configure the TM Timebase unit: + * - Set/Get Prescaler + * - Set/Get Autoreload + * - Counter modes configuration + * - Set Clock division + * - Select the One Pulse mode + * - Update Request Configuration + * - Update Disable Configuration + * - Auto-Preload Configuration + * - Enable/Disable the counter + * + * 2. TIM Output Compare management: this group includes all needed + * functions to configure the Capture/Compare unit used in Output + * compare mode: + * - Configure each channel, independently, in Output Compare mode + * - Select the output compare modes + * - Select the Polarities of each channel + * - Set/Get the Capture/Compare register values + * - Select the Output Compare Fast mode + * - Select the Output Compare Forced mode + * - Output Compare-Preload Configuration + * - Clear Output Compare Reference + * - Select the OCREF Clear signal + * - Enable/Disable the Capture/Compare Channels + * + * 3. TIM Input Capture management: this group includes all needed + * functions to configure the Capture/Compare unit used in + * Input Capture mode: + * - Configure each channel in input capture mode + * - Configure Channel1/2 in PWM Input mode + * - Set the Input Capture Prescaler + * - Get the Capture/Compare values + * + * 4. Advanced-control timers (TIM1 and TIM8) specific features + * - Configures the Break input, dead time, Lock level, the OSSI, + * the OSSR State and the AOE(automatic output enable) + * - Enable/Disable the TIM peripheral Main Outputs + * - Select the Commutation event + * - Set/Reset the Capture Compare Preload Control bit + * + * 5. TIM interrupts, DMA and flags management + * - Enable/Disable interrupt sources + * - Get flags status + * - Clear flags/ Pending bits + * - Enable/Disable DMA requests + * - Configure DMA burst mode + * - Select CaptureCompare DMA request + * + * 6. TIM clocks management: this group includes all needed functions + * to configure the clock controller unit: + * - Select internal/External clock + * - Select the external clock mode: ETR(Mode1/Mode2), TIx or ITRx + * + * 7. TIM synchronization management: this group includes all needed + * functions to configure the Synchronization unit: + * - Select Input Trigger + * - Select Output Trigger + * - Select Master Slave Mode + * - ETR Configuration when used as external trigger + * + * 8. TIM specific interface management, this group includes all + * needed functions to use the specific TIM interface: + * - Encoder Interface Configuration + * - Select Hall Sensor + * + * 9. TIM specific remapping management includes the Remapping + * configuration of specific timers + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_tim.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup TIM + * @brief TIM driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* ---------------------- TIM registers bit mask ------------------------ */ +#define SMCR_ETR_MASK ((uint16_t)0x00FF) +#define CCMR_OFFSET ((uint16_t)0x0018) +#define CCER_CCE_SET ((uint16_t)0x0001) +#define CCER_CCNE_SET ((uint16_t)0x0004) +#define CCMR_OC13M_MASK ((uint16_t)0xFF8F) +#define CCMR_OC24M_MASK ((uint16_t)0x8FFF) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); + +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup TIM_Private_Functions + * @{ + */ + +/** @defgroup TIM_Group1 TimeBase management functions + * @brief TimeBase management functions + * +@verbatim + =============================================================================== + TimeBase management functions + =============================================================================== + + =================================================================== + TIM Driver: how to use it in Timing(Time base) Mode + =================================================================== + To use the Timer in Timing(Time base) mode, the following steps are mandatory: + + 1. Enable TIM clock using RCC_APBxPeriphClockCmd(RCC_APBxPeriph_TIMx, ENABLE) function + + 2. Fill the TIM_TimeBaseInitStruct with the desired parameters. + + 3. Call TIM_TimeBaseInit(TIMx, &TIM_TimeBaseInitStruct) to configure the Time Base unit + with the corresponding configuration + + 4. Enable the NVIC if you need to generate the update interrupt. + + 5. Enable the corresponding interrupt using the function TIM_ITConfig(TIMx, TIM_IT_Update) + + 6. Call the TIM_Cmd(ENABLE) function to enable the TIM counter. + + Note1: All other functions can be used separately to modify, if needed, + a specific feature of the Timer. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the TIMx peripheral registers to their default reset values. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @retval None + + */ +void TIM_DeInit(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + if (TIMx == TIM1) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, DISABLE); + } + else if (TIMx == TIM2) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE); + } + else if (TIMx == TIM3) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE); + } + else if (TIMx == TIM4) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE); + } + else if (TIMx == TIM5) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, DISABLE); + } + else if (TIMx == TIM6) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, DISABLE); + } + else if (TIMx == TIM7) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, DISABLE); + } + else if (TIMx == TIM8) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, DISABLE); + } + else if (TIMx == TIM9) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, DISABLE); + } + else if (TIMx == TIM10) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, DISABLE); + } + else if (TIMx == TIM11) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, DISABLE); + } + else if (TIMx == TIM12) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, DISABLE); + } + else if (TIMx == TIM13) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, DISABLE); + } + else + { + if (TIMx == TIM14) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, DISABLE); + } + } +} + +/** + * @brief Initializes the TIMx Time Base Unit peripheral according to + * the specified parameters in the TIM_TimeBaseInitStruct. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param TIM_TimeBaseInitStruct: pointer to a TIM_TimeBaseInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, const TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +{ + uint16_t tmpcr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_COUNTER_MODE(TIM_TimeBaseInitStruct->TIM_CounterMode)); + assert_param(IS_TIM_CKD_DIV(TIM_TimeBaseInitStruct->TIM_ClockDivision)); + + tmpcr1 = TIMx->CR1; + + if((TIMx == TIM1) || (TIMx == TIM8)|| + (TIMx == TIM2) || (TIMx == TIM3)|| + (TIMx == TIM4) || (TIMx == TIM5)) + { + /* Select the Counter Mode */ + tmpcr1 &= (uint16_t)(~(TIM_CR1_DIR | TIM_CR1_CMS)); + tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_CounterMode; + } + + if((TIMx != TIM6) && (TIMx != TIM7)) + { + /* Set the clock division */ + tmpcr1 &= (uint16_t)(~TIM_CR1_CKD); + tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_ClockDivision; + } + + TIMx->CR1 = tmpcr1; + + /* Set the Autoreload value */ + TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period ; + + /* Set the Prescaler value */ + TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler; + + if ((TIMx == TIM1) || (TIMx == TIM8)) + { + /* Set the Repetition Counter value */ + TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter; + } + + /* Generate an update event to reload the Prescaler + and the repetition counter(only for TIM1 and TIM8) value immediatly */ + TIMx->EGR = TIM_PSCReloadMode_Immediate; +} + +/** + * @brief Fills each TIM_TimeBaseInitStruct member with its default value. + * @param TIM_TimeBaseInitStruct : pointer to a TIM_TimeBaseInitTypeDef + * structure which will be initialized. + * @retval None + */ +void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +{ + /* Set the default configuration */ + TIM_TimeBaseInitStruct->TIM_Period = 0xFFFFFFFF; + TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000; + TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1; + TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000; +} + +/** + * @brief Configures the TIMx Prescaler. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param Prescaler: specifies the Prescaler Register value + * @param TIM_PSCReloadMode: specifies the TIM Prescaler Reload mode + * This parameter can be one of the following values: + * @arg TIM_PSCReloadMode_Update: The Prescaler is loaded at the update event. + * @arg TIM_PSCReloadMode_Immediate: The Prescaler is loaded immediatly. + * @retval None + */ +void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_PRESCALER_RELOAD(TIM_PSCReloadMode)); + /* Set the Prescaler value */ + TIMx->PSC = Prescaler; + /* Set or reset the UG Bit */ + TIMx->EGR = TIM_PSCReloadMode; +} + +/** + * @brief Specifies the TIMx Counter Mode to be used. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_CounterMode: specifies the Counter Mode to be used + * This parameter can be one of the following values: + * @arg TIM_CounterMode_Up: TIM Up Counting Mode + * @arg TIM_CounterMode_Down: TIM Down Counting Mode + * @arg TIM_CounterMode_CenterAligned1: TIM Center Aligned Mode1 + * @arg TIM_CounterMode_CenterAligned2: TIM Center Aligned Mode2 + * @arg TIM_CounterMode_CenterAligned3: TIM Center Aligned Mode3 + * @retval None + */ +void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode) +{ + uint16_t tmpcr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_COUNTER_MODE(TIM_CounterMode)); + + tmpcr1 = TIMx->CR1; + + /* Reset the CMS and DIR Bits */ + tmpcr1 &= (uint16_t)~(TIM_CR1_DIR | TIM_CR1_CMS); + + /* Set the Counter Mode */ + tmpcr1 |= TIM_CounterMode; + + /* Write to TIMx CR1 register */ + TIMx->CR1 = tmpcr1; +} + +/** + * @brief Sets the TIMx Counter Register value + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param Counter: specifies the Counter register new value. + * @retval None + */ +void TIM_SetCounter(TIM_TypeDef* TIMx, uint32_t Counter) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Set the Counter Register value */ + TIMx->CNT = Counter; +} + +/** + * @brief Sets the TIMx Autoreload Register value + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param Autoreload: specifies the Autoreload register new value. + * @retval None + */ +void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint32_t Autoreload) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Set the Autoreload Register value */ + TIMx->ARR = Autoreload; +} + +/** + * @brief Gets the TIMx Counter value. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @retval Counter Register value + */ +uint32_t TIM_GetCounter(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Get the Counter Register value */ + return TIMx->CNT; +} + +/** + * @brief Gets the TIMx Prescaler value. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @retval Prescaler Register value. + */ +uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Get the Prescaler Register value */ + return TIMx->PSC; +} + +/** + * @brief Enables or Disables the TIMx Update event. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param NewState: new state of the TIMx UDIS bit + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the Update Disable Bit */ + TIMx->CR1 |= TIM_CR1_UDIS; + } + else + { + /* Reset the Update Disable Bit */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_UDIS; + } +} + +/** + * @brief Configures the TIMx Update Request Interrupt source. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param TIM_UpdateSource: specifies the Update source. + * This parameter can be one of the following values: + * @arg TIM_UpdateSource_Global: Source of update is the counter + * overflow/underflow or the setting of UG bit, or an update + * generation through the slave mode controller. + * @arg TIM_UpdateSource_Regular: Source of update is counter overflow/underflow. + * @retval None + */ +void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_UPDATE_SOURCE(TIM_UpdateSource)); + + if (TIM_UpdateSource != TIM_UpdateSource_Global) + { + /* Set the URS Bit */ + TIMx->CR1 |= TIM_CR1_URS; + } + else + { + /* Reset the URS Bit */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_URS; + } +} + +/** + * @brief Enables or disables TIMx peripheral Preload register on ARR. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param NewState: new state of the TIMx peripheral Preload register + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the ARR Preload Bit */ + TIMx->CR1 |= TIM_CR1_ARPE; + } + else + { + /* Reset the ARR Preload Bit */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_ARPE; + } +} + +/** + * @brief Selects the TIMx's One Pulse Mode. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param TIM_OPMode: specifies the OPM Mode to be used. + * This parameter can be one of the following values: + * @arg TIM_OPMode_Single + * @arg TIM_OPMode_Repetitive + * @retval None + */ +void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_OPM_MODE(TIM_OPMode)); + + /* Reset the OPM Bit */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_OPM; + + /* Configure the OPM Mode */ + TIMx->CR1 |= TIM_OPMode; +} + +/** + * @brief Sets the TIMx Clock Division value. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_CKD: specifies the clock division value. + * This parameter can be one of the following value: + * @arg TIM_CKD_DIV1: TDTS = Tck_tim + * @arg TIM_CKD_DIV2: TDTS = 2*Tck_tim + * @arg TIM_CKD_DIV4: TDTS = 4*Tck_tim + * @retval None + */ +void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_CKD_DIV(TIM_CKD)); + + /* Reset the CKD Bits */ + TIMx->CR1 &= (uint16_t)(~TIM_CR1_CKD); + + /* Set the CKD value */ + TIMx->CR1 |= TIM_CKD; +} + +/** + * @brief Enables or disables the specified TIM peripheral. + * @param TIMx: where x can be 1 to 14 to select the TIMx peripheral. + * @param NewState: new state of the TIMx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the TIM Counter */ + TIMx->CR1 |= TIM_CR1_CEN; + } + else + { + /* Disable the TIM Counter */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_CEN; + } +} +/** + * @} + */ + +/** @defgroup TIM_Group2 Output Compare management functions + * @brief Output Compare management functions + * +@verbatim + =============================================================================== + Output Compare management functions + =============================================================================== + + =================================================================== + TIM Driver: how to use it in Output Compare Mode + =================================================================== + To use the Timer in Output Compare mode, the following steps are mandatory: + + 1. Enable TIM clock using RCC_APBxPeriphClockCmd(RCC_APBxPeriph_TIMx, ENABLE) function + + 2. Configure the TIM pins by configuring the corresponding GPIO pins + + 2. Configure the Time base unit as described in the first part of this driver, + if needed, else the Timer will run with the default configuration: + - Autoreload value = 0xFFFF + - Prescaler value = 0x0000 + - Counter mode = Up counting + - Clock Division = TIM_CKD_DIV1 + + 3. Fill the TIM_OCInitStruct with the desired parameters including: + - The TIM Output Compare mode: TIM_OCMode + - TIM Output State: TIM_OutputState + - TIM Pulse value: TIM_Pulse + - TIM Output Compare Polarity : TIM_OCPolarity + + 4. Call TIM_OCxInit(TIMx, &TIM_OCInitStruct) to configure the desired channel with the + corresponding configuration + + 5. Call the TIM_Cmd(ENABLE) function to enable the TIM counter. + + Note1: All other functions can be used separately to modify, if needed, + a specific feature of the Timer. + + Note2: In case of PWM mode, this function is mandatory: + TIM_OCxPreloadConfig(TIMx, TIM_OCPreload_ENABLE); + + Note3: If the corresponding interrupt or DMA request are needed, the user should: + 1. Enable the NVIC (or the DMA) to use the TIM interrupts (or DMA requests). + 2. Enable the corresponding interrupt (or DMA request) using the function + TIM_ITConfig(TIMx, TIM_IT_CCx) (or TIM_DMA_Cmd(TIMx, TIM_DMA_CCx)) + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the TIMx Channel1 according to the specified parameters in + * the TIM_OCInitStruct. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC1Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC1E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare Mode Bits */ + tmpccmrx &= (uint16_t)~TIM_CCMR1_OC1M; + tmpccmrx &= (uint16_t)~TIM_CCMR1_CC1S; + /* Select the Output Compare Mode */ + tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)~TIM_CCER_CC1P; + /* Set the Output Compare Polarity */ + tmpccer |= TIM_OCInitStruct->TIM_OCPolarity; + + /* Set the Output State */ + tmpccer |= TIM_OCInitStruct->TIM_OutputState; + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)~TIM_CCER_CC1NP; + /* Set the Output N Polarity */ + tmpccer |= TIM_OCInitStruct->TIM_OCNPolarity; + /* Reset the Output N State */ + tmpccer &= (uint16_t)~TIM_CCER_CC1NE; + + /* Set the Output N State */ + tmpccer |= TIM_OCInitStruct->TIM_OutputNState; + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)~TIM_CR2_OIS1; + tmpcr2 &= (uint16_t)~TIM_CR2_OIS1N; + /* Set the Output Idle state */ + tmpcr2 |= TIM_OCInitStruct->TIM_OCIdleState; + /* Set the Output N Idle state */ + tmpcr2 |= TIM_OCInitStruct->TIM_OCNIdleState; + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR1 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel2 according to the specified parameters + * in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC2Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC2E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)~TIM_CCMR1_OC2M; + tmpccmrx &= (uint16_t)~TIM_CCMR1_CC2S; + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)~TIM_CCER_CC2P; + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 4); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 4); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)~TIM_CCER_CC2NP; + /* Set the Output N Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 4); + /* Reset the Output N State */ + tmpccer &= (uint16_t)~TIM_CCER_CC2NE; + + /* Set the Output N State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 4); + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)~TIM_CR2_OIS2; + tmpcr2 &= (uint16_t)~TIM_CR2_OIS2N; + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 2); + /* Set the Output N Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 2); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR2 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel3 according to the specified parameters + * in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC3Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + + /* Disable the Channel 3: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC3E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)~TIM_CCMR2_OC3M; + tmpccmrx &= (uint16_t)~TIM_CCMR2_CC3S; + /* Select the Output Compare Mode */ + tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)~TIM_CCER_CC3P; + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 8); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 8); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)~TIM_CCER_CC3NP; + /* Set the Output N Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 8); + /* Reset the Output N State */ + tmpccer &= (uint16_t)~TIM_CCER_CC3NE; + + /* Set the Output N State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 8); + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)~TIM_CR2_OIS3; + tmpcr2 &= (uint16_t)~TIM_CR2_OIS3N; + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 4); + /* Set the Output N Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 4); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR3 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel4 according to the specified parameters + * in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC4Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC4E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)~TIM_CCMR2_OC4M; + tmpccmrx &= (uint16_t)~TIM_CCMR2_CC4S; + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)~TIM_CCER_CC4P; + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 12); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 12); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + /* Reset the Output Compare IDLE State */ + tmpcr2 &=(uint16_t) ~TIM_CR2_OIS4; + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 6); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR4 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Fills each TIM_OCInitStruct member with its default value. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure which will + * be initialized. + * @retval None + */ +void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + /* Set the default configuration */ + TIM_OCInitStruct->TIM_OCMode = TIM_OCMode_Timing; + TIM_OCInitStruct->TIM_OutputState = TIM_OutputState_Disable; + TIM_OCInitStruct->TIM_OutputNState = TIM_OutputNState_Disable; + TIM_OCInitStruct->TIM_Pulse = 0x00000000; + TIM_OCInitStruct->TIM_OCPolarity = TIM_OCPolarity_High; + TIM_OCInitStruct->TIM_OCNPolarity = TIM_OCPolarity_High; + TIM_OCInitStruct->TIM_OCIdleState = TIM_OCIdleState_Reset; + TIM_OCInitStruct->TIM_OCNIdleState = TIM_OCNIdleState_Reset; +} + +/** + * @brief Selects the TIM Output Compare Mode. + * @note This function disables the selected channel before changing the Output + * Compare Mode. If needed, user has to enable this channel using + * TIM_CCxCmd() and TIM_CCxNCmd() functions. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @arg TIM_Channel_4: TIM Channel 4 + * @param TIM_OCMode: specifies the TIM Output Compare Mode. + * This parameter can be one of the following values: + * @arg TIM_OCMode_Timing + * @arg TIM_OCMode_Active + * @arg TIM_OCMode_Toggle + * @arg TIM_OCMode_PWM1 + * @arg TIM_OCMode_PWM2 + * @arg TIM_ForcedAction_Active + * @arg TIM_ForcedAction_InActive + * @retval None + */ +void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode) +{ + uint32_t tmp = 0; + uint16_t tmp1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_OCM(TIM_OCMode)); + + tmp = (uint32_t) TIMx; + tmp += CCMR_OFFSET; + + tmp1 = CCER_CCE_SET << (uint16_t)TIM_Channel; + + /* Disable the Channel: Reset the CCxE Bit */ + TIMx->CCER &= (uint16_t) ~tmp1; + + if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) + { + tmp += (TIM_Channel>>1); + + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= CCMR_OC13M_MASK; + + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= TIM_OCMode; + } + else + { + tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1; + + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= CCMR_OC24M_MASK; + + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8); + } +} + +/** + * @brief Sets the TIMx Capture Compare1 Register value + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param Compare1: specifies the Capture Compare1 register new value. + * @retval None + */ +void TIM_SetCompare1(TIM_TypeDef* TIMx, uint32_t Compare1) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + + /* Set the Capture Compare1 Register value */ + TIMx->CCR1 = Compare1; +} + +/** + * @brief Sets the TIMx Capture Compare2 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param Compare2: specifies the Capture Compare2 register new value. + * @retval None + */ +void TIM_SetCompare2(TIM_TypeDef* TIMx, uint32_t Compare2) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + + /* Set the Capture Compare2 Register value */ + TIMx->CCR2 = Compare2; +} + +/** + * @brief Sets the TIMx Capture Compare3 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param Compare3: specifies the Capture Compare3 register new value. + * @retval None + */ +void TIM_SetCompare3(TIM_TypeDef* TIMx, uint32_t Compare3) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + + /* Set the Capture Compare3 Register value */ + TIMx->CCR3 = Compare3; +} + +/** + * @brief Sets the TIMx Capture Compare4 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param Compare4: specifies the Capture Compare4 register new value. + * @retval None + */ +void TIM_SetCompare4(TIM_TypeDef* TIMx, uint32_t Compare4) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + + /* Set the Capture Compare4 Register value */ + TIMx->CCR4 = Compare4; +} + +/** + * @brief Forces the TIMx output 1 waveform to active or inactive level. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC1REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC1REF. + * @retval None + */ +void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1M Bits */ + tmpccmr1 &= (uint16_t)~TIM_CCMR1_OC1M; + + /* Configure The Forced output Mode */ + tmpccmr1 |= TIM_ForcedAction; + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Forces the TIMx output 2 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC2REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC2REF. + * @retval None + */ +void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC2M Bits */ + tmpccmr1 &= (uint16_t)~TIM_CCMR1_OC2M; + + /* Configure The Forced output Mode */ + tmpccmr1 |= (uint16_t)(TIM_ForcedAction << 8); + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Forces the TIMx output 3 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC3REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC3REF. + * @retval None + */ +void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC1M Bits */ + tmpccmr2 &= (uint16_t)~TIM_CCMR2_OC3M; + + /* Configure The Forced output Mode */ + tmpccmr2 |= TIM_ForcedAction; + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Forces the TIMx output 4 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC4REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC4REF. + * @retval None + */ +void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC2M Bits */ + tmpccmr2 &= (uint16_t)~TIM_CCMR2_OC4M; + + /* Configure The Forced output Mode */ + tmpccmr2 |= (uint16_t)(TIM_ForcedAction << 8); + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR1. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1PE Bit */ + tmpccmr1 &= (uint16_t)(~TIM_CCMR1_OC1PE); + + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr1 |= TIM_OCPreload; + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR2. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC2PE Bit */ + tmpccmr1 &= (uint16_t)(~TIM_CCMR1_OC2PE); + + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr1 |= (uint16_t)(TIM_OCPreload << 8); + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR3. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC3PE Bit */ + tmpccmr2 &= (uint16_t)(~TIM_CCMR2_OC3PE); + + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr2 |= TIM_OCPreload; + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR4. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC4PE Bit */ + tmpccmr2 &= (uint16_t)(~TIM_CCMR2_OC4PE); + + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr2 |= (uint16_t)(TIM_OCPreload << 8); + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx Output Compare 1 Fast feature. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1FE Bit */ + tmpccmr1 &= (uint16_t)~TIM_CCMR1_OC1FE; + + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr1 |= TIM_OCFast; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Configures the TIMx Output Compare 2 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC2FE Bit */ + tmpccmr1 &= (uint16_t)(~TIM_CCMR1_OC2FE); + + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr1 |= (uint16_t)(TIM_OCFast << 8); + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Configures the TIMx Output Compare 3 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC3FE Bit */ + tmpccmr2 &= (uint16_t)~TIM_CCMR2_OC3FE; + + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr2 |= TIM_OCFast; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx Output Compare 4 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC4FE Bit */ + tmpccmr2 &= (uint16_t)(~TIM_CCMR2_OC4FE); + + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr2 |= (uint16_t)(TIM_OCFast << 8); + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF1 signal on an external event + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1CE Bit */ + tmpccmr1 &= (uint16_t)~TIM_CCMR1_OC1CE; + + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr1 |= TIM_OCClear; + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Clears or safeguards the OCREF2 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC2CE Bit */ + tmpccmr1 &= (uint16_t)~TIM_CCMR1_OC2CE; + + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr1 |= (uint16_t)(TIM_OCClear << 8); + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Clears or safeguards the OCREF3 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC3CE Bit */ + tmpccmr2 &= (uint16_t)~TIM_CCMR2_OC3CE; + + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr2 |= TIM_OCClear; + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF4 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC4CE Bit */ + tmpccmr2 &= (uint16_t)~TIM_CCMR2_OC4CE; + + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr2 |= (uint16_t)(TIM_OCClear << 8); + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx channel 1 polarity. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC1 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC1P Bit */ + tmpccer &= (uint16_t)(~TIM_CCER_CC1P); + tmpccer |= TIM_OCPolarity; + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 1N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC1N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC1NP Bit */ + tmpccer &= (uint16_t)~TIM_CCER_CC1NP; + tmpccer |= TIM_OCNPolarity; + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 2 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_OCPolarity: specifies the OC2 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC2P Bit */ + tmpccer &= (uint16_t)(~TIM_CCER_CC2P); + tmpccer |= (uint16_t)(TIM_OCPolarity << 4); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 2N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC2N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC2NP Bit */ + tmpccer &= (uint16_t)~TIM_CCER_CC2NP; + tmpccer |= (uint16_t)(TIM_OCNPolarity << 4); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 3 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC3 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC3P Bit */ + tmpccer &= (uint16_t)~TIM_CCER_CC3P; + tmpccer |= (uint16_t)(TIM_OCPolarity << 8); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 3N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC3N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC3NP Bit */ + tmpccer &= (uint16_t)~TIM_CCER_CC3NP; + tmpccer |= (uint16_t)(TIM_OCNPolarity << 8); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 4 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC4 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC4P Bit */ + tmpccer &= (uint16_t)~TIM_CCER_CC4P; + tmpccer |= (uint16_t)(TIM_OCPolarity << 12); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel x. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @arg TIM_Channel_4: TIM Channel 4 + * @param TIM_CCx: specifies the TIM Channel CCxE bit new state. + * This parameter can be: TIM_CCx_Enable or TIM_CCx_Disable. + * @retval None + */ +void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx) +{ + uint16_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_CCX(TIM_CCx)); + + tmp = CCER_CCE_SET << TIM_Channel; + + /* Reset the CCxE Bit */ + TIMx->CCER &= (uint16_t)~ tmp; + + /* Set or reset the CCxE Bit */ + TIMx->CCER |= (uint16_t)(TIM_CCx << TIM_Channel); +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel xN. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @param TIM_CCxN: specifies the TIM Channel CCxNE bit new state. + * This parameter can be: TIM_CCxN_Enable or TIM_CCxN_Disable. + * @retval None + */ +void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN) +{ + uint16_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_COMPLEMENTARY_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_CCXN(TIM_CCxN)); + + tmp = CCER_CCNE_SET << TIM_Channel; + + /* Reset the CCxNE Bit */ + TIMx->CCER &= (uint16_t) ~tmp; + + /* Set or reset the CCxNE Bit */ + TIMx->CCER |= (uint16_t)(TIM_CCxN << TIM_Channel); +} +/** + * @} + */ + +/** @defgroup TIM_Group3 Input Capture management functions + * @brief Input Capture management functions + * +@verbatim + =============================================================================== + Input Capture management functions + =============================================================================== + + =================================================================== + TIM Driver: how to use it in Input Capture Mode + =================================================================== + To use the Timer in Input Capture mode, the following steps are mandatory: + + 1. Enable TIM clock using RCC_APBxPeriphClockCmd(RCC_APBxPeriph_TIMx, ENABLE) function + + 2. Configure the TIM pins by configuring the corresponding GPIO pins + + 2. Configure the Time base unit as described in the first part of this driver, + if needed, else the Timer will run with the default configuration: + - Autoreload value = 0xFFFF + - Prescaler value = 0x0000 + - Counter mode = Up counting + - Clock Division = TIM_CKD_DIV1 + + 3. Fill the TIM_ICInitStruct with the desired parameters including: + - TIM Channel: TIM_Channel + - TIM Input Capture polarity: TIM_ICPolarity + - TIM Input Capture selection: TIM_ICSelection + - TIM Input Capture Prescaler: TIM_ICPrescaler + - TIM Input CApture filter value: TIM_ICFilter + + 4. Call TIM_ICInit(TIMx, &TIM_ICInitStruct) to configure the desired channel with the + corresponding configuration and to measure only frequency or duty cycle of the input signal, + or, + Call TIM_PWMIConfig(TIMx, &TIM_ICInitStruct) to configure the desired channels with the + corresponding configuration and to measure the frequency and the duty cycle of the input signal + + 5. Enable the NVIC or the DMA to read the measured frequency. + + 6. Enable the corresponding interrupt (or DMA request) to read the Captured value, + using the function TIM_ITConfig(TIMx, TIM_IT_CCx) (or TIM_DMA_Cmd(TIMx, TIM_DMA_CCx)) + + 7. Call the TIM_Cmd(ENABLE) function to enable the TIM counter. + + 8. Use TIM_GetCapturex(TIMx); to read the captured value. + + Note1: All other functions can be used separately to modify, if needed, + a specific feature of the Timer. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the TIM peripheral according to the specified parameters + * in the TIM_ICInitStruct. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_IC_POLARITY(TIM_ICInitStruct->TIM_ICPolarity)); + assert_param(IS_TIM_IC_SELECTION(TIM_ICInitStruct->TIM_ICSelection)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICInitStruct->TIM_ICPrescaler)); + assert_param(IS_TIM_IC_FILTER(TIM_ICInitStruct->TIM_ICFilter)); + + if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) + { + /* TI1 Configuration */ + TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_2) + { + /* TI2 Configuration */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_3) + { + /* TI3 Configuration */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + TI3_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC3Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else + { + /* TI4 Configuration */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + TI4_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC4Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } +} + +/** + * @brief Fills each TIM_ICInitStruct member with its default value. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure which will + * be initialized. + * @retval None + */ +void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + /* Set the default configuration */ + TIM_ICInitStruct->TIM_Channel = TIM_Channel_1; + TIM_ICInitStruct->TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStruct->TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStruct->TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStruct->TIM_ICFilter = 0x00; +} + +/** + * @brief Configures the TIM peripheral according to the specified parameters + * in the TIM_ICInitStruct to measure an external PWM signal. + * @param TIMx: where x can be 1, 2, 3, 4, 5,8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + uint16_t icoppositepolarity = TIM_ICPolarity_Rising; + uint16_t icoppositeselection = TIM_ICSelection_DirectTI; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + + /* Select the Opposite Input Polarity */ + if (TIM_ICInitStruct->TIM_ICPolarity == TIM_ICPolarity_Rising) + { + icoppositepolarity = TIM_ICPolarity_Falling; + } + else + { + icoppositepolarity = TIM_ICPolarity_Rising; + } + /* Select the Opposite Input */ + if (TIM_ICInitStruct->TIM_ICSelection == TIM_ICSelection_DirectTI) + { + icoppositeselection = TIM_ICSelection_IndirectTI; + } + else + { + icoppositeselection = TIM_ICSelection_DirectTI; + } + if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) + { + /* TI1 Configuration */ + TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + /* TI2 Configuration */ + TI2_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else + { + /* TI2 Configuration */ + TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + /* TI1 Configuration */ + TI1_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } +} + +/** + * @brief Gets the TIMx Input Capture 1 value. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @retval Capture Compare 1 Register value. + */ +uint32_t TIM_GetCapture1(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + + /* Get the Capture 1 Register value */ + return TIMx->CCR1; +} + +/** + * @brief Gets the TIMx Input Capture 2 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @retval Capture Compare 2 Register value. + */ +uint32_t TIM_GetCapture2(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + + /* Get the Capture 2 Register value */ + return TIMx->CCR2; +} + +/** + * @brief Gets the TIMx Input Capture 3 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @retval Capture Compare 3 Register value. + */ +uint32_t TIM_GetCapture3(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + + /* Get the Capture 3 Register value */ + return TIMx->CCR3; +} + +/** + * @brief Gets the TIMx Input Capture 4 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @retval Capture Compare 4 Register value. + */ +uint32_t TIM_GetCapture4(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + + /* Get the Capture 4 Register value */ + return TIMx->CCR4; +} + +/** + * @brief Sets the TIMx Input Capture 1 prescaler. + * @param TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture1 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + + /* Reset the IC1PSC Bits */ + TIMx->CCMR1 &= (uint16_t)~TIM_CCMR1_IC1PSC; + + /* Set the IC1PSC value */ + TIMx->CCMR1 |= TIM_ICPSC; +} + +/** + * @brief Sets the TIMx Input Capture 2 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_ICPSC: specifies the Input Capture2 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + + /* Reset the IC2PSC Bits */ + TIMx->CCMR1 &= (uint16_t)~TIM_CCMR1_IC2PSC; + + /* Set the IC2PSC value */ + TIMx->CCMR1 |= (uint16_t)(TIM_ICPSC << 8); +} + +/** + * @brief Sets the TIMx Input Capture 3 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture3 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + + /* Reset the IC3PSC Bits */ + TIMx->CCMR2 &= (uint16_t)~TIM_CCMR2_IC3PSC; + + /* Set the IC3PSC value */ + TIMx->CCMR2 |= TIM_ICPSC; +} + +/** + * @brief Sets the TIMx Input Capture 4 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture4 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + + /* Reset the IC4PSC Bits */ + TIMx->CCMR2 &= (uint16_t)~TIM_CCMR2_IC4PSC; + + /* Set the IC4PSC value */ + TIMx->CCMR2 |= (uint16_t)(TIM_ICPSC << 8); +} +/** + * @} + */ + +/** @defgroup TIM_Group4 Advanced-control timers (TIM1 and TIM8) specific features + * @brief Advanced-control timers (TIM1 and TIM8) specific features + * +@verbatim + =============================================================================== + Advanced-control timers (TIM1 and TIM8) specific features + =============================================================================== + + =================================================================== + TIM Driver: how to use the Break feature + =================================================================== + After configuring the Timer channel(s) in the appropriate Output Compare mode: + + 1. Fill the TIM_BDTRInitStruct with the desired parameters for the Timer + Break Polarity, dead time, Lock level, the OSSI/OSSR State and the + AOE(automatic output enable). + + 2. Call TIM_BDTRConfig(TIMx, &TIM_BDTRInitStruct) to configure the Timer + + 3. Enable the Main Output using TIM_CtrlPWMOutputs(TIM1, ENABLE) + + 4. Once the break even occurs, the Timer's output signals are put in reset + state or in a known state (according to the configuration made in + TIM_BDTRConfig() function). + +@endverbatim + * @{ + */ + +/** + * @brief Configures the Break feature, dead time, Lock level, OSSI/OSSR State + * and the AOE(automatic output enable). + * @param TIMx: where x can be 1 or 8 to select the TIM + * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure that + * contains the BDTR Register configuration information for the TIM peripheral. + * @retval None + */ +void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OSSR_STATE(TIM_BDTRInitStruct->TIM_OSSRState)); + assert_param(IS_TIM_OSSI_STATE(TIM_BDTRInitStruct->TIM_OSSIState)); + assert_param(IS_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->TIM_LOCKLevel)); + assert_param(IS_TIM_BREAK_STATE(TIM_BDTRInitStruct->TIM_Break)); + assert_param(IS_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->TIM_BreakPolarity)); + assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->TIM_AutomaticOutput)); + + /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State, + the OSSI State, the dead time value and the Automatic Output Enable Bit */ + TIMx->BDTR = (uint32_t)TIM_BDTRInitStruct->TIM_OSSRState | TIM_BDTRInitStruct->TIM_OSSIState | + TIM_BDTRInitStruct->TIM_LOCKLevel | TIM_BDTRInitStruct->TIM_DeadTime | + TIM_BDTRInitStruct->TIM_Break | TIM_BDTRInitStruct->TIM_BreakPolarity | + TIM_BDTRInitStruct->TIM_AutomaticOutput; +} + +/** + * @brief Fills each TIM_BDTRInitStruct member with its default value. + * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure which + * will be initialized. + * @retval None + */ +void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct) +{ + /* Set the default configuration */ + TIM_BDTRInitStruct->TIM_OSSRState = TIM_OSSRState_Disable; + TIM_BDTRInitStruct->TIM_OSSIState = TIM_OSSIState_Disable; + TIM_BDTRInitStruct->TIM_LOCKLevel = TIM_LOCKLevel_OFF; + TIM_BDTRInitStruct->TIM_DeadTime = 0x00; + TIM_BDTRInitStruct->TIM_Break = TIM_Break_Disable; + TIM_BDTRInitStruct->TIM_BreakPolarity = TIM_BreakPolarity_Low; + TIM_BDTRInitStruct->TIM_AutomaticOutput = TIM_AutomaticOutput_Disable; +} + +/** + * @brief Enables or disables the TIM peripheral Main Outputs. + * @param TIMx: where x can be 1 or 8 to select the TIMx peripheral. + * @param NewState: new state of the TIM peripheral Main Outputs. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the TIM Main Output */ + TIMx->BDTR |= TIM_BDTR_MOE; + } + else + { + /* Disable the TIM Main Output */ + TIMx->BDTR &= (uint16_t)~TIM_BDTR_MOE; + } +} + +/** + * @brief Selects the TIM peripheral Commutation event. + * @param TIMx: where x can be 1 or 8 to select the TIMx peripheral + * @param NewState: new state of the Commutation event. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the COM Bit */ + TIMx->CR2 |= TIM_CR2_CCUS; + } + else + { + /* Reset the COM Bit */ + TIMx->CR2 &= (uint16_t)~TIM_CR2_CCUS; + } +} + +/** + * @brief Sets or Resets the TIM peripheral Capture Compare Preload Control bit. + * @param TIMx: where x can be 1 or 8 to select the TIMx peripheral + * @param NewState: new state of the Capture Compare Preload Control bit + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the CCPC Bit */ + TIMx->CR2 |= TIM_CR2_CCPC; + } + else + { + /* Reset the CCPC Bit */ + TIMx->CR2 &= (uint16_t)~TIM_CR2_CCPC; + } +} +/** + * @} + */ + +/** @defgroup TIM_Group5 Interrupts DMA and flags management functions + * @brief Interrupts, DMA and flags management functions + * +@verbatim + =============================================================================== + Interrupts, DMA and flags management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified TIM interrupts. + * @param TIMx: where x can be 1 to 14 to select the TIMx peripheral. + * @param TIM_IT: specifies the TIM interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg TIM_IT_Update: TIM update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * + * @note For TIM6 and TIM7 only the parameter TIM_IT_Update can be used + * @note For TIM9 and TIM12 only one of the following parameters can be used: TIM_IT_Update, + * TIM_IT_CC1, TIM_IT_CC2 or TIM_IT_Trigger. + * @note For TIM10, TIM11, TIM13 and TIM14 only one of the following parameters can + * be used: TIM_IT_Update or TIM_IT_CC1 + * @note TIM_IT_COM and TIM_IT_Break can be used only with TIM1 and TIM8 + * + * @param NewState: new state of the TIM interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_IT(TIM_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Interrupt sources */ + TIMx->DIER |= TIM_IT; + } + else + { + /* Disable the Interrupt sources */ + TIMx->DIER &= (uint16_t)~TIM_IT; + } +} + +/** + * @brief Configures the TIMx event to be generate by software. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param TIM_EventSource: specifies the event source. + * This parameter can be one or more of the following values: + * @arg TIM_EventSource_Update: Timer update Event source + * @arg TIM_EventSource_CC1: Timer Capture Compare 1 Event source + * @arg TIM_EventSource_CC2: Timer Capture Compare 2 Event source + * @arg TIM_EventSource_CC3: Timer Capture Compare 3 Event source + * @arg TIM_EventSource_CC4: Timer Capture Compare 4 Event source + * @arg TIM_EventSource_COM: Timer COM event source + * @arg TIM_EventSource_Trigger: Timer Trigger Event source + * @arg TIM_EventSource_Break: Timer Break event source + * + * @note TIM6 and TIM7 can only generate an update event. + * @note TIM_EventSource_COM and TIM_EventSource_Break are used only with TIM1 and TIM8. + * + * @retval None + */ +void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_EVENT_SOURCE(TIM_EventSource)); + + /* Set the event sources */ + TIMx->EGR = TIM_EventSource; +} + +/** + * @brief Checks whether the specified TIM flag is set or not. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param TIM_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg TIM_FLAG_Update: TIM update Flag + * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag + * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag + * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag + * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag + * @arg TIM_FLAG_COM: TIM Commutation Flag + * @arg TIM_FLAG_Trigger: TIM Trigger Flag + * @arg TIM_FLAG_Break: TIM Break Flag + * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 over capture Flag + * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 over capture Flag + * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 over capture Flag + * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 over capture Flag + * + * @note TIM6 and TIM7 can have only one update flag. + * @note TIM_FLAG_COM and TIM_FLAG_Break are used only with TIM1 and TIM8. + * + * @retval The new state of TIM_FLAG (SET or RESET). + */ +FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_GET_FLAG(TIM_FLAG)); + + + if ((TIMx->SR & TIM_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the TIMx's pending flags. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param TIM_FLAG: specifies the flag bit to clear. + * This parameter can be any combination of the following values: + * @arg TIM_FLAG_Update: TIM update Flag + * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag + * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag + * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag + * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag + * @arg TIM_FLAG_COM: TIM Commutation Flag + * @arg TIM_FLAG_Trigger: TIM Trigger Flag + * @arg TIM_FLAG_Break: TIM Break Flag + * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 over capture Flag + * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 over capture Flag + * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 over capture Flag + * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 over capture Flag + * + * @note TIM6 and TIM7 can have only one update flag. + * @note TIM_FLAG_COM and TIM_FLAG_Break are used only with TIM1 and TIM8. + * + * @retval None + */ +void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Clear the flags */ + TIMx->SR = (uint16_t)~TIM_FLAG; +} + +/** + * @brief Checks whether the TIM interrupt has occurred or not. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param TIM_IT: specifies the TIM interrupt source to check. + * This parameter can be one of the following values: + * @arg TIM_IT_Update: TIM update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * + * @note TIM6 and TIM7 can generate only an update interrupt. + * @note TIM_IT_COM and TIM_IT_Break are used only with TIM1 and TIM8. + * + * @retval The new state of the TIM_IT(SET or RESET). + */ +ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itstatus = 0x0, itenable = 0x0; + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_GET_IT(TIM_IT)); + + itstatus = TIMx->SR & TIM_IT; + + itenable = TIMx->DIER & TIM_IT; + if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the TIMx's interrupt pending bits. + * @param TIMx: where x can be 1 to 14 to select the TIM peripheral. + * @param TIM_IT: specifies the pending bit to clear. + * This parameter can be any combination of the following values: + * @arg TIM_IT_Update: TIM1 update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * + * @note TIM6 and TIM7 can generate only an update interrupt. + * @note TIM_IT_COM and TIM_IT_Break are used only with TIM1 and TIM8. + * + * @retval None + */ +void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Clear the IT pending Bit */ + TIMx->SR = (uint16_t)~TIM_IT; +} + +/** + * @brief Configures the TIMx's DMA interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_DMABase: DMA Base address. + * This parameter can be one of the following values: + * @arg TIM_DMABase_CR1 + * @arg TIM_DMABase_CR2 + * @arg TIM_DMABase_SMCR + * @arg TIM_DMABase_DIER + * @arg TIM1_DMABase_SR + * @arg TIM_DMABase_EGR + * @arg TIM_DMABase_CCMR1 + * @arg TIM_DMABase_CCMR2 + * @arg TIM_DMABase_CCER + * @arg TIM_DMABase_CNT + * @arg TIM_DMABase_PSC + * @arg TIM_DMABase_ARR + * @arg TIM_DMABase_RCR + * @arg TIM_DMABase_CCR1 + * @arg TIM_DMABase_CCR2 + * @arg TIM_DMABase_CCR3 + * @arg TIM_DMABase_CCR4 + * @arg TIM_DMABase_BDTR + * @arg TIM_DMABase_DCR + * @param TIM_DMABurstLength: DMA Burst length. This parameter can be one value + * between: TIM_DMABurstLength_1Transfer and TIM_DMABurstLength_18Transfers. + * @retval None + */ +void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_DMA_BASE(TIM_DMABase)); + assert_param(IS_TIM_DMA_LENGTH(TIM_DMABurstLength)); + + /* Set the DMA Base and the DMA Burst Length */ + TIMx->DCR = TIM_DMABase | TIM_DMABurstLength; +} + +/** + * @brief Enables or disables the TIMx's DMA Requests. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the TIM peripheral. + * @param TIM_DMASource: specifies the DMA Request sources. + * This parameter can be any combination of the following values: + * @arg TIM_DMA_Update: TIM update Interrupt source + * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source + * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source + * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source + * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source + * @arg TIM_DMA_COM: TIM Commutation DMA source + * @arg TIM_DMA_Trigger: TIM Trigger DMA source + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST5_PERIPH(TIMx)); + assert_param(IS_TIM_DMA_SOURCE(TIM_DMASource)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DMA sources */ + TIMx->DIER |= TIM_DMASource; + } + else + { + /* Disable the DMA sources */ + TIMx->DIER &= (uint16_t)~TIM_DMASource; + } +} + +/** + * @brief Selects the TIMx peripheral Capture Compare DMA source. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param NewState: new state of the Capture Compare DMA source + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the CCDS Bit */ + TIMx->CR2 |= TIM_CR2_CCDS; + } + else + { + /* Reset the CCDS Bit */ + TIMx->CR2 &= (uint16_t)~TIM_CR2_CCDS; + } +} +/** + * @} + */ + +/** @defgroup TIM_Group6 Clocks management functions + * @brief Clocks management functions + * +@verbatim + =============================================================================== + Clocks management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the TIMx internal Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @retval None + */ +void TIM_InternalClockConfig(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + + /* Disable slave mode to clock the prescaler directly with the internal clock */ + TIMx->SMCR &= (uint16_t)~TIM_SMCR_SMS; +} + +/** + * @brief Configures the TIMx Internal Trigger as External Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_InputTriggerSource: Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal Trigger 0 + * @arg TIM_TS_ITR1: Internal Trigger 1 + * @arg TIM_TS_ITR2: Internal Trigger 2 + * @arg TIM_TS_ITR3: Internal Trigger 3 + * @retval None + */ +void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_INTERNAL_TRIGGER_SELECTION(TIM_InputTriggerSource)); + + /* Select the Internal Trigger */ + TIM_SelectInputTrigger(TIMx, TIM_InputTriggerSource); + + /* Select the External clock mode1 */ + TIMx->SMCR |= TIM_SlaveMode_External1; +} + +/** + * @brief Configures the TIMx Trigger as External Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13 or 14 + * to select the TIM peripheral. + * @param TIM_TIxExternalCLKSource: Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TIxExternalCLK1Source_TI1ED: TI1 Edge Detector + * @arg TIM_TIxExternalCLK1Source_TI1: Filtered Timer Input 1 + * @arg TIM_TIxExternalCLK1Source_TI2: Filtered Timer Input 2 + * @param TIM_ICPolarity: specifies the TIx Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param ICFilter: specifies the filter value. + * This parameter must be a value between 0x0 and 0xF. + * @retval None + */ +void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, + uint16_t TIM_ICPolarity, uint16_t ICFilter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_IC_POLARITY(TIM_ICPolarity)); + assert_param(IS_TIM_IC_FILTER(ICFilter)); + + /* Configure the Timer Input Clock Source */ + if (TIM_TIxExternalCLKSource == TIM_TIxExternalCLK1Source_TI2) + { + TI2_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); + } + else + { + TI1_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); + } + /* Select the Trigger source */ + TIM_SelectInputTrigger(TIMx, TIM_TIxExternalCLKSource); + /* Select the External clock mode1 */ + TIMx->SMCR |= TIM_SlaveMode_External1; +} + +/** + * @brief Configures the External clock Mode1 + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter) +{ + uint16_t tmpsmcr = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + /* Configure the ETR Clock source */ + TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + + /* Reset the SMS Bits */ + tmpsmcr &= (uint16_t)~TIM_SMCR_SMS; + + /* Select the External clock mode1 */ + tmpsmcr |= TIM_SlaveMode_External1; + + /* Select the Trigger selection : ETRF */ + tmpsmcr &= (uint16_t)~TIM_SMCR_TS; + tmpsmcr |= TIM_TS_ETRF; + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the External clock Mode2 + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + + /* Configure the ETR Clock source */ + TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); + + /* Enable the External clock mode2 */ + TIMx->SMCR |= TIM_SMCR_ECE; +} +/** + * @} + */ + +/** @defgroup TIM_Group7 Synchronization management functions + * @brief Synchronization management functions + * +@verbatim + =============================================================================== + Synchronization management functions + =============================================================================== + + =================================================================== + TIM Driver: how to use it in synchronization Mode + =================================================================== + Case of two/several Timers + ************************** + 1. Configure the Master Timers using the following functions: + - void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource); + - void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode); + 2. Configure the Slave Timers using the following functions: + - void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); + - void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); + + Case of Timers and external trigger(ETR pin) + ******************************************** + 1. Configure the External trigger using this function: + - void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); + 2. Configure the Slave Timers using the following functions: + - void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); + - void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); + +@endverbatim + * @{ + */ + +/** + * @brief Selects the Input Trigger source + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13 or 14 + * to select the TIM peripheral. + * @param TIM_InputTriggerSource: The Input Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal Trigger 0 + * @arg TIM_TS_ITR1: Internal Trigger 1 + * @arg TIM_TS_ITR2: Internal Trigger 2 + * @arg TIM_TS_ITR3: Internal Trigger 3 + * @arg TIM_TS_TI1F_ED: TI1 Edge Detector + * @arg TIM_TS_TI1FP1: Filtered Timer Input 1 + * @arg TIM_TS_TI2FP2: Filtered Timer Input 2 + * @arg TIM_TS_ETRF: External Trigger input + * @retval None + */ +void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) +{ + uint16_t tmpsmcr = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_TRIGGER_SELECTION(TIM_InputTriggerSource)); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + + /* Reset the TS Bits */ + tmpsmcr &= (uint16_t)~TIM_SMCR_TS; + + /* Set the Input Trigger source */ + tmpsmcr |= TIM_InputTriggerSource; + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Selects the TIMx Trigger Output Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the TIM peripheral. + * + * @param TIM_TRGOSource: specifies the Trigger Output source. + * This parameter can be one of the following values: + * + * - For all TIMx + * @arg TIM_TRGOSource_Reset: The UG bit in the TIM_EGR register is used as the trigger output(TRGO) + * @arg TIM_TRGOSource_Enable: The Counter Enable CEN is used as the trigger output(TRGO) + * @arg TIM_TRGOSource_Update: The update event is selected as the trigger output(TRGO) + * + * - For all TIMx except TIM6 and TIM7 + * @arg TIM_TRGOSource_OC1: The trigger output sends a positive pulse when the CC1IF flag + * is to be set, as soon as a capture or compare match occurs(TRGO) + * @arg TIM_TRGOSource_OC1Ref: OC1REF signal is used as the trigger output(TRGO) + * @arg TIM_TRGOSource_OC2Ref: OC2REF signal is used as the trigger output(TRGO) + * @arg TIM_TRGOSource_OC3Ref: OC3REF signal is used as the trigger output(TRGO) + * @arg TIM_TRGOSource_OC4Ref: OC4REF signal is used as the trigger output(TRGO) + * + * @retval None + */ +void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST5_PERIPH(TIMx)); + assert_param(IS_TIM_TRGO_SOURCE(TIM_TRGOSource)); + + /* Reset the MMS Bits */ + TIMx->CR2 &= (uint16_t)~TIM_CR2_MMS; + /* Select the TRGO source */ + TIMx->CR2 |= TIM_TRGOSource; +} + +/** + * @brief Selects the TIMx Slave Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM peripheral. + * @param TIM_SlaveMode: specifies the Timer Slave Mode. + * This parameter can be one of the following values: + * @arg TIM_SlaveMode_Reset: Rising edge of the selected trigger signal(TRGI) reinitialize + * the counter and triggers an update of the registers + * @arg TIM_SlaveMode_Gated: The counter clock is enabled when the trigger signal (TRGI) is high + * @arg TIM_SlaveMode_Trigger: The counter starts at a rising edge of the trigger TRGI + * @arg TIM_SlaveMode_External1: Rising edges of the selected trigger (TRGI) clock the counter + * @retval None + */ +void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_SLAVE_MODE(TIM_SlaveMode)); + + /* Reset the SMS Bits */ + TIMx->SMCR &= (uint16_t)~TIM_SMCR_SMS; + + /* Select the Slave Mode */ + TIMx->SMCR |= TIM_SlaveMode; +} + +/** + * @brief Sets or Resets the TIMx Master/Slave Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM peripheral. + * @param TIM_MasterSlaveMode: specifies the Timer Master Slave Mode. + * This parameter can be one of the following values: + * @arg TIM_MasterSlaveMode_Enable: synchronization between the current timer + * and its slaves (through TRGO) + * @arg TIM_MasterSlaveMode_Disable: No action + * @retval None + */ +void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_MSM_STATE(TIM_MasterSlaveMode)); + + /* Reset the MSM Bit */ + TIMx->SMCR &= (uint16_t)~TIM_SMCR_MSM; + + /* Set or Reset the MSM Bit */ + TIMx->SMCR |= TIM_MasterSlaveMode; +} + +/** + * @brief Configures the TIMx External Trigger (ETR). + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter) +{ + uint16_t tmpsmcr = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + + tmpsmcr = TIMx->SMCR; + + /* Reset the ETR Bits */ + tmpsmcr &= SMCR_ETR_MASK; + + /* Set the Prescaler, the Filter value and the Polarity */ + tmpsmcr |= (uint16_t)(TIM_ExtTRGPrescaler | (uint16_t)(TIM_ExtTRGPolarity | (uint16_t)(ExtTRGFilter << (uint16_t)8))); + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} +/** + * @} + */ + +/** @defgroup TIM_Group8 Specific interface management functions + * @brief Specific interface management functions + * +@verbatim + =============================================================================== + Specific interface management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the TIMx Encoder Interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_EncoderMode: specifies the TIMx Encoder Mode. + * This parameter can be one of the following values: + * @arg TIM_EncoderMode_TI1: Counter counts on TI1FP1 edge depending on TI2FP2 level. + * @arg TIM_EncoderMode_TI2: Counter counts on TI2FP2 edge depending on TI1FP1 level. + * @arg TIM_EncoderMode_TI12: Counter counts on both TI1FP1 and TI2FP2 edges depending + * on the level of the other input. + * @param TIM_IC1Polarity: specifies the IC1 Polarity + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Falling: IC Falling edge. + * @arg TIM_ICPolarity_Rising: IC Rising edge. + * @param TIM_IC2Polarity: specifies the IC2 Polarity + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Falling: IC Falling edge. + * @arg TIM_ICPolarity_Rising: IC Rising edge. + * @retval None + */ +void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, + uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity) +{ + uint16_t tmpsmcr = 0; + uint16_t tmpccmr1 = 0; + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_ENCODER_MODE(TIM_EncoderMode)); + assert_param(IS_TIM_IC_POLARITY(TIM_IC1Polarity)); + assert_param(IS_TIM_IC_POLARITY(TIM_IC2Polarity)); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + + /* Set the encoder Mode */ + tmpsmcr &= (uint16_t)~TIM_SMCR_SMS; + tmpsmcr |= TIM_EncoderMode; + + /* Select the Capture Compare 1 and the Capture Compare 2 as input */ + tmpccmr1 &= ((uint16_t)~TIM_CCMR1_CC1S) & ((uint16_t)~TIM_CCMR1_CC2S); + tmpccmr1 |= TIM_CCMR1_CC1S_0 | TIM_CCMR1_CC2S_0; + + /* Set the TI1 and the TI2 Polarities */ + tmpccer &= ((uint16_t)~TIM_CCER_CC1P) & ((uint16_t)~TIM_CCER_CC2P); + tmpccer |= (uint16_t)(TIM_IC1Polarity | (uint16_t)(TIM_IC2Polarity << (uint16_t)4)); + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Enables or disables the TIMx's Hall sensor interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param NewState: new state of the TIMx Hall sensor interface. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the TI1S Bit */ + TIMx->CR2 |= TIM_CR2_TI1S; + } + else + { + /* Reset the TI1S Bit */ + TIMx->CR2 &= (uint16_t)~TIM_CR2_TI1S; + } +} +/** + * @} + */ + +/** @defgroup TIM_Group9 Specific remapping management function + * @brief Specific remapping management function + * +@verbatim + =============================================================================== + Specific remapping management function + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the TIM2, TIM5 and TIM11 Remapping input capabilities. + * @param TIMx: where x can be 2, 5 or 11 to select the TIM peripheral. + * @param TIM_Remap: specifies the TIM input remapping source. + * This parameter can be one of the following values: + * @arg TIM2_TIM8_TRGO: TIM2 ITR1 input is connected to TIM8 Trigger output(default) + * @arg TIM2_ETH_PTP: TIM2 ITR1 input is connected to ETH PTP trogger output. + * @arg TIM2_USBFS_SOF: TIM2 ITR1 input is connected to USB FS SOF. + * @arg TIM2_USBHS_SOF: TIM2 ITR1 input is connected to USB HS SOF. + * @arg TIM5_GPIO: TIM5 CH4 input is connected to dedicated Timer pin(default) + * @arg TIM5_LSI: TIM5 CH4 input is connected to LSI clock. + * @arg TIM5_LSE: TIM5 CH4 input is connected to LSE clock. + * @arg TIM5_RTC: TIM5 CH4 input is connected to RTC Output event. + * @arg TIM11_GPIO: TIM11 CH4 input is connected to dedicated Timer pin(default) + * @arg TIM11_HSE: TIM11 CH4 input is connected to HSE_RTC clock + * (HSE divided by a programmable prescaler) + * @retval None + */ +void TIM_RemapConfig(TIM_TypeDef* TIMx, uint16_t TIM_Remap) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_REMAP(TIM_Remap)); + + /* Set the Timer remapping configuration */ + TIMx->OR = TIM_Remap; +} +/** + * @} + */ + +/** + * @brief Configure the TI1 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13 or 14 + * to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @arg TIM_ICPolarity_BothEdge + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 1 is selected to be connected to IC1. + * @arg TIM_ICSelection_IndirectTI: TIM Input 1 is selected to be connected to IC2. + * @arg TIM_ICSelection_TRC: TIM Input 1 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr1 = 0, tmpccer = 0; + + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC1E; + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + + /* Select the Input and set the filter */ + tmpccmr1 &= ((uint16_t)~TIM_CCMR1_CC1S) & ((uint16_t)~TIM_CCMR1_IC1F); + tmpccmr1 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); + + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= (uint16_t)~(TIM_CCER_CC1P | TIM_CCER_CC1NP); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC1E); + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI2 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @arg TIM_ICPolarity_BothEdge + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 2 is selected to be connected to IC2. + * @arg TIM_ICSelection_IndirectTI: TIM Input 2 is selected to be connected to IC1. + * @arg TIM_ICSelection_TRC: TIM Input 2 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr1 = 0, tmpccer = 0, tmp = 0; + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC2E; + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 4); + + /* Select the Input and set the filter */ + tmpccmr1 &= ((uint16_t)~TIM_CCMR1_CC2S) & ((uint16_t)~TIM_CCMR1_IC2F); + tmpccmr1 |= (uint16_t)(TIM_ICFilter << 12); + tmpccmr1 |= (uint16_t)(TIM_ICSelection << 8); + + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= (uint16_t)~(TIM_CCER_CC2P | TIM_CCER_CC2NP); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC2E); + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1 ; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI3 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @arg TIM_ICPolarity_BothEdge + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 3 is selected to be connected to IC3. + * @arg TIM_ICSelection_IndirectTI: TIM Input 3 is selected to be connected to IC4. + * @arg TIM_ICSelection_TRC: TIM Input 3 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; + + /* Disable the Channel 3: Reset the CC3E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC3E; + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 8); + + /* Select the Input and set the filter */ + tmpccmr2 &= ((uint16_t)~TIM_CCMR1_CC1S) & ((uint16_t)~TIM_CCMR2_IC3F); + tmpccmr2 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); + + /* Select the Polarity and set the CC3E Bit */ + tmpccer &= (uint16_t)~(TIM_CCER_CC3P | TIM_CCER_CC3NP); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC3E); + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI4 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @arg TIM_ICPolarity_BothEdge + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 4 is selected to be connected to IC4. + * @arg TIM_ICSelection_IndirectTI: TIM Input 4 is selected to be connected to IC3. + * @arg TIM_ICSelection_TRC: TIM Input 4 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC4E; + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 12); + + /* Select the Input and set the filter */ + tmpccmr2 &= ((uint16_t)~TIM_CCMR1_CC2S) & ((uint16_t)~TIM_CCMR1_IC2F); + tmpccmr2 |= (uint16_t)(TIM_ICSelection << 8); + tmpccmr2 |= (uint16_t)(TIM_ICFilter << 12); + + /* Select the Polarity and set the CC4E Bit */ + tmpccer &= (uint16_t)~(TIM_CCER_CC4P | TIM_CCER_CC4NP); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC4E); + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer ; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c new file mode 100644 index 000000000..1bb99ad22 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c @@ -0,0 +1,1463 @@ +/** + ****************************************************************************** + * @file stm32f4xx_usart.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Universal synchronous asynchronous receiver + * transmitter (USART): + * - Initialization and Configuration + * - Data transfers + * - Multi-Processor Communication + * - LIN mode + * - Half-duplex mode + * - Smartcard mode + * - IrDA mode + * - DMA transfers management + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * How to use this driver + * =================================================================== + * 1. Enable peripheral clock using the follwoing functions + * RCC_APB2PeriphClockCmd(RCC_APB2Periph_USARTx, ENABLE) for USART1 and USART6 + * RCC_APB1PeriphClockCmd(RCC_APB1Periph_USARTx, ENABLE) for USART2, USART3, UART4 or UART5. + * + * 2. According to the USART mode, enable the GPIO clocks using + * RCC_AHB1PeriphClockCmd() function. (The I/O can be TX, RX, CTS, + * or/and SCLK). + * + * 3. Peripheral's alternate function: + * - Connect the pin to the desired peripherals' Alternate + * Function (AF) using GPIO_PinAFConfig() function + * - Configure the desired pin in alternate function by: + * GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF + * - Select the type, pull-up/pull-down and output speed via + * GPIO_PuPd, GPIO_OType and GPIO_Speed members + * - Call GPIO_Init() function + * + * 4. Program the Baud Rate, Word Length , Stop Bit, Parity, Hardware + * flow control and Mode(Receiver/Transmitter) using the USART_Init() + * function. + * + * 5. For synchronous mode, enable the clock and program the polarity, + * phase and last bit using the USART_ClockInit() function. + * + * 5. Enable the NVIC and the corresponding interrupt using the function + * USART_ITConfig() if you need to use interrupt mode. + * + * 6. When using the DMA mode + * - Configure the DMA using DMA_Init() function + * - Active the needed channel Request using USART_DMACmd() function + * + * 7. Enable the USART using the USART_Cmd() function. + * + * 8. Enable the DMA using the DMA_Cmd() function, when using DMA mode. + * + * Refer to Multi-Processor, LIN, half-duplex, Smartcard, IrDA sub-sections + * for more details + * + * In order to reach higher communication baudrates, it is possible to + * enable the oversampling by 8 mode using the function USART_OverSampling8Cmd(). + * This function should be called after enabling the USART clock (RCC_APBxPeriphClockCmd()) + * and before calling the function USART_Init(). + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_usart.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup USART + * @brief USART driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/*!< USART CR1 register clear Mask ((~(uint16_t)0xE9F3)) */ +#define CR1_CLEAR_MASK ((uint16_t)(USART_CR1_M | USART_CR1_PCE | \ + USART_CR1_PS | USART_CR1_TE | \ + USART_CR1_RE)) + +/*!< USART CR2 register clock bits clear Mask ((~(uint16_t)0xF0FF)) */ +#define CR2_CLOCK_CLEAR_MASK ((uint16_t)(USART_CR2_CLKEN | USART_CR2_CPOL | \ + USART_CR2_CPHA | USART_CR2_LBCL)) + +/*!< USART CR3 register clear Mask ((~(uint16_t)0xFCFF)) */ +#define CR3_CLEAR_MASK ((uint16_t)(USART_CR3_RTSE | USART_CR3_CTSE)) + +/*!< USART Interrupts mask */ +#define IT_MASK ((uint16_t)0x001F) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup USART_Private_Functions + * @{ + */ + +/** @defgroup USART_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + Initialization and Configuration functions + =============================================================================== + + This subsection provides a set of functions allowing to initialize the USART + in asynchronous and in synchronous modes. + - For the asynchronous mode only these parameters can be configured: + - Baud Rate + - Word Length + - Stop Bit + - Parity: If the parity is enabled, then the MSB bit of the data written + in the data register is transmitted but is changed by the parity bit. + Depending on the frame length defined by the M bit (8-bits or 9-bits), + the possible USART frame formats are as listed in the following table: + +-------------------------------------------------------------+ + | M bit | PCE bit | USART frame | + |---------------------|---------------------------------------| + | 0 | 0 | | SB | 8 bit data | STB | | + |---------|-----------|---------------------------------------| + | 0 | 1 | | SB | 7 bit data | PB | STB | | + |---------|-----------|---------------------------------------| + | 1 | 0 | | SB | 9 bit data | STB | | + |---------|-----------|---------------------------------------| + | 1 | 1 | | SB | 8 bit data | PB | STB | | + +-------------------------------------------------------------+ + - Hardware flow control + - Receiver/transmitter modes + + The USART_Init() function follows the USART asynchronous configuration procedure + (details for the procedure are available in reference manual (RM0090)). + + - For the synchronous mode in addition to the asynchronous mode parameters these + parameters should be also configured: + - USART Clock Enabled + - USART polarity + - USART phase + - USART LastBit + + These parameters can be configured using the USART_ClockInit() function. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the USARTx peripheral registers to their default reset values. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @retval None + */ +void USART_DeInit(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + if (USARTx == USART1) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE); + } + else if (USARTx == USART2) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE); + } + else if (USARTx == USART3) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE); + } + else if (USARTx == UART4) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE); + } + else if (USARTx == UART5) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE); + } + else + { + if (USARTx == USART6) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART6, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART6, DISABLE); + } + } +} + +/** + * @brief Initializes the USARTx peripheral according to the specified + * parameters in the USART_InitStruct . + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_InitStruct: pointer to a USART_InitTypeDef structure that contains + * the configuration information for the specified USART peripheral. + * @retval None + */ +void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct) +{ + uint32_t tmpreg = 0x00, apbclock = 0x00; + uint32_t integerdivider = 0x00; + uint32_t fractionaldivider = 0x00; + RCC_ClocksTypeDef RCC_ClocksStatus; + + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate)); + assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength)); + assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits)); + assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity)); + assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode)); + assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl)); + + /* The hardware flow control is available only for USART1, USART2, USART3 and USART6 */ + if (USART_InitStruct->USART_HardwareFlowControl != USART_HardwareFlowControl_None) + { + assert_param(IS_USART_1236_PERIPH(USARTx)); + } + +/*---------------------------- USART CR2 Configuration -----------------------*/ + tmpreg = USARTx->CR2; + + /* Clear STOP[13:12] bits */ + tmpreg &= (uint32_t)~((uint32_t)USART_CR2_STOP); + + /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit : + Set STOP[13:12] bits according to USART_StopBits value */ + tmpreg |= (uint32_t)USART_InitStruct->USART_StopBits; + + /* Write to USART CR2 */ + USARTx->CR2 = (uint16_t)tmpreg; + +/*---------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = USARTx->CR1; + + /* Clear M, PCE, PS, TE and RE bits */ + tmpreg &= (uint32_t)~((uint32_t)CR1_CLEAR_MASK); + + /* Configure the USART Word Length, Parity and mode: + Set the M bits according to USART_WordLength value + Set PCE and PS bits according to USART_Parity value + Set TE and RE bits according to USART_Mode value */ + tmpreg |= (uint32_t)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity | + USART_InitStruct->USART_Mode; + + /* Write to USART CR1 */ + USARTx->CR1 = (uint16_t)tmpreg; + +/*---------------------------- USART CR3 Configuration -----------------------*/ + tmpreg = USARTx->CR3; + + /* Clear CTSE and RTSE bits */ + tmpreg &= (uint32_t)~((uint32_t)CR3_CLEAR_MASK); + + /* Configure the USART HFC : + Set CTSE and RTSE bits according to USART_HardwareFlowControl value */ + tmpreg |= USART_InitStruct->USART_HardwareFlowControl; + + /* Write to USART CR3 */ + USARTx->CR3 = (uint16_t)tmpreg; + +/*---------------------------- USART BRR Configuration -----------------------*/ + /* Configure the USART Baud Rate */ + RCC_GetClocksFreq(&RCC_ClocksStatus); + + if ((USARTx == USART1) || (USARTx == USART6)) + { + apbclock = RCC_ClocksStatus.PCLK2_Frequency; + } + else + { + apbclock = RCC_ClocksStatus.PCLK1_Frequency; + } + + /* Determine the integer part */ + if ((USARTx->CR1 & USART_CR1_OVER8) != 0) + { + /* Integer part computing in case Oversampling mode is 8 Samples */ + integerdivider = ((25 * apbclock) / (2 * (USART_InitStruct->USART_BaudRate))); + } + else /* if ((USARTx->CR1 & USART_CR1_OVER8) == 0) */ + { + /* Integer part computing in case Oversampling mode is 16 Samples */ + integerdivider = ((25 * apbclock) / (4 * (USART_InitStruct->USART_BaudRate))); + } + tmpreg = (integerdivider / 100) << 4; + + /* Determine the fractional part */ + fractionaldivider = integerdivider - (100 * (tmpreg >> 4)); + + /* Implement the fractional part in the register */ + if ((USARTx->CR1 & USART_CR1_OVER8) != 0) + { + tmpreg |= ((((fractionaldivider * 8) + 50) / 100)) & ((uint8_t)0x07); + } + else /* if ((USARTx->CR1 & USART_CR1_OVER8) == 0) */ + { + tmpreg |= ((((fractionaldivider * 16) + 50) / 100)) & ((uint8_t)0x0F); + } + + /* Write to USART BRR register */ + USARTx->BRR = (uint16_t)tmpreg; +} + +/** + * @brief Fills each USART_InitStruct member with its default value. + * @param USART_InitStruct: pointer to a USART_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void USART_StructInit(USART_InitTypeDef* USART_InitStruct) +{ + /* USART_InitStruct members default value */ + USART_InitStruct->USART_BaudRate = 9600; + USART_InitStruct->USART_WordLength = USART_WordLength_8b; + USART_InitStruct->USART_StopBits = USART_StopBits_1; + USART_InitStruct->USART_Parity = USART_Parity_No ; + USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None; +} + +/** + * @brief Initializes the USARTx peripheral Clock according to the + * specified parameters in the USART_ClockInitStruct . + * @param USARTx: where x can be 1, 2, 3 or 6 to select the USART peripheral. + * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef structure that + * contains the configuration information for the specified USART peripheral. + * @note The Smart Card and Synchronous modes are not available for UART4 and UART5. + * @retval None + */ +void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct) +{ + uint32_t tmpreg = 0x00; + /* Check the parameters */ + assert_param(IS_USART_1236_PERIPH(USARTx)); + assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock)); + assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL)); + assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA)); + assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit)); + +/*---------------------------- USART CR2 Configuration -----------------------*/ + tmpreg = USARTx->CR2; + /* Clear CLKEN, CPOL, CPHA and LBCL bits */ + tmpreg &= (uint32_t)~((uint32_t)CR2_CLOCK_CLEAR_MASK); + /* Configure the USART Clock, CPOL, CPHA and LastBit ------------*/ + /* Set CLKEN bit according to USART_Clock value */ + /* Set CPOL bit according to USART_CPOL value */ + /* Set CPHA bit according to USART_CPHA value */ + /* Set LBCL bit according to USART_LastBit value */ + tmpreg |= (uint32_t)USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL | + USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit; + /* Write to USART CR2 */ + USARTx->CR2 = (uint16_t)tmpreg; +} + +/** + * @brief Fills each USART_ClockInitStruct member with its default value. + * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef structure + * which will be initialized. + * @retval None + */ +void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct) +{ + /* USART_ClockInitStruct members default value */ + USART_ClockInitStruct->USART_Clock = USART_Clock_Disable; + USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low; + USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge; + USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable; +} + +/** + * @brief Enables or disables the specified USART peripheral. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param NewState: new state of the USARTx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected USART by setting the UE bit in the CR1 register */ + USARTx->CR1 |= USART_CR1_UE; + } + else + { + /* Disable the selected USART by clearing the UE bit in the CR1 register */ + USARTx->CR1 &= (uint16_t)~((uint16_t)USART_CR1_UE); + } +} + +/** + * @brief Sets the system clock prescaler. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_Prescaler: specifies the prescaler clock. + * @note The function is used for IrDA mode with UART4 and UART5. + * @retval None + */ +void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Clear the USART prescaler */ + USARTx->GTPR &= USART_GTPR_GT; + /* Set the USART prescaler */ + USARTx->GTPR |= USART_Prescaler; +} + +/** + * @brief Enables or disables the USART's 8x oversampling mode. + * @note This function has to be called before calling USART_Init() function + * in order to have correct baudrate Divider value. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param NewState: new state of the USART 8x oversampling mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the 8x Oversampling mode by setting the OVER8 bit in the CR1 register */ + USARTx->CR1 |= USART_CR1_OVER8; + } + else + { + /* Disable the 8x Oversampling mode by clearing the OVER8 bit in the CR1 register */ + USARTx->CR1 &= (uint16_t)~((uint16_t)USART_CR1_OVER8); + } +} + +/** + * @brief Enables or disables the USART's one bit sampling method. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param NewState: new state of the USART one bit sampling method. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the one bit method by setting the ONEBITE bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_ONEBIT; + } + else + { + /* Disable the one bit method by clearing the ONEBITE bit in the CR3 register */ + USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT); + } +} + +/** + * @} + */ + +/** @defgroup USART_Group2 Data transfers functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + Data transfers functions + =============================================================================== + + This subsection provides a set of functions allowing to manage the USART data + transfers. + + During an USART reception, data shifts in least significant bit first through + the RX pin. In this mode, the USART_DR register consists of a buffer (RDR) + between the internal bus and the received shift register. + + When a transmission is taking place, a write instruction to the USART_DR register + stores the data in the TDR register and which is copied in the shift register + at the end of the current transmission. + + The read access of the USART_DR register can be done using the USART_ReceiveData() + function and returns the RDR buffered value. Whereas a write access to the USART_DR + can be done using USART_SendData() function and stores the written data into + TDR buffer. + +@endverbatim + * @{ + */ + +/** + * @brief Transmits single data through the USARTx peripheral. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param Data: the data to transmit. + * @retval None + */ +void USART_SendData(USART_TypeDef* USARTx, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DATA(Data)); + + /* Transmit Data */ + USARTx->DR = (Data & (uint16_t)0x01FF); +} + +/** + * @brief Returns the most recent received data by the USARTx peripheral. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @retval The received data. + */ +uint16_t USART_ReceiveData(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Receive Data */ + return (uint16_t)(USARTx->DR & (uint16_t)0x01FF); +} + +/** + * @} + */ + +/** @defgroup USART_Group3 MultiProcessor Communication functions + * @brief Multi-Processor Communication functions + * +@verbatim + =============================================================================== + Multi-Processor Communication functions + =============================================================================== + + This subsection provides a set of functions allowing to manage the USART + multiprocessor communication. + + For instance one of the USARTs can be the master, its TX output is connected to + the RX input of the other USART. The others are slaves, their respective TX outputs + are logically ANDed together and connected to the RX input of the master. + + USART multiprocessor communication is possible through the following procedure: + 1. Program the Baud rate, Word length = 9 bits, Stop bits, Parity, Mode transmitter + or Mode receiver and hardware flow control values using the USART_Init() + function. + 2. Configures the USART address using the USART_SetAddress() function. + 3. Configures the wake up method (USART_WakeUp_IdleLine or USART_WakeUp_AddressMark) + using USART_WakeUpConfig() function only for the slaves. + 4. Enable the USART using the USART_Cmd() function. + 5. Enter the USART slaves in mute mode using USART_ReceiverWakeUpCmd() function. + + The USART Slave exit from mute mode when receive the wake up condition. + +@endverbatim + * @{ + */ + +/** + * @brief Sets the address of the USART node. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_Address: Indicates the address of the USART node. + * @retval None + */ +void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_ADDRESS(USART_Address)); + + /* Clear the USART address */ + USARTx->CR2 &= (uint16_t)~((uint16_t)USART_CR2_ADD); + /* Set the USART address node */ + USARTx->CR2 |= USART_Address; +} + +/** + * @brief Determines if the USART is in mute mode or not. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param NewState: new state of the USART mute mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the USART mute mode by setting the RWU bit in the CR1 register */ + USARTx->CR1 |= USART_CR1_RWU; + } + else + { + /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */ + USARTx->CR1 &= (uint16_t)~((uint16_t)USART_CR1_RWU); + } +} +/** + * @brief Selects the USART WakeUp method. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_WakeUp: specifies the USART wakeup method. + * This parameter can be one of the following values: + * @arg USART_WakeUp_IdleLine: WakeUp by an idle line detection + * @arg USART_WakeUp_AddressMark: WakeUp by an address mark + * @retval None + */ +void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_WAKEUP(USART_WakeUp)); + + USARTx->CR1 &= (uint16_t)~((uint16_t)USART_CR1_WAKE); + USARTx->CR1 |= USART_WakeUp; +} + +/** + * @} + */ + +/** @defgroup USART_Group4 LIN mode functions + * @brief LIN mode functions + * +@verbatim + =============================================================================== + LIN mode functions + =============================================================================== + + This subsection provides a set of functions allowing to manage the USART LIN + Mode communication. + + In LIN mode, 8-bit data format with 1 stop bit is required in accordance with + the LIN standard. + + Only this LIN Feature is supported by the USART IP: + - LIN Master Synchronous Break send capability and LIN slave break detection + capability : 13-bit break generation and 10/11 bit break detection + + + USART LIN Master transmitter communication is possible through the following procedure: + 1. Program the Baud rate, Word length = 8bits, Stop bits = 1bit, Parity, + Mode transmitter or Mode receiver and hardware flow control values using + the USART_Init() function. + 2. Enable the USART using the USART_Cmd() function. + 3. Enable the LIN mode using the USART_LINCmd() function. + 4. Send the break character using USART_SendBreak() function. + + USART LIN Master receiver communication is possible through the following procedure: + 1. Program the Baud rate, Word length = 8bits, Stop bits = 1bit, Parity, + Mode transmitter or Mode receiver and hardware flow control values using + the USART_Init() function. + 2. Enable the USART using the USART_Cmd() function. + 3. Configures the break detection length using the USART_LINBreakDetectLengthConfig() + function. + 4. Enable the LIN mode using the USART_LINCmd() function. + + +@note In LIN mode, the following bits must be kept cleared: + - CLKEN in the USART_CR2 register, + - STOP[1:0], SCEN, HDSEL and IREN in the USART_CR3 register. + +@endverbatim + * @{ + */ + +/** + * @brief Sets the USART LIN Break detection length. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_LINBreakDetectLength: specifies the LIN break detection length. + * This parameter can be one of the following values: + * @arg USART_LINBreakDetectLength_10b: 10-bit break detection + * @arg USART_LINBreakDetectLength_11b: 11-bit break detection + * @retval None + */ +void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength)); + + USARTx->CR2 &= (uint16_t)~((uint16_t)USART_CR2_LBDL); + USARTx->CR2 |= USART_LINBreakDetectLength; +} + +/** + * @brief Enables or disables the USART's LIN mode. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param NewState: new state of the USART LIN mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ + USARTx->CR2 |= USART_CR2_LINEN; + } + else + { + /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */ + USARTx->CR2 &= (uint16_t)~((uint16_t)USART_CR2_LINEN); + } +} + +/** + * @brief Transmits break characters. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @retval None + */ +void USART_SendBreak(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Send break characters */ + USARTx->CR1 |= USART_CR1_SBK; +} + +/** + * @} + */ + +/** @defgroup USART_Group5 Halfduplex mode function + * @brief Half-duplex mode function + * +@verbatim + =============================================================================== + Half-duplex mode function + =============================================================================== + + This subsection provides a set of functions allowing to manage the USART + Half-duplex communication. + + The USART can be configured to follow a single-wire half-duplex protocol where + the TX and RX lines are internally connected. + + USART Half duplex communication is possible through the following procedure: + 1. Program the Baud rate, Word length, Stop bits, Parity, Mode transmitter + or Mode receiver and hardware flow control values using the USART_Init() + function. + 2. Configures the USART address using the USART_SetAddress() function. + 3. Enable the USART using the USART_Cmd() function. + 4. Enable the half duplex mode using USART_HalfDuplexCmd() function. + + +@note The RX pin is no longer used +@note In Half-duplex mode the following bits must be kept cleared: + - LINEN and CLKEN bits in the USART_CR2 register. + - SCEN and IREN bits in the USART_CR3 register. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the USART's Half Duplex communication. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param NewState: new state of the USART Communication. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_HDSEL; + } + else + { + /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */ + USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_HDSEL); + } +} + +/** + * @} + */ + + +/** @defgroup USART_Group6 Smartcard mode functions + * @brief Smartcard mode functions + * +@verbatim + =============================================================================== + Smartcard mode functions + =============================================================================== + + This subsection provides a set of functions allowing to manage the USART + Smartcard communication. + + The Smartcard interface is designed to support asynchronous protocol Smartcards as + defined in the ISO 7816-3 standard. + + The USART can provide a clock to the smartcard through the SCLK output. + In smartcard mode, SCLK is not associated to the communication but is simply derived + from the internal peripheral input clock through a 5-bit prescaler. + + Smartcard communication is possible through the following procedure: + 1. Configures the Smartcard Prescaler using the USART_SetPrescaler() function. + 2. Configures the Smartcard Guard Time using the USART_SetGuardTime() function. + 3. Program the USART clock using the USART_ClockInit() function as following: + - USART Clock enabled + - USART CPOL Low + - USART CPHA on first edge + - USART Last Bit Clock Enabled + 4. Program the Smartcard interface using the USART_Init() function as following: + - Word Length = 9 Bits + - 1.5 Stop Bit + - Even parity + - BaudRate = 12096 baud + - Hardware flow control disabled (RTS and CTS signals) + - Tx and Rx enabled + 5. Optionally you can enable the parity error interrupt using the USART_ITConfig() + function + 6. Enable the USART using the USART_Cmd() function. + 7. Enable the Smartcard NACK using the USART_SmartCardNACKCmd() function. + 8. Enable the Smartcard interface using the USART_SmartCardCmd() function. + + Please refer to the ISO 7816-3 specification for more details. + + +@note It is also possible to choose 0.5 stop bit for receiving but it is recommended + to use 1.5 stop bits for both transmitting and receiving to avoid switching + between the two configurations. +@note In smartcard mode, the following bits must be kept cleared: + - LINEN bit in the USART_CR2 register. + - HDSEL and IREN bits in the USART_CR3 register. +@note Smartcard mode is available on USART peripherals only (not available on UART4 + and UART5 peripherals). + +@endverbatim + * @{ + */ + +/** + * @brief Sets the specified USART guard time. + * @param USARTx: where x can be 1, 2, 3 or 6 to select the USART or + * UART peripheral. + * @param USART_GuardTime: specifies the guard time. + * @retval None + */ +void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime) +{ + /* Check the parameters */ + assert_param(IS_USART_1236_PERIPH(USARTx)); + + /* Clear the USART Guard time */ + USARTx->GTPR &= USART_GTPR_PSC; + /* Set the USART guard time */ + USARTx->GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08); +} + +/** + * @brief Enables or disables the USART's Smart Card mode. + * @param USARTx: where x can be 1, 2, 3 or 6 to select the USART or + * UART peripheral. + * @param NewState: new state of the Smart Card mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_1236_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the SC mode by setting the SCEN bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_SCEN; + } + else + { + /* Disable the SC mode by clearing the SCEN bit in the CR3 register */ + USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_SCEN); + } +} + +/** + * @brief Enables or disables NACK transmission. + * @param USARTx: where x can be 1, 2, 3 or 6 to select the USART or + * UART peripheral. + * @param NewState: new state of the NACK transmission. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_1236_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the NACK transmission by setting the NACK bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_NACK; + } + else + { + /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */ + USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_NACK); + } +} + +/** + * @} + */ + +/** @defgroup USART_Group7 IrDA mode functions + * @brief IrDA mode functions + * +@verbatim + =============================================================================== + IrDA mode functions + =============================================================================== + + This subsection provides a set of functions allowing to manage the USART + IrDA communication. + + IrDA is a half duplex communication protocol. If the Transmitter is busy, any data + on the IrDA receive line will be ignored by the IrDA decoder and if the Receiver + is busy, data on the TX from the USART to IrDA will not be encoded by IrDA. + While receiving data, transmission should be avoided as the data to be transmitted + could be corrupted. + + IrDA communication is possible through the following procedure: + 1. Program the Baud rate, Word length = 8 bits, Stop bits, Parity, Transmitter/Receiver + modes and hardware flow control values using the USART_Init() function. + 2. Enable the USART using the USART_Cmd() function. + 3. Configures the IrDA pulse width by configuring the prescaler using + the USART_SetPrescaler() function. + 4. Configures the IrDA USART_IrDAMode_LowPower or USART_IrDAMode_Normal mode + using the USART_IrDAConfig() function. + 5. Enable the IrDA using the USART_IrDACmd() function. + +@note A pulse of width less than two and greater than one PSC period(s) may or may + not be rejected. +@note The receiver set up time should be managed by software. The IrDA physical layer + specification specifies a minimum of 10 ms delay between transmission and + reception (IrDA is a half duplex protocol). +@note In IrDA mode, the following bits must be kept cleared: + - LINEN, STOP and CLKEN bits in the USART_CR2 register. + - SCEN and HDSEL bits in the USART_CR3 register. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the USART's IrDA interface. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_IrDAMode: specifies the IrDA mode. + * This parameter can be one of the following values: + * @arg USART_IrDAMode_LowPower + * @arg USART_IrDAMode_Normal + * @retval None + */ +void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_IRDA_MODE(USART_IrDAMode)); + + USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_IRLP); + USARTx->CR3 |= USART_IrDAMode; +} + +/** + * @brief Enables or disables the USART's IrDA interface. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param NewState: new state of the IrDA mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the IrDA mode by setting the IREN bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_IREN; + } + else + { + /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */ + USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_IREN); + } +} + +/** + * @} + */ + +/** @defgroup USART_Group8 DMA transfers management functions + * @brief DMA transfers management functions + * +@verbatim + =============================================================================== + DMA transfers management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the USART's DMA interface. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_DMAReq: specifies the DMA request. + * This parameter can be any combination of the following values: + * @arg USART_DMAReq_Tx: USART DMA transmit request + * @arg USART_DMAReq_Rx: USART DMA receive request + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DMAREQ(USART_DMAReq)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DMA transfer for selected requests by setting the DMAT and/or + DMAR bits in the USART CR3 register */ + USARTx->CR3 |= USART_DMAReq; + } + else + { + /* Disable the DMA transfer for selected requests by clearing the DMAT and/or + DMAR bits in the USART CR3 register */ + USARTx->CR3 &= (uint16_t)~USART_DMAReq; + } +} + +/** + * @} + */ + +/** @defgroup USART_Group9 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + + This subsection provides a set of functions allowing to configure the USART + Interrupts sources, DMA channels requests and check or clear the flags or + pending bits status. + The user should identify which mode will be used in his application to manage + the communication: Polling mode, Interrupt mode or DMA mode. + + Polling Mode + ============= + In Polling Mode, the SPI communication can be managed by 10 flags: + 1. USART_FLAG_TXE : to indicate the status of the transmit buffer register + 2. USART_FLAG_RXNE : to indicate the status of the receive buffer register + 3. USART_FLAG_TC : to indicate the status of the transmit operation + 4. USART_FLAG_IDLE : to indicate the status of the Idle Line + 5. USART_FLAG_CTS : to indicate the status of the nCTS input + 6. USART_FLAG_LBD : to indicate the status of the LIN break detection + 7. USART_FLAG_NE : to indicate if a noise error occur + 8. USART_FLAG_FE : to indicate if a frame error occur + 9. USART_FLAG_PE : to indicate if a parity error occur + 10. USART_FLAG_ORE : to indicate if an Overrun error occur + + In this Mode it is advised to use the following functions: + - FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG); + - void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG); + + Interrupt Mode + =============== + In Interrupt Mode, the USART communication can be managed by 8 interrupt sources + and 10 pending bits: + + Pending Bits: + ------------- + 1. USART_IT_TXE : to indicate the status of the transmit buffer register + 2. USART_IT_RXNE : to indicate the status of the receive buffer register + 3. USART_IT_TC : to indicate the status of the transmit operation + 4. USART_IT_IDLE : to indicate the status of the Idle Line + 5. USART_IT_CTS : to indicate the status of the nCTS input + 6. USART_IT_LBD : to indicate the status of the LIN break detection + 7. USART_IT_NE : to indicate if a noise error occur + 8. USART_IT_FE : to indicate if a frame error occur + 9. USART_IT_PE : to indicate if a parity error occur + 10. USART_IT_ORE : to indicate if an Overrun error occur + + Interrupt Source: + ----------------- + 1. USART_IT_TXE : specifies the interrupt source for the Tx buffer empty + interrupt. + 2. USART_IT_RXNE : specifies the interrupt source for the Rx buffer not + empty interrupt. + 3. USART_IT_TC : specifies the interrupt source for the Transmit complete + interrupt. + 4. USART_IT_IDLE : specifies the interrupt source for the Idle Line interrupt. + 5. USART_IT_CTS : specifies the interrupt source for the CTS interrupt. + 6. USART_IT_LBD : specifies the interrupt source for the LIN break detection + interrupt. + 7. USART_IT_PE : specifies the interrupt source for the parity error interrupt. + 8. USART_IT_ERR : specifies the interrupt source for the errors interrupt. + +@note Some parameters are coded in order to use them as interrupt source or as pending bits. + + In this Mode it is advised to use the following functions: + - void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState); + - ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT); + - void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT); + + DMA Mode + ======== + In DMA Mode, the USART communication can be managed by 2 DMA Channel requests: + 1. USART_DMAReq_Tx: specifies the Tx buffer DMA transfer request + 2. USART_DMAReq_Rx: specifies the Rx buffer DMA transfer request + + In this Mode it is advised to use the following function: + - void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState); + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified USART interrupts. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_IT: specifies the USART interrupt sources to be enabled or disabled. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TXE: Transmit Data Register empty interrupt + * @arg USART_IT_TC: Transmission complete interrupt + * @arg USART_IT_RXNE: Receive Data register not empty interrupt + * @arg USART_IT_IDLE: Idle line detection interrupt + * @arg USART_IT_PE: Parity Error interrupt + * @arg USART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) + * @param NewState: new state of the specified USARTx interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState) +{ + uint32_t usartreg = 0x00, itpos = 0x00, itmask = 0x00; + uint32_t usartxbase = 0x00; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CONFIG_IT(USART_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_1236_PERIPH(USARTx)); + } + + usartxbase = (uint32_t)USARTx; + + /* Get the USART register index */ + usartreg = (((uint8_t)USART_IT) >> 0x05); + + /* Get the interrupt position */ + itpos = USART_IT & IT_MASK; + itmask = (((uint32_t)0x01) << itpos); + + if (usartreg == 0x01) /* The IT is in CR1 register */ + { + usartxbase += 0x0C; + } + else if (usartreg == 0x02) /* The IT is in CR2 register */ + { + usartxbase += 0x10; + } + else /* The IT is in CR3 register */ + { + usartxbase += 0x14; + } + if (NewState != DISABLE) + { + *(__IO uint32_t*)usartxbase |= itmask; + } + else + { + *(__IO uint32_t*)usartxbase &= ~itmask; + } +} + +/** + * @brief Checks whether the specified USART flag is set or not. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg USART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5) + * @arg USART_FLAG_LBD: LIN Break detection flag + * @arg USART_FLAG_TXE: Transmit data register empty flag + * @arg USART_FLAG_TC: Transmission Complete flag + * @arg USART_FLAG_RXNE: Receive data register not empty flag + * @arg USART_FLAG_IDLE: Idle Line detection flag + * @arg USART_FLAG_ORE: OverRun Error flag + * @arg USART_FLAG_NE: Noise Error flag + * @arg USART_FLAG_FE: Framing Error flag + * @arg USART_FLAG_PE: Parity Error flag + * @retval The new state of USART_FLAG (SET or RESET). + */ +FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_FLAG(USART_FLAG)); + + /* The CTS flag is not available for UART4 and UART5 */ + if (USART_FLAG == USART_FLAG_CTS) + { + assert_param(IS_USART_1236_PERIPH(USARTx)); + } + + if ((USARTx->SR & USART_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the USARTx's pending flags. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg USART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5). + * @arg USART_FLAG_LBD: LIN Break detection flag. + * @arg USART_FLAG_TC: Transmission Complete flag. + * @arg USART_FLAG_RXNE: Receive data register not empty flag. + * + * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun + * error) and IDLE (Idle line detected) flags are cleared by software + * sequence: a read operation to USART_SR register (USART_GetFlagStatus()) + * followed by a read operation to USART_DR register (USART_ReceiveData()). + * @note RXNE flag can be also cleared by a read to the USART_DR register + * (USART_ReceiveData()). + * @note TC flag can be also cleared by software sequence: a read operation to + * USART_SR register (USART_GetFlagStatus()) followed by a write operation + * to USART_DR register (USART_SendData()). + * @note TXE flag is cleared only by a write to the USART_DR register + * (USART_SendData()). + * + * @retval None + */ +void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CLEAR_FLAG(USART_FLAG)); + + /* The CTS flag is not available for UART4 and UART5 */ + if ((USART_FLAG & USART_FLAG_CTS) == USART_FLAG_CTS) + { + assert_param(IS_USART_1236_PERIPH(USARTx)); + } + + USARTx->SR = (uint16_t)~USART_FLAG; +} + +/** + * @brief Checks whether the specified USART interrupt has occurred or not. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_IT: specifies the USART interrupt source to check. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TXE: Transmit Data Register empty interrupt + * @arg USART_IT_TC: Transmission complete interrupt + * @arg USART_IT_RXNE: Receive Data register not empty interrupt + * @arg USART_IT_IDLE: Idle line detection interrupt + * @arg USART_IT_ORE_RX : OverRun Error interrupt if the RXNEIE bit is set + * @arg USART_IT_ORE_ER : OverRun Error interrupt if the EIE bit is set + * @arg USART_IT_NE: Noise Error interrupt + * @arg USART_IT_FE: Framing Error interrupt + * @arg USART_IT_PE: Parity Error interrupt + * @retval The new state of USART_IT (SET or RESET). + */ +ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT) +{ + uint32_t bitpos = 0x00, itmask = 0x00, usartreg = 0x00; + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_GET_IT(USART_IT)); + + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_1236_PERIPH(USARTx)); + } + + /* Get the USART register index */ + usartreg = (((uint8_t)USART_IT) >> 0x05); + /* Get the interrupt position */ + itmask = USART_IT & IT_MASK; + itmask = (uint32_t)0x01 << itmask; + + if (usartreg == 0x01) /* The IT is in CR1 register */ + { + itmask &= USARTx->CR1; + } + else if (usartreg == 0x02) /* The IT is in CR2 register */ + { + itmask &= USARTx->CR2; + } + else /* The IT is in CR3 register */ + { + itmask &= USARTx->CR3; + } + + bitpos = USART_IT >> 0x08; + bitpos = (uint32_t)0x01 << bitpos; + bitpos &= USARTx->SR; + if ((itmask != (uint16_t)RESET)&&(bitpos != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + return bitstatus; +} + +/** + * @brief Clears the USARTx's interrupt pending bits. + * @param USARTx: where x can be 1, 2, 3, 4, 5 or 6 to select the USART or + * UART peripheral. + * @param USART_IT: specifies the interrupt pending bit to clear. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TC: Transmission complete interrupt. + * @arg USART_IT_RXNE: Receive Data register not empty interrupt. + * + * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun + * error) and IDLE (Idle line detected) pending bits are cleared by + * software sequence: a read operation to USART_SR register + * (USART_GetITStatus()) followed by a read operation to USART_DR register + * (USART_ReceiveData()). + * @note RXNE pending bit can be also cleared by a read to the USART_DR register + * (USART_ReceiveData()). + * @note TC pending bit can be also cleared by software sequence: a read + * operation to USART_SR register (USART_GetITStatus()) followed by a write + * operation to USART_DR register (USART_SendData()). + * @note TXE pending bit is cleared only by a write to the USART_DR register + * (USART_SendData()). + * + * @retval None + */ +void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT) +{ + uint16_t bitpos = 0x00, itmask = 0x00; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CLEAR_IT(USART_IT)); + + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_1236_PERIPH(USARTx)); + } + + bitpos = USART_IT >> 0x08; + itmask = ((uint16_t)0x01 << (uint16_t)bitpos); + USARTx->SR = (uint16_t)~itmask; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_wwdg.c b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_wwdg.c new file mode 100644 index 000000000..816a92d81 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_wwdg.c @@ -0,0 +1,303 @@ +/** + ****************************************************************************** + * @file stm32f4xx_wwdg.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief This file provides firmware functions to manage the following + * functionalities of the Window watchdog (WWDG) peripheral: + * - Prescaler, Refresh window and Counter configuration + * - WWDG activation + * - Interrupts and flags management + * + * @verbatim + * + * =================================================================== + * WWDG features + * =================================================================== + * + * Once enabled the WWDG generates a system reset on expiry of a programmed + * time period, unless the program refreshes the counter (downcounter) + * before to reach 0x3F value (i.e. a reset is generated when the counter + * value rolls over from 0x40 to 0x3F). + * An MCU reset is also generated if the counter value is refreshed + * before the counter has reached the refresh window value. This + * implies that the counter must be refreshed in a limited window. + * + * Once enabled the WWDG cannot be disabled except by a system reset. + * + * WWDGRST flag in RCC_CSR register can be used to inform when a WWDG + * reset occurs. + * + * The WWDG counter input clock is derived from the APB clock divided + * by a programmable prescaler. + * + * WWDG counter clock = PCLK1 / Prescaler + * WWDG timeout = (WWDG counter clock) * (counter value) + * + * Min-max timeout value @42 MHz(PCLK1): ~97.5 us / ~49.9 ms + * + * =================================================================== + * How to use this driver + * =================================================================== + * 1. Enable WWDG clock using RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, ENABLE) function + * + * 2. Configure the WWDG prescaler using WWDG_SetPrescaler() function + * + * 3. Configure the WWDG refresh window using WWDG_SetWindowValue() function + * + * 4. Set the WWDG counter value and start it using WWDG_Enable() function. + * When the WWDG is enabled the counter value should be configured to + * a value greater than 0x40 to prevent generating an immediate reset. + * + * 5. Optionally you can enable the Early wakeup interrupt which is + * generated when the counter reach 0x40. + * Once enabled this interrupt cannot be disabled except by a system reset. + * + * 6. Then the application program must refresh the WWDG counter at regular + * intervals during normal operation to prevent an MCU reset, using + * WWDG_SetCounter() function. This operation must occur only when + * the counter value is lower than the refresh window value, + * programmed using WWDG_SetWindowValue(). + * + * @endverbatim + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_wwdg.h" +#include "stm32f4xx_rcc.h" + +/** @addtogroup STM32F4xx_StdPeriph_Driver + * @{ + */ + +/** @defgroup WWDG + * @brief WWDG driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* ----------- WWDG registers bit address in the alias region ----------- */ +#define WWDG_OFFSET (WWDG_BASE - PERIPH_BASE) +/* Alias word address of EWI bit */ +#define CFR_OFFSET (WWDG_OFFSET + 0x04) +#define EWI_BitNumber 0x09 +#define CFR_EWI_BB (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4)) + +/* --------------------- WWDG registers bit mask ------------------------ */ +/* CFR register bit mask */ +#define CFR_WDGTB_MASK ((uint32_t)0xFFFFFE7F) +#define CFR_W_MASK ((uint32_t)0xFFFFFF80) +#define BIT_MASK ((uint8_t)0x7F) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup WWDG_Private_Functions + * @{ + */ + +/** @defgroup WWDG_Group1 Prescaler, Refresh window and Counter configuration functions + * @brief Prescaler, Refresh window and Counter configuration functions + * +@verbatim + =============================================================================== + Prescaler, Refresh window and Counter configuration functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the WWDG peripheral registers to their default reset values. + * @param None + * @retval None + */ +void WWDG_DeInit(void) +{ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE); +} + +/** + * @brief Sets the WWDG Prescaler. + * @param WWDG_Prescaler: specifies the WWDG Prescaler. + * This parameter can be one of the following values: + * @arg WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1 + * @arg WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2 + * @arg WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4 + * @arg WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8 + * @retval None + */ +void WWDG_SetPrescaler(uint32_t WWDG_Prescaler) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler)); + /* Clear WDGTB[1:0] bits */ + tmpreg = WWDG->CFR & CFR_WDGTB_MASK; + /* Set WDGTB[1:0] bits according to WWDG_Prescaler value */ + tmpreg |= WWDG_Prescaler; + /* Store the new value */ + WWDG->CFR = tmpreg; +} + +/** + * @brief Sets the WWDG window value. + * @param WindowValue: specifies the window value to be compared to the downcounter. + * This parameter value must be lower than 0x80. + * @retval None + */ +void WWDG_SetWindowValue(uint8_t WindowValue) +{ + __IO uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_WWDG_WINDOW_VALUE(WindowValue)); + /* Clear W[6:0] bits */ + + tmpreg = WWDG->CFR & CFR_W_MASK; + + /* Set W[6:0] bits according to WindowValue value */ + tmpreg |= WindowValue & (uint32_t) BIT_MASK; + + /* Store the new value */ + WWDG->CFR = tmpreg; +} + +/** + * @brief Enables the WWDG Early Wakeup interrupt(EWI). + * @note Once enabled this interrupt cannot be disabled except by a system reset. + * @param None + * @retval None + */ +void WWDG_EnableIT(void) +{ + *(__IO uint32_t *) CFR_EWI_BB = (uint32_t)ENABLE; +} + +/** + * @brief Sets the WWDG counter value. + * @param Counter: specifies the watchdog counter value. + * This parameter must be a number between 0x40 and 0x7F (to prevent generating + * an immediate reset) + * @retval None + */ +void WWDG_SetCounter(uint8_t Counter) +{ + /* Check the parameters */ + assert_param(IS_WWDG_COUNTER(Counter)); + /* Write to T[6:0] bits to configure the counter value, no need to do + a read-modify-write; writing a 0 to WDGA bit does nothing */ + WWDG->CR = Counter & BIT_MASK; +} +/** + * @} + */ + +/** @defgroup WWDG_Group2 WWDG activation functions + * @brief WWDG activation functions + * +@verbatim + =============================================================================== + WWDG activation function + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables WWDG and load the counter value. + * @param Counter: specifies the watchdog counter value. + * This parameter must be a number between 0x40 and 0x7F (to prevent generating + * an immediate reset) + * @retval None + */ +void WWDG_Enable(uint8_t Counter) +{ + /* Check the parameters */ + assert_param(IS_WWDG_COUNTER(Counter)); + WWDG->CR = WWDG_CR_WDGA | Counter; +} +/** + * @} + */ + +/** @defgroup WWDG_Group3 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + Interrupts and flags management functions + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Checks whether the Early Wakeup interrupt flag is set or not. + * @param None + * @retval The new state of the Early Wakeup interrupt flag (SET or RESET) + */ +FlagStatus WWDG_GetFlagStatus(void) +{ + FlagStatus bitstatus = RESET; + + if ((WWDG->SR) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears Early Wakeup interrupt flag. + * @param None + * @retval None + */ +void WWDG_ClearFlag(void) +{ + WWDG->SR = (uint32_t)RESET; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_conf.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_conf.h new file mode 100644 index 000000000..3cfd5b6d6 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_conf.h @@ -0,0 +1,75 @@ +/** + ****************************************************************************** + * @file usbd_conf_template.h + * @author MCD Application Team + * @version V1.0.0 + * @date 22-July-2011 + * @brief usb device configuration template file + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBD_CONF__H__ +#define __USBD_CONF__H__ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + + + +/** @defgroup USB_CONF_Exported_Defines + * @{ + */ +#define USBD_CFG_MAX_NUM 1 +#define USB_MAX_STR_DESC_SIZ 64 + +/** + * @} + */ + + +/** @defgroup USB_CONF_Exported_Types + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_CONF_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_CONF_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_CONF_Exported_FunctionsPrototype + * @{ + */ +/** + * @} + */ + + +#endif //__USBD_CONF__H__ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_core.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_core.h new file mode 100644 index 000000000..fb20acf63 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_core.h @@ -0,0 +1,114 @@ +/** + ****************************************************************************** + * @file usbd_core.h + * @author MCD Application Team + * @version V1.0.0 + * @date 22-July-2011 + * @brief Header file for usbd_core.c + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBD_CORE_H +#define __USBD_CORE_H + +/* Includes ------------------------------------------------------------------*/ +#include "usb_dcd.h" +#include "usbd_def.h" +#include "usbd_conf.h" + +/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY + * @{ + */ + +/** @defgroup USBD_CORE + * @brief This file is the Header file for usbd_core.c file + * @{ + */ + + +/** @defgroup USBD_CORE_Exported_Defines + * @{ + */ + +typedef enum { + USBD_OK = 0, + USBD_BUSY, + USBD_FAIL, +}USBD_Status; +/** + * @} + */ + + +/** @defgroup USBD_CORE_Exported_TypesDefinitions + * @{ + */ + + +/** + * @} + */ + + + +/** @defgroup USBD_CORE_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup USBD_CORE_Exported_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup USBD_CORE_Exported_FunctionsPrototype + * @{ + */ +void USBD_Init(USB_OTG_CORE_HANDLE *pdev, + USB_OTG_CORE_ID_TypeDef coreID, + USBD_DEVICE *pDevice, + USBD_Class_cb_TypeDef *class_cb, + USBD_Usr_cb_TypeDef *usr_cb); + +USBD_Status USBD_DeInit(USB_OTG_CORE_HANDLE *pdev); + +USBD_Status USBD_ClrCfg(USB_OTG_CORE_HANDLE *pdev, uint8_t cfgidx); + +USBD_Status USBD_SetCfg(USB_OTG_CORE_HANDLE *pdev, uint8_t cfgidx); + +/** + * @} + */ + +#endif /* __USBD_CORE_H */ + +/** + * @} + */ + +/** +* @} +*/ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + + + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_def.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_def.h new file mode 100644 index 000000000..a8c86710d --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_def.h @@ -0,0 +1,149 @@ +/** + ****************************************************************************** + * @file usbd_def.h + * @author MCD Application Team + * @version V1.0.0 + * @date 22-July-2011 + * @brief general defines for the usb device library + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ + +#ifndef __USBD_DEF_H +#define __USBD_DEF_H +/* Includes ------------------------------------------------------------------*/ +#include "usbd_conf.h" + +/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY + * @{ + */ + +/** @defgroup USB_DEF + * @brief general defines for the usb device library file + * @{ + */ + +/** @defgroup USB_DEF_Exported_Defines + * @{ + */ + +#ifndef NULL +#define NULL 0 +#endif + +#define USB_LEN_DEV_QUALIFIER_DESC 0x0A +#define USB_LEN_DEV_DESC 0x12 +#define USB_LEN_CFG_DESC 0x09 +#define USB_LEN_IF_DESC 0x09 +#define USB_LEN_EP_DESC 0x07 +#define USB_LEN_OTG_DESC 0x03 + +#define USBD_IDX_LANGID_STR 0x00 +#define USBD_IDX_MFC_STR 0x01 +#define USBD_IDX_PRODUCT_STR 0x02 +#define USBD_IDX_SERIAL_STR 0x03 +#define USBD_IDX_CONFIG_STR 0x04 +#define USBD_IDX_INTERFACE_STR 0x05 + +#define USB_REQ_TYPE_STANDARD 0x00 +#define USB_REQ_TYPE_CLASS 0x20 +#define USB_REQ_TYPE_VENDOR 0x40 +#define USB_REQ_TYPE_MASK 0x60 + +#define USB_REQ_RECIPIENT_DEVICE 0x00 +#define USB_REQ_RECIPIENT_INTERFACE 0x01 +#define USB_REQ_RECIPIENT_ENDPOINT 0x02 +#define USB_REQ_RECIPIENT_MASK 0x03 + +#define USB_REQ_GET_STATUS 0x00 +#define USB_REQ_CLEAR_FEATURE 0x01 +#define USB_REQ_SET_FEATURE 0x03 +#define USB_REQ_SET_ADDRESS 0x05 +#define USB_REQ_GET_DESCRIPTOR 0x06 +#define USB_REQ_SET_DESCRIPTOR 0x07 +#define USB_REQ_GET_CONFIGURATION 0x08 +#define USB_REQ_SET_CONFIGURATION 0x09 +#define USB_REQ_GET_INTERFACE 0x0A +#define USB_REQ_SET_INTERFACE 0x0B +#define USB_REQ_SYNCH_FRAME 0x0C + +#define USB_DESC_TYPE_DEVICE 1 +#define USB_DESC_TYPE_CONFIGURATION 2 +#define USB_DESC_TYPE_STRING 3 +#define USB_DESC_TYPE_INTERFACE 4 +#define USB_DESC_TYPE_ENDPOINT 5 +#define USB_DESC_TYPE_DEVICE_QUALIFIER 6 +#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 7 + + +#define USB_CONFIG_REMOTE_WAKEUP 2 +#define USB_CONFIG_SELF_POWERED 1 + +#define USB_FEATURE_EP_HALT 0 +#define USB_FEATURE_REMOTE_WAKEUP 1 +#define USB_FEATURE_TEST_MODE 2 + +/** + * @} + */ + + +/** @defgroup USBD_DEF_Exported_TypesDefinitions + * @{ + */ +/** + * @} + */ + + + +/** @defgroup USBD_DEF_Exported_Macros + * @{ + */ +#define SWAPBYTE(addr) (((uint16_t)(*((uint8_t *)(addr)))) + \ + (((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8)) + +#define LOBYTE(x) ((uint8_t)(x & 0x00FF)) +#define HIBYTE(x) ((uint8_t)((x & 0xFF00) >>8)) +/** + * @} + */ + +/** @defgroup USBD_DEF_Exported_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup USBD_DEF_Exported_FunctionsPrototype + * @{ + */ + +/** + * @} + */ + +#endif /* __USBD_DEF_H */ + +/** + * @} + */ + +/** +* @} +*/ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_desc.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_desc.h new file mode 100644 index 000000000..6f0a6d268 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_desc.h @@ -0,0 +1 @@ +#define USBD_ITF_MAX_NUM 2 diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_ioreq.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_ioreq.h new file mode 100644 index 000000000..92de45e8c --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_ioreq.h @@ -0,0 +1,115 @@ +/** + ****************************************************************************** + * @file usbd_ioreq.h + * @author MCD Application Team + * @version V1.0.0 + * @date 22-July-2011 + * @brief header file for the usbd_ioreq.c file + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ + +#ifndef __USBD_IOREQ_H_ +#define __USBD_IOREQ_H_ + +/* Includes ------------------------------------------------------------------*/ +#include "usbd_def.h" +#include "usbd_core.h" + +/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY + * @{ + */ + +/** @defgroup USBD_IOREQ + * @brief header file for the usbd_ioreq.c file + * @{ + */ + +/** @defgroup USBD_IOREQ_Exported_Defines + * @{ + */ +/** + * @} + */ + + +/** @defgroup USBD_IOREQ_Exported_Types + * @{ + */ + + +/** + * @} + */ + + + +/** @defgroup USBD_IOREQ_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup USBD_IOREQ_Exported_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup USBD_IOREQ_Exported_FunctionsPrototype + * @{ + */ + +USBD_Status USBD_CtlSendData (USB_OTG_CORE_HANDLE *pdev, + const uint8_t *buf, + uint16_t len); + +USBD_Status USBD_CtlContinueSendData (USB_OTG_CORE_HANDLE *pdev, + uint8_t *pbuf, + uint16_t len); + +USBD_Status USBD_CtlPrepareRx (USB_OTG_CORE_HANDLE *pdev, + uint8_t *pbuf, + uint16_t len); + +USBD_Status USBD_CtlContinueRx (USB_OTG_CORE_HANDLE *pdev, + uint8_t *pbuf, + uint16_t len); + +USBD_Status USBD_CtlSendStatus (USB_OTG_CORE_HANDLE *pdev); + +USBD_Status USBD_CtlReceiveStatus (USB_OTG_CORE_HANDLE *pdev); + +uint16_t USBD_GetRxCount (USB_OTG_CORE_HANDLE *pdev , + uint8_t epnum); + +/** + * @} + */ + +#endif /* __USBD_IOREQ_H_ */ + +/** + * @} + */ + +/** +* @} +*/ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_req.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_req.h new file mode 100644 index 000000000..9aa9e44a3 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_req.h @@ -0,0 +1,102 @@ +/** + ****************************************************************************** + * @file usbd_req.h + * @author MCD Application Team + * @version V1.0.0 + * @date 22-July-2011 + * @brief header file for the usbd_req.c file + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ + +#ifndef __USB_REQUEST_H_ +#define __USB_REQUEST_H_ + +/* Includes ------------------------------------------------------------------*/ +#include "usbd_def.h" +#include "usbd_core.h" +#include "usbd_conf.h" + + +/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY + * @{ + */ + +/** @defgroup USBD_REQ + * @brief header file for the usbd_ioreq.c file + * @{ + */ + +/** @defgroup USBD_REQ_Exported_Defines + * @{ + */ +/** + * @} + */ + + +/** @defgroup USBD_REQ_Exported_Types + * @{ + */ +/** + * @} + */ + + + +/** @defgroup USBD_REQ_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USBD_REQ_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USBD_REQ_Exported_FunctionsPrototype + * @{ + */ + +USBD_Status USBD_StdDevReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req); +USBD_Status USBD_StdItfReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req); +USBD_Status USBD_StdEPReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req); +void USBD_ParseSetupRequest( USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req); + +void USBD_CtlError( USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req); + +void USBD_GetString(uint8_t *desc, uint8_t *unicode, uint16_t *len); +/** + * @} + */ + +#endif /* __USB_REQUEST_H_ */ + +/** + * @} + */ + +/** +* @} +*/ + + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_usr.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_usr.h new file mode 100644 index 000000000..44e7b1dd2 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/inc/usbd_usr.h @@ -0,0 +1,135 @@ +/** + ****************************************************************************** + * @file usbd_usr.h + * @author MCD Application Team + * @version V1.0.0 + * @date 22-July-2011 + * @brief Header file for usbd_usr.c + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBD_USR_H__ +#define __USBD_USR_H__ + +/* Includes ------------------------------------------------------------------*/ +#include "usbd_core.h" + + +/** @addtogroup USBD_USER + * @{ + */ + +/** @addtogroup USBD_MSC_DEMO_USER_CALLBACKS + * @{ + */ + +/** @defgroup USBD_USR + * @brief This file is the Header file for usbd_usr.c + * @{ + */ + + +/** @defgroup USBD_USR_Exported_Types + * @{ + */ + +extern USBD_Usr_cb_TypeDef USR_cb; +extern USBD_Usr_cb_TypeDef USR_FS_cb; +extern USBD_Usr_cb_TypeDef USR_HS_cb; + + + +/** + * @} + */ + + + +/** @defgroup USBD_USR_Exported_Defines + * @{ + */ + +/** + * @} + */ + +/** @defgroup USBD_USR_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USBD_USR_Exported_Variables + * @{ + */ + +void USBD_USR_Init(void); +void USBD_USR_DeviceReset (uint8_t speed); +void USBD_USR_DeviceConfigured (void); +void USBD_USR_DeviceSuspended(void); +void USBD_USR_DeviceResumed(void); + +void USBD_USR_DeviceConnected(void); +void USBD_USR_DeviceDisconnected(void); + +void USBD_USR_FS_Init(void); +void USBD_USR_FS_DeviceReset (uint8_t speed); +void USBD_USR_FS_DeviceConfigured (void); +void USBD_USR_FS_DeviceSuspended(void); +void USBD_USR_FS_DeviceResumed(void); + +void USBD_USR_FS_DeviceConnected(void); +void USBD_USR_FS_DeviceDisconnected(void); + +void USBD_USR_HS_Init(void); +void USBD_USR_HS_DeviceReset (uint8_t speed); +void USBD_USR_HS_DeviceConfigured (void); +void USBD_USR_HS_DeviceSuspended(void); +void USBD_USR_HS_DeviceResumed(void); + +void USBD_USR_HS_DeviceConnected(void); +void USBD_USR_HS_DeviceDisconnected(void); + +/** + * @} + */ + +/** @defgroup USBD_USR_Exported_FunctionsPrototype + * @{ + */ +/** + * @} + */ + +#endif /*__USBD_USR_H__*/ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + + + + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/src/usbd_core.c b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/src/usbd_core.c new file mode 100644 index 000000000..2a51d3aef --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/src/usbd_core.c @@ -0,0 +1,476 @@ +/** + ****************************************************************************** + * @file usbd_core.c + * @author MCD Application Team + * @version V1.0.0 + * @date 22-July-2011 + * @brief This file provides all the USBD core functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usbd_core.h" +#include "usbd_req.h" +#include "usbd_ioreq.h" +#include "usb_dcd_int.h" +#include "usb_bsp.h" + +/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY +* @{ +*/ + + +/** @defgroup USBD_CORE +* @brief usbd core module +* @{ +*/ + +/** @defgroup USBD_CORE_Private_TypesDefinitions +* @{ +*/ +/** +* @} +*/ + + +/** @defgroup USBD_CORE_Private_Defines +* @{ +*/ + +/** +* @} +*/ + + +/** @defgroup USBD_CORE_Private_Macros +* @{ +*/ +/** +* @} +*/ + + + + +/** @defgroup USBD_CORE_Private_FunctionPrototypes +* @{ +*/ +static uint8_t USBD_SetupStage(USB_OTG_CORE_HANDLE *pdev); +static uint8_t USBD_DataOutStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum); +static uint8_t USBD_DataInStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum); +static uint8_t USBD_SOF(USB_OTG_CORE_HANDLE *pdev); +static uint8_t USBD_Reset(USB_OTG_CORE_HANDLE *pdev); +static uint8_t USBD_Suspend(USB_OTG_CORE_HANDLE *pdev); +static uint8_t USBD_Resume(USB_OTG_CORE_HANDLE *pdev); +#ifdef VBUS_SENSING_ENABLED +static uint8_t USBD_DevConnected(USB_OTG_CORE_HANDLE *pdev); +static uint8_t USBD_DevDisconnected(USB_OTG_CORE_HANDLE *pdev); +#endif +static uint8_t USBD_IsoINIncomplete(USB_OTG_CORE_HANDLE *pdev); +static uint8_t USBD_IsoOUTIncomplete(USB_OTG_CORE_HANDLE *pdev); +/** +* @} +*/ + +/** @defgroup USBD_CORE_Private_Variables +* @{ +*/ + + + +USBD_DCD_INT_cb_TypeDef USBD_DCD_INT_cb = +{ + USBD_DataOutStage, + USBD_DataInStage, + USBD_SetupStage, + USBD_SOF, + USBD_Reset, + USBD_Suspend, + USBD_Resume, + USBD_IsoINIncomplete, + USBD_IsoOUTIncomplete, +#ifdef VBUS_SENSING_ENABLED +USBD_DevConnected, +USBD_DevDisconnected, +#endif +}; + +USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops = &USBD_DCD_INT_cb; +/** +* @} +*/ + +/** @defgroup USBD_CORE_Private_Functions +* @{ +*/ + +/** +* @brief USBD_Init +* Initailizes the device stack and load the class driver +* @param pdev: device instance +* @param core_address: USB OTG core ID +* @param class_cb: Class callback structure address +* @param usr_cb: User callback structure address +* @retval None +*/ +void USBD_Init(USB_OTG_CORE_HANDLE *pdev, + USB_OTG_CORE_ID_TypeDef coreID, + USBD_DEVICE *pDevice, + USBD_Class_cb_TypeDef *class_cb, + USBD_Usr_cb_TypeDef *usr_cb) +{ + /* Hardware Init */ + USB_OTG_BSP_Init(pdev); + + USBD_DeInit(pdev); + + /*Register class and user callbacks */ + pdev->dev.class_cb = class_cb; + pdev->dev.usr_cb = usr_cb; + pdev->dev.usr_device = pDevice; + + /* set USB OTG core params */ + DCD_Init(pdev , coreID); + + /* Upon Init call usr callback */ + pdev->dev.usr_cb->Init(); + + /* Enable Interrupts */ + USB_OTG_BSP_EnableInterrupt(pdev); +} + +/** +* @brief USBD_DeInit +* Re-Initialize th deviuce library +* @param pdev: device instance +* @retval status: status +*/ +USBD_Status USBD_DeInit(USB_OTG_CORE_HANDLE *pdev) +{ + /* Software Init */ + + return USBD_OK; +} + +/** +* @brief USBD_SetupStage +* Handle the setup stage +* @param pdev: device instance +* @retval status +*/ +static uint8_t USBD_SetupStage(USB_OTG_CORE_HANDLE *pdev) +{ + USB_SETUP_REQ req; + + USBD_ParseSetupRequest(pdev , &req); + + switch (req.bmRequest & 0x1F) + { + case USB_REQ_RECIPIENT_DEVICE: + USBD_StdDevReq (pdev, &req); + break; + + case USB_REQ_RECIPIENT_INTERFACE: + USBD_StdItfReq(pdev, &req); + break; + + case USB_REQ_RECIPIENT_ENDPOINT: + USBD_StdEPReq(pdev, &req); + break; + + default: + DCD_EP_Stall(pdev , req.bmRequest & 0x80); + break; + } + return USBD_OK; +} + +/** +* @brief USBD_DataOutStage +* Handle data out stage +* @param pdev: device instance +* @param epnum: endpoint index +* @retval status +*/ +static uint8_t USBD_DataOutStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum) +{ + USB_OTG_EP *ep; + + if(epnum == 0) + { + ep = &pdev->dev.out_ep[0]; + if ( pdev->dev.device_state == USB_OTG_EP0_DATA_OUT) + { + if(ep->rem_data_len > ep->maxpacket) + { + ep->rem_data_len -= ep->maxpacket; + + if(pdev->cfg.dma_enable == 1) + { + /* in slave mode this, is handled by the RxSTSQLvl ISR */ + ep->xfer_buff += ep->maxpacket; + } + USBD_CtlContinueRx (pdev, + ep->xfer_buff, + MIN(ep->rem_data_len ,ep->maxpacket)); + } + else + { + if((pdev->dev.class_cb->EP0_RxReady != NULL)&& + (pdev->dev.device_status == USB_OTG_CONFIGURED)) + { + pdev->dev.class_cb->EP0_RxReady(pdev); + } + USBD_CtlSendStatus(pdev); + } + } + } + else if((pdev->dev.class_cb->DataOut != NULL)&& + (pdev->dev.device_status == USB_OTG_CONFIGURED)) + { + pdev->dev.class_cb->DataOut(pdev, epnum); + } + return USBD_OK; +} + +/** +* @brief USBD_DataInStage +* Handle data in stage +* @param pdev: device instance +* @param epnum: endpoint index +* @retval status +*/ +static uint8_t USBD_DataInStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum) +{ + USB_OTG_EP *ep; + + if(epnum == 0) + { + ep = &pdev->dev.in_ep[0]; + if ( pdev->dev.device_state == USB_OTG_EP0_DATA_IN) + { + if(ep->rem_data_len > ep->maxpacket) + { + ep->rem_data_len -= ep->maxpacket; + if(pdev->cfg.dma_enable == 1) + { + /* in slave mode this, is handled by the TxFifoEmpty ISR */ + ep->xfer_buff += ep->maxpacket; + } + USBD_CtlContinueSendData (pdev, + ep->xfer_buff, + ep->rem_data_len); + } + else + { /* last packet is MPS multiple, so send ZLP packet */ + if((ep->total_data_len % ep->maxpacket == 0) && + (ep->total_data_len >= ep->maxpacket) && + (ep->total_data_len < ep->ctl_data_len )) + { + + USBD_CtlContinueSendData(pdev , NULL, 0); + ep->ctl_data_len = 0; + } + else + { + if((pdev->dev.class_cb->EP0_TxSent != NULL)&& + (pdev->dev.device_status == USB_OTG_CONFIGURED)) + { + pdev->dev.class_cb->EP0_TxSent(pdev); + } + USBD_CtlReceiveStatus(pdev); + } + } + } + } + else if((pdev->dev.class_cb->DataIn != NULL)&& + (pdev->dev.device_status == USB_OTG_CONFIGURED)) + { + pdev->dev.class_cb->DataIn(pdev, epnum); + } + return USBD_OK; +} + +/** +* @brief USBD_Reset +* Handle Reset event +* @param pdev: device instance +* @retval status +*/ + +static uint8_t USBD_Reset(USB_OTG_CORE_HANDLE *pdev) +{ + /* Open EP0 OUT */ + DCD_EP_Open(pdev, + 0x00, + USB_OTG_MAX_EP0_SIZE, + EP_TYPE_CTRL); + + /* Open EP0 IN */ + DCD_EP_Open(pdev, + 0x80, + USB_OTG_MAX_EP0_SIZE, + EP_TYPE_CTRL); + + /* Upon Reset call usr call back */ + pdev->dev.device_status = USB_OTG_DEFAULT; + pdev->dev.usr_cb->DeviceReset(pdev->cfg.speed); + + return USBD_OK; +} + +/** +* @brief USBD_Resume +* Handle Resume event +* @param pdev: device instance +* @retval status +*/ + +static uint8_t USBD_Resume(USB_OTG_CORE_HANDLE *pdev) +{ + /* Upon Resume call usr call back */ + pdev->dev.usr_cb->DeviceResumed(); + pdev->dev.device_status = USB_OTG_CONFIGURED; + return USBD_OK; +} + + +/** +* @brief USBD_Suspend +* Handle Suspend event +* @param pdev: device instance +* @retval status +*/ + +static uint8_t USBD_Suspend(USB_OTG_CORE_HANDLE *pdev) +{ + + pdev->dev.device_status = USB_OTG_SUSPENDED; + /* Upon Resume call usr call back */ + pdev->dev.usr_cb->DeviceSuspended(); + return USBD_OK; +} + + +/** +* @brief USBD_SOF +* Handle SOF event +* @param pdev: device instance +* @retval status +*/ + +static uint8_t USBD_SOF(USB_OTG_CORE_HANDLE *pdev) +{ + if(pdev->dev.class_cb->SOF) + { + pdev->dev.class_cb->SOF(pdev); + } + return USBD_OK; +} +/** +* @brief USBD_SetCfg +* Configure device and start the interface +* @param pdev: device instance +* @param cfgidx: configuration index +* @retval status +*/ + +USBD_Status USBD_SetCfg(USB_OTG_CORE_HANDLE *pdev, uint8_t cfgidx) +{ + pdev->dev.class_cb->Init(pdev, cfgidx); + + /* Upon set config call usr call back */ + pdev->dev.usr_cb->DeviceConfigured(); + return USBD_OK; +} + +/** +* @brief USBD_ClrCfg +* Clear current configuration +* @param pdev: device instance +* @param cfgidx: configuration index +* @retval status: USBD_Status +*/ +USBD_Status USBD_ClrCfg(USB_OTG_CORE_HANDLE *pdev, uint8_t cfgidx) +{ + pdev->dev.class_cb->DeInit(pdev, cfgidx); + return USBD_OK; +} + +/** +* @brief USBD_IsoINIncomplete +* Handle iso in incomplete event +* @param pdev: device instance +* @retval status +*/ +static uint8_t USBD_IsoINIncomplete(USB_OTG_CORE_HANDLE *pdev) +{ + pdev->dev.class_cb->IsoINIncomplete(pdev); + return USBD_OK; +} + +/** +* @brief USBD_IsoOUTIncomplete +* Handle iso out incomplete event +* @param pdev: device instance +* @retval status +*/ +static uint8_t USBD_IsoOUTIncomplete(USB_OTG_CORE_HANDLE *pdev) +{ + pdev->dev.class_cb->IsoOUTIncomplete(pdev); + return USBD_OK; +} + +#ifdef VBUS_SENSING_ENABLED +/** +* @brief USBD_DevConnected +* Handle device connection event +* @param pdev: device instance +* @retval status +*/ +static uint8_t USBD_DevConnected(USB_OTG_CORE_HANDLE *pdev) +{ + pdev->dev.usr_cb->DeviceConnected(); + return USBD_OK; +} + +/** +* @brief USBD_DevDisconnected +* Handle device disconnection event +* @param pdev: device instance +* @retval status +*/ +static uint8_t USBD_DevDisconnected(USB_OTG_CORE_HANDLE *pdev) +{ + pdev->dev.usr_cb->DeviceDisconnected(); + pdev->dev.class_cb->DeInit(pdev, 0); + return USBD_OK; +} +#endif +/** +* @} +*/ + + +/** +* @} +*/ + + +/** +* @} +*/ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/src/usbd_ioreq.c b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/src/usbd_ioreq.c new file mode 100644 index 000000000..b8204f844 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/src/usbd_ioreq.c @@ -0,0 +1,237 @@ +/** + ****************************************************************************** + * @file usbd_ioreq.c + * @author MCD Application Team + * @version V1.0.0 + * @date 22-July-2011 + * @brief This file provides the IO requests APIs for control endpoints. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usbd_ioreq.h" +/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY + * @{ + */ + + +/** @defgroup USBD_IOREQ + * @brief control I/O requests module + * @{ + */ + +/** @defgroup USBD_IOREQ_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + + +/** @defgroup USBD_IOREQ_Private_Defines + * @{ + */ + +/** + * @} + */ + + +/** @defgroup USBD_IOREQ_Private_Macros + * @{ + */ +/** + * @} + */ + + +/** @defgroup USBD_IOREQ_Private_Variables + * @{ + */ + +/** + * @} + */ + + +/** @defgroup USBD_IOREQ_Private_FunctionPrototypes + * @{ + */ +/** + * @} + */ + + +/** @defgroup USBD_IOREQ_Private_Functions + * @{ + */ + +/** +* @brief USBD_CtlSendData +* send data on the ctl pipe +* @param pdev: device instance +* @param buff: pointer to data buffer +* @param len: length of data to be sent +* @retval status +*/ +USBD_Status USBD_CtlSendData (USB_OTG_CORE_HANDLE *pdev, + const uint8_t *pbuf, + uint16_t len) +{ + USBD_Status ret = USBD_OK; + + pdev->dev.in_ep[0].total_data_len = len; + pdev->dev.in_ep[0].rem_data_len = len; + pdev->dev.device_state = USB_OTG_EP0_DATA_IN; + + DCD_EP_Tx (pdev, 0, pbuf, len); + + return ret; +} + +/** +* @brief USBD_CtlContinueSendData +* continue sending data on the ctl pipe +* @param pdev: device instance +* @param buff: pointer to data buffer +* @param len: length of data to be sent +* @retval status +*/ +USBD_Status USBD_CtlContinueSendData (USB_OTG_CORE_HANDLE *pdev, + uint8_t *pbuf, + uint16_t len) +{ + USBD_Status ret = USBD_OK; + + DCD_EP_Tx (pdev, 0, pbuf, len); + + + return ret; +} + +/** +* @brief USBD_CtlPrepareRx +* receive data on the ctl pipe +* @param pdev: USB OTG device instance +* @param buff: pointer to data buffer +* @param len: length of data to be received +* @retval status +*/ +USBD_Status USBD_CtlPrepareRx (USB_OTG_CORE_HANDLE *pdev, + uint8_t *pbuf, + uint16_t len) +{ + USBD_Status ret = USBD_OK; + + pdev->dev.out_ep[0].total_data_len = len; + pdev->dev.out_ep[0].rem_data_len = len; + pdev->dev.device_state = USB_OTG_EP0_DATA_OUT; + + DCD_EP_PrepareRx (pdev, + 0, + pbuf, + len); + + + return ret; +} + +/** +* @brief USBD_CtlContinueRx +* continue receive data on the ctl pipe +* @param pdev: USB OTG device instance +* @param buff: pointer to data buffer +* @param len: length of data to be received +* @retval status +*/ +USBD_Status USBD_CtlContinueRx (USB_OTG_CORE_HANDLE *pdev, + uint8_t *pbuf, + uint16_t len) +{ + USBD_Status ret = USBD_OK; + + DCD_EP_PrepareRx (pdev, + 0, + pbuf, + len); + return ret; +} +/** +* @brief USBD_CtlSendStatus +* send zero lzngth packet on the ctl pipe +* @param pdev: USB OTG device instance +* @retval status +*/ +USBD_Status USBD_CtlSendStatus (USB_OTG_CORE_HANDLE *pdev) +{ + USBD_Status ret = USBD_OK; + pdev->dev.device_state = USB_OTG_EP0_STATUS_IN; + DCD_EP_Tx (pdev, + 0, + NULL, + 0); + + USB_OTG_EP0_OutStart(pdev); + + return ret; +} + +/** +* @brief USBD_CtlReceiveStatus +* receive zero lzngth packet on the ctl pipe +* @param pdev: USB OTG device instance +* @retval status +*/ +USBD_Status USBD_CtlReceiveStatus (USB_OTG_CORE_HANDLE *pdev) +{ + USBD_Status ret = USBD_OK; + pdev->dev.device_state = USB_OTG_EP0_STATUS_OUT; + DCD_EP_PrepareRx ( pdev, + 0, + NULL, + 0); + + USB_OTG_EP0_OutStart(pdev); + + return ret; +} + + +/** +* @brief USBD_GetRxCount +* returns the received data length +* @param pdev: USB OTG device instance +* epnum: endpoint index +* @retval Rx Data blength +*/ +uint16_t USBD_GetRxCount (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum) +{ + return pdev->dev.out_ep[epnum].xfer_count; +} + +/** + * @} + */ + + +/** + * @} + */ + + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/src/usbd_req.c b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/src/usbd_req.c new file mode 100644 index 000000000..92e468d00 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Core/src/usbd_req.c @@ -0,0 +1,867 @@ +/** + ****************************************************************************** + * @file usbd_req.c + * @author MCD Application Team + * @version V1.0.0 + * @date 22-July-2011 + * @brief This file provides the standard USB requests following chapter 9. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usbd_req.h" +#include "usbd_ioreq.h" +#include "usbd_desc.h" + + +/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY + * @{ + */ + + +/** @defgroup USBD_REQ + * @brief USB standard requests module + * @{ + */ + +/** @defgroup USBD_REQ_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + + +/** @defgroup USBD_REQ_Private_Defines + * @{ + */ + +/** + * @} + */ + + +/** @defgroup USBD_REQ_Private_Macros + * @{ + */ +/** + * @} + */ + + +/** @defgroup USBD_REQ_Private_Variables + * @{ + */ + +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED + #if defined ( __ICCARM__ ) /*!< IAR Compiler */ + #pragma data_alignment=4 + #endif +#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ +__ALIGN_BEGIN uint32_t USBD_ep_status __ALIGN_END = 0; + +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED + #if defined ( __ICCARM__ ) /*!< IAR Compiler */ + #pragma data_alignment=4 + #endif +#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ +__ALIGN_BEGIN uint32_t USBD_default_cfg __ALIGN_END = 0; + +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED + #if defined ( __ICCARM__ ) /*!< IAR Compiler */ + #pragma data_alignment=4 + #endif +#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ +__ALIGN_BEGIN uint32_t USBD_cfg_status __ALIGN_END = 0; + +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED + #if defined ( __ICCARM__ ) /*!< IAR Compiler */ + #pragma data_alignment=4 + #endif +#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ +__ALIGN_BEGIN uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ] __ALIGN_END ; +/** + * @} + */ + + +/** @defgroup USBD_REQ_Private_FunctionPrototypes + * @{ + */ +static void USBD_GetDescriptor(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req); + +static void USBD_SetAddress(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req); + +static void USBD_SetConfig(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req); + +static void USBD_GetConfig(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req); + +static void USBD_GetStatus(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req); + +static void USBD_SetFeature(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req); + +static void USBD_ClrFeature(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req); + +static uint8_t USBD_GetLen(uint8_t *buf); +/** + * @} + */ + + +/** @defgroup USBD_REQ_Private_Functions + * @{ + */ + + +/** +* @brief USBD_StdDevReq +* Handle standard usb device requests +* @param pdev: device instance +* @param req: usb request +* @retval status +*/ +USBD_Status USBD_StdDevReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req) +{ + USBD_Status ret = USBD_OK; + + switch (req->bRequest) + { + case USB_REQ_GET_DESCRIPTOR: + + USBD_GetDescriptor (pdev, req) ; + break; + + case USB_REQ_SET_ADDRESS: + USBD_SetAddress(pdev, req); + break; + + case USB_REQ_SET_CONFIGURATION: + USBD_SetConfig (pdev , req); + break; + + case USB_REQ_GET_CONFIGURATION: + USBD_GetConfig (pdev , req); + break; + + case USB_REQ_GET_STATUS: + USBD_GetStatus (pdev , req); + break; + + + case USB_REQ_SET_FEATURE: + USBD_SetFeature (pdev , req); + break; + + case USB_REQ_CLEAR_FEATURE: + USBD_ClrFeature (pdev , req); + break; + + default: + USBD_CtlError(pdev , req); + break; + } + + return ret; +} + +/** +* @brief USBD_StdItfReq +* Handle standard usb interface requests +* @param pdev: USB OTG device instance +* @param req: usb request +* @retval status +*/ +USBD_Status USBD_StdItfReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req) +{ + USBD_Status ret = USBD_OK; + + switch (pdev->dev.device_status) + { + case USB_OTG_CONFIGURED: + + if (LOBYTE(req->wIndex) <= USBD_ITF_MAX_NUM) + { + pdev->dev.class_cb->Setup (pdev, req); + + if((req->wLength == 0)&& (ret == USBD_OK)) + { + USBD_CtlSendStatus(pdev); + } + } + else + { + USBD_CtlError(pdev , req); + } + break; + + default: + USBD_CtlError(pdev , req); + break; + } + return ret; +} + +/** +* @brief USBD_StdEPReq +* Handle standard usb endpoint requests +* @param pdev: USB OTG device instance +* @param req: usb request +* @retval status +*/ +USBD_Status USBD_StdEPReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req) +{ + + uint8_t ep_addr; + USBD_Status ret = USBD_OK; + + ep_addr = LOBYTE(req->wIndex); + + switch (req->bRequest) + { + + case USB_REQ_SET_FEATURE : + + switch (pdev->dev.device_status) + { + case USB_OTG_ADDRESSED: + if ((ep_addr != 0x00) && (ep_addr != 0x80)) + { + DCD_EP_Stall(pdev , ep_addr); + } + break; + + case USB_OTG_CONFIGURED: + if (req->wValue == USB_FEATURE_EP_HALT) + { + if ((ep_addr != 0x00) && (ep_addr != 0x80)) + { + DCD_EP_Stall(pdev , ep_addr); + + } + } + pdev->dev.class_cb->Setup (pdev, req); + USBD_CtlSendStatus(pdev); + + break; + + default: + USBD_CtlError(pdev , req); + break; + } + break; + + case USB_REQ_CLEAR_FEATURE : + + switch (pdev->dev.device_status) + { + case USB_OTG_ADDRESSED: + if ((ep_addr != 0x00) && (ep_addr != 0x80)) + { + DCD_EP_Stall(pdev , ep_addr); + } + break; + + case USB_OTG_CONFIGURED: + if (req->wValue == USB_FEATURE_EP_HALT) + { + if ((ep_addr != 0x00) && (ep_addr != 0x80)) + { + DCD_EP_ClrStall(pdev , ep_addr); + pdev->dev.class_cb->Setup (pdev, req); + } + USBD_CtlSendStatus(pdev); + } + break; + + default: + USBD_CtlError(pdev , req); + break; + } + break; + + case USB_REQ_GET_STATUS: + switch (pdev->dev.device_status) + { + case USB_OTG_ADDRESSED: + if ((ep_addr != 0x00) && (ep_addr != 0x80)) + { + DCD_EP_Stall(pdev , ep_addr); + } + break; + + case USB_OTG_CONFIGURED: + + + if ((ep_addr & 0x80)== 0x80) + { + if(pdev->dev.in_ep[ep_addr & 0x7F].is_stall) + { + USBD_ep_status = 0x0001; + } + else + { + USBD_ep_status = 0x0000; + } + } + else if ((ep_addr & 0x80)== 0x00) + { + if(pdev->dev.out_ep[ep_addr].is_stall) + { + USBD_ep_status = 0x0001; + } + + else + { + USBD_ep_status = 0x0000; + } + } + USBD_CtlSendData (pdev, + (uint8_t *)&USBD_ep_status, + 2); + break; + + default: + USBD_CtlError(pdev , req); + break; + } + break; + + default: + break; + } + return ret; +} +/** +* @brief USBD_GetDescriptor +* Handle Get Descriptor requests +* @param pdev: device instance +* @param req: usb request +* @retval status +*/ +static void USBD_GetDescriptor(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req) +{ + uint16_t len; + const uint8_t * pbuf; + + switch (req->wValue >> 8) + { + case USB_DESC_TYPE_DEVICE: + pbuf = pdev->dev.usr_device->GetDeviceDescriptor(pdev->cfg.speed, &len); + if ((req->wLength == 64) ||( pdev->dev.device_status == USB_OTG_DEFAULT)) + { + len = 8; + } + break; + + case USB_DESC_TYPE_CONFIGURATION: + pbuf = (uint8_t *)pdev->dev.class_cb->GetConfigDescriptor(pdev->cfg.speed, &len); +#ifdef USB_OTG_HS_CORE + if((pdev->cfg.speed == USB_OTG_SPEED_FULL )&& + (pdev->cfg.phy_itface == USB_OTG_ULPI_PHY)) + { + pbuf = (uint8_t *)pdev->dev.class_cb->GetOtherConfigDescriptor(pdev->cfg.speed, &len); + } +#endif + pdev->dev.pConfig_descriptor = pbuf; + break; + + case USB_DESC_TYPE_STRING: + switch ((uint8_t)(req->wValue)) + { + case USBD_IDX_LANGID_STR: + pbuf = pdev->dev.usr_device->GetLangIDStrDescriptor(pdev->cfg.speed, &len); + break; + + case USBD_IDX_MFC_STR: + pbuf = pdev->dev.usr_device->GetManufacturerStrDescriptor(pdev->cfg.speed, &len); + break; + + case USBD_IDX_PRODUCT_STR: + pbuf = pdev->dev.usr_device->GetProductStrDescriptor(pdev->cfg.speed, &len); + break; + + case USBD_IDX_SERIAL_STR: + pbuf = pdev->dev.usr_device->GetSerialStrDescriptor(pdev->cfg.speed, &len); + break; + + case USBD_IDX_CONFIG_STR: + pbuf = pdev->dev.usr_device->GetConfigurationStrDescriptor(pdev->cfg.speed, &len); + break; + + case USBD_IDX_INTERFACE_STR: + pbuf = pdev->dev.usr_device->GetInterfaceStrDescriptor(pdev->cfg.speed, &len); + break; + + default: +#ifdef USB_SUPPORT_USER_STRING_DESC + pbuf = pdev->dev.class_cb->GetUsrStrDescriptor(pdev->cfg.speed, (req->wValue) , &len); + break; +#else + USBD_CtlError(pdev , req); + return; +#endif /* USBD_CtlError(pdev , req); */ + } + break; + case USB_DESC_TYPE_DEVICE_QUALIFIER: +#ifdef USB_OTG_HS_CORE + if(pdev->cfg.speed == USB_OTG_SPEED_HIGH ) + { + + pbuf = (uint8_t *)pdev->dev.class_cb->GetConfigDescriptor(pdev->cfg.speed, &len); + + USBD_DeviceQualifierDesc[4]= pbuf[14]; + USBD_DeviceQualifierDesc[5]= pbuf[15]; + USBD_DeviceQualifierDesc[6]= pbuf[16]; + + pbuf = USBD_DeviceQualifierDesc; + len = USB_LEN_DEV_QUALIFIER_DESC; + break; + } + else + { + USBD_CtlError(pdev , req); + return; + } +#else + USBD_CtlError(pdev , req); + return; +#endif + + case USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION: +#ifdef USB_OTG_HS_CORE + + if(pdev->cfg.speed == USB_OTG_SPEED_HIGH ) + { + pbuf = (uint8_t *)pdev->dev.class_cb->GetOtherConfigDescriptor(pdev->cfg.speed, &len); + pbuf[1] = USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION; + break; + } + else + { + USBD_CtlError(pdev , req); + return; + } +#else + USBD_CtlError(pdev , req); + return; +#endif + + + default: + USBD_CtlError(pdev , req); + return; + } + + if((len != 0)&& (req->wLength != 0)) + { + + len = MIN(len , req->wLength); + + USBD_CtlSendData (pdev, + pbuf, + len); + } + +} + +/** +* @brief USBD_SetAddress +* Set device address +* @param pdev: device instance +* @param req: usb request +* @retval status +*/ +static void USBD_SetAddress(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req) +{ + uint8_t dev_addr; + + if ((req->wIndex == 0) && (req->wLength == 0)) + { + dev_addr = (uint8_t)(req->wValue) & 0x7F; + + if (pdev->dev.device_status == USB_OTG_CONFIGURED) + { + USBD_CtlError(pdev , req); + } + else + { + pdev->dev.device_address = dev_addr; + DCD_EP_SetAddress(pdev, dev_addr); + USBD_CtlSendStatus(pdev); + + if (dev_addr != 0) + { + pdev->dev.device_status = USB_OTG_ADDRESSED; + } + else + { + pdev->dev.device_status = USB_OTG_DEFAULT; + } + } + } + else + { + USBD_CtlError(pdev , req); + } +} + +/** +* @brief USBD_SetConfig +* Handle Set device configuration request +* @param pdev: device instance +* @param req: usb request +* @retval status +*/ +static void USBD_SetConfig(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req) +{ + + static uint8_t cfgidx; + + cfgidx = (uint8_t)(req->wValue); + + if (cfgidx > USBD_CFG_MAX_NUM ) + { + USBD_CtlError(pdev , req); + } + else + { + switch (pdev->dev.device_status) + { + case USB_OTG_ADDRESSED: + if (cfgidx) + { + pdev->dev.device_config = cfgidx; + pdev->dev.device_status = USB_OTG_CONFIGURED; + USBD_SetCfg(pdev , cfgidx); + USBD_CtlSendStatus(pdev); + } + else + { + USBD_CtlSendStatus(pdev); + } + break; + + case USB_OTG_CONFIGURED: + if (cfgidx == 0) + { + pdev->dev.device_status = USB_OTG_ADDRESSED; + pdev->dev.device_config = cfgidx; + USBD_ClrCfg(pdev , cfgidx); + USBD_CtlSendStatus(pdev); + + } + else if (cfgidx != pdev->dev.device_config) + { + /* Clear old configuration */ + USBD_ClrCfg(pdev , pdev->dev.device_config); + + /* set new configuration */ + pdev->dev.device_config = cfgidx; + USBD_SetCfg(pdev , cfgidx); + USBD_CtlSendStatus(pdev); + } + else + { + USBD_CtlSendStatus(pdev); + } + break; + + default: + USBD_CtlError(pdev , req); + break; + } + } +} + +/** +* @brief USBD_GetConfig +* Handle Get device configuration request +* @param pdev: device instance +* @param req: usb request +* @retval status +*/ +static void USBD_GetConfig(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req) +{ + + if (req->wLength != 1) + { + USBD_CtlError(pdev , req); + } + else + { + switch (pdev->dev.device_status ) + { + case USB_OTG_ADDRESSED: + + USBD_CtlSendData (pdev, + (uint8_t *)&USBD_default_cfg, + 1); + break; + + case USB_OTG_CONFIGURED: + + USBD_CtlSendData (pdev, + &pdev->dev.device_config, + 1); + break; + + default: + USBD_CtlError(pdev , req); + break; + } + } +} + +/** +* @brief USBD_GetStatus +* Handle Get Status request +* @param pdev: device instance +* @param req: usb request +* @retval status +*/ +static void USBD_GetStatus(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req) +{ + + switch (pdev->dev.device_status) + { + case USB_OTG_ADDRESSED: + case USB_OTG_CONFIGURED: + + if (pdev->dev.DevRemoteWakeup) + { + USBD_cfg_status = USB_CONFIG_SELF_POWERED | USB_CONFIG_REMOTE_WAKEUP; + } + else + { + USBD_cfg_status = USB_CONFIG_SELF_POWERED; + } + + USBD_CtlSendData (pdev, + (uint8_t *)&USBD_cfg_status, + 1); + break; + + default : + USBD_CtlError(pdev , req); + break; + } +} + + +/** +* @brief USBD_SetFeature +* Handle Set device feature request +* @param pdev: device instance +* @param req: usb request +* @retval status +*/ +static void USBD_SetFeature(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req) +{ + + USB_OTG_DCTL_TypeDef dctl; + uint8_t test_mode = 0; + + if (req->wValue == USB_FEATURE_REMOTE_WAKEUP) + { + pdev->dev.DevRemoteWakeup = 1; + pdev->dev.class_cb->Setup (pdev, req); + USBD_CtlSendStatus(pdev); + } + + else if ((req->wValue == USB_FEATURE_TEST_MODE) && + ((req->wIndex & 0xFF) == 0)) + { + dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL); + + test_mode = req->wIndex >> 8; + switch (test_mode) + { + case 1: // TEST_J + dctl.b.tstctl = 1; + break; + + case 2: // TEST_K + dctl.b.tstctl = 2; + break; + + case 3: // TEST_SE0_NAK + dctl.b.tstctl = 3; + break; + + case 4: // TEST_PACKET + dctl.b.tstctl = 4; + break; + + case 5: // TEST_FORCE_ENABLE + dctl.b.tstctl = 5; + break; + } + USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32); + USBD_CtlSendStatus(pdev); + } + +} + + +/** +* @brief USBD_ClrFeature +* Handle clear device feature request +* @param pdev: device instance +* @param req: usb request +* @retval status +*/ +static void USBD_ClrFeature(USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req) +{ + switch (pdev->dev.device_status) + { + case USB_OTG_ADDRESSED: + case USB_OTG_CONFIGURED: + if (req->wValue == USB_FEATURE_REMOTE_WAKEUP) + { + pdev->dev.DevRemoteWakeup = 0; + pdev->dev.class_cb->Setup (pdev, req); + USBD_CtlSendStatus(pdev); + } + break; + + default : + USBD_CtlError(pdev , req); + break; + } +} + +/** +* @brief USBD_ParseSetupRequest +* Copy buffer into setup structure +* @param pdev: device instance +* @param req: usb request +* @retval None +*/ + +void USBD_ParseSetupRequest( USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req) +{ + req->bmRequest = *(uint8_t *) (pdev->dev.setup_packet); + req->bRequest = *(uint8_t *) (pdev->dev.setup_packet + 1); + req->wValue = SWAPBYTE (pdev->dev.setup_packet + 2); + req->wIndex = SWAPBYTE (pdev->dev.setup_packet + 4); + req->wLength = SWAPBYTE (pdev->dev.setup_packet + 6); + + pdev->dev.in_ep[0].ctl_data_len = req->wLength ; + pdev->dev.device_state = USB_OTG_EP0_SETUP; +} + +/** +* @brief USBD_CtlError +* Handle USB low level Error +* @param pdev: device instance +* @param req: usb request +* @retval None +*/ + +void USBD_CtlError( USB_OTG_CORE_HANDLE *pdev, + USB_SETUP_REQ *req) +{ + if((req->bmRequest & 0x80) == 0x80) + { + DCD_EP_Stall(pdev , 0x80); + } + else + { + if(req->wLength == 0) + { + DCD_EP_Stall(pdev , 0x80); + } + else + { + DCD_EP_Stall(pdev , 0); + } + } + USB_OTG_EP0_OutStart(pdev); +} + + +/** + * @brief USBD_GetString + * Convert Ascii string into unicode one + * @param desc : descriptor buffer + * @param unicode : Formatted string buffer (unicode) + * @param len : descriptor length + * @retval None + */ +void USBD_GetString(uint8_t *desc, uint8_t *unicode, uint16_t *len) +{ + uint8_t idx = 0; + + if (desc != NULL) + { + *len = USBD_GetLen(desc) * 2 + 2; + unicode[idx++] = *len; + unicode[idx++] = USB_DESC_TYPE_STRING; + + while (*desc != NULL) + { + unicode[idx++] = *desc++; + unicode[idx++] = 0x00; + } + } +} + +/** + * @brief USBD_GetLen + * return the string length + * @param buf : pointer to the ascii string buffer + * @retval string length + */ +static uint8_t USBD_GetLen(uint8_t *buf) +{ + uint8_t len = 0; + + while (*buf != NULL) + { + len++; + buf++; + } + + return len; +} +/** + * @} + */ + + +/** + * @} + */ + + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Release_Notes.html b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Release_Notes.html new file mode 100644 index 000000000..ecb499875 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_Device_Library/Release_Notes.html @@ -0,0 +1,941 @@ + + + + + + + + +Release Notes for STM32F105/7xx and STM32F2xx USB Device Library + + + + + +
+ +

 

+ +
+ + + + + +
+ + + + + + + +
+

Back to Release page

+
+

Release Notes for STM32F105/7xx and STM32F2xx USB Device Library

+

Copyright + 2011 STMicroelectronics

+

+
+

 

+ + + + +
+

Contents

+
    +
  1. STM32F105/7xx and STM32F2xx USB Device Library update History
  2. +
  3. License
  4. +
+

STM32F105/7xx and STM32F2xx USB Device Library  update History

V1.0.0 / 22-July-2011

Main +Changes

+
  • First official version for STM32F105/7xx and STM32F2xx devices

+

License

+

The use of this STM32 software is governed by the terms and conditions of the License Agreement "MCD-ST Liberty SW License Agreement 20Jul2011 v0.1.pdf" available in the root of this package. 

+
+
+
+

For + complete documentation on STM32(CORTEX M3) 32-Bit + Microcontrollers visit www.st.com/STM32

+
+

+
+ +
+ +

 

+ +
+ + \ No newline at end of file diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/Release_Notes.html b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/Release_Notes.html new file mode 100644 index 000000000..17d2a0832 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/Release_Notes.html @@ -0,0 +1,941 @@ + + + + + + + + +Release Notes for STM32F105/7xx and STM32F2xx USB OTG Driver + + + + + +
+ +

 

+ +
+ + + + + +
+ + + + + + + +
+

Back to Release page

+
+

Release Notes for STM32F105/7xx and STM32F2xx USB OTG Driver

+

Copyright + 2011 STMicroelectronics

+

+
+

 

+ + + + +
+

Contents

+
    +
  1. STM32F105/7xx and STM32F2xx USB OTG Driver update History
  2. +
  3. License
  4. +
+

STM32F105/7xx and STM32F2xx USB OTG Driver  update History

V2.0.0 / 22-July-2011

Main +Changes

+
  • Second official version supporting STM32F105/7 and STM32F2xx devices
  • Rename the Library from "STM32_USB_HOST_Driver" to "STM32_USB_OTG_Driver"
  • Add support for STM32F2xx devices
  • Add support for Device and OTG modes
  • Change HCD layer to support High speed core
  • Change the Low level driver to support multi core support for Host mode
  • Add Stop mechanism for Host and Device modes
  • Change VBUS enabling method, to use the external or the internal VBUS when using the ULPI

V1.0.0 - 11/29/2010

+
  • Created 

License

+

The use of this STM32 software is governed by the terms and conditions of the License Agreement "MCD-ST Liberty SW License Agreement 20Jul2011 v0.1.pdf" available in the root of this package. 

+
+
+
+

For + complete documentation on STM32(CORTEX M3) 32-Bit + Microcontrollers visit www.st.com/STM32

+
+

+
+ +
+ +

 

+ +
+ + \ No newline at end of file diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_bsp.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_bsp.h new file mode 100644 index 000000000..37a1344dc --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_bsp.h @@ -0,0 +1,96 @@ +/** + ****************************************************************************** + * @file usb_bsp.h + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Specific api's relative to the used hardware platform + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_BSP__H__ +#define __USB_BSP__H__ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_core.h" + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_BSP + * @brief This file is the + * @{ + */ + + +/** @defgroup USB_BSP_Exported_Defines + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_BSP_Exported_Types + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_BSP_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_BSP_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_BSP_Exported_FunctionsPrototype + * @{ + */ +void BSP_Init(void); + +void USB_OTG_BSP_Init (USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_BSP_uDelay (const uint32_t usec); +void USB_OTG_BSP_mDelay (const uint32_t msec); +void USB_OTG_BSP_EnableInterrupt (USB_OTG_CORE_HANDLE *pdev); +#ifdef USE_HOST_MODE +void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state); +#endif +/** + * @} + */ + +#endif //__USB_BSP__H__ + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_conf.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_conf.h new file mode 100644 index 000000000..b479677c3 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_conf.h @@ -0,0 +1,287 @@ +/** + ****************************************************************************** + * @file usb_conf.h + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief general low level driver configuration + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_CONF__H__ +#define __USB_CONF__H__ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx.h" + + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_CONF + * @brief USB low level driver configuration file + * @{ + */ + +/** @defgroup USB_CONF_Exported_Defines + * @{ + */ + +/* USB Core and PHY interface configuration. + Tip: To avoid modifying these defines each time you need to change the USB + configuration, you can declare the needed define in your toolchain + compiler preprocessor. + */ +#ifndef USE_USB_OTG_FS + #define USE_USB_OTG_FS +#endif /* USE_USB_OTG_FS */ + +#ifndef USE_USB_OTG_HS + //#define USE_USB_OTG_HS +#endif /* USE_USB_OTG_HS */ + +#ifndef USE_ULPI_PHY + //#define USE_ULPI_PHY +#endif /* USE_ULPI_PHY */ + +#ifndef USE_EMBEDDED_PHY + #define USE_EMBEDDED_PHY +#endif /* USE_EMBEDDED_PHY */ + +#ifndef USE_I2C_PHY + //#define USE_I2C_PHY +#endif /* USE_I2C_PHY */ + + +#ifdef USE_USB_OTG_FS + #define USB_OTG_FS_CORE +#endif + +#ifdef USE_USB_OTG_HS + #define USB_OTG_HS_CORE +#endif + +/******************************************************************************* +* FIFO Size Configuration in Device mode +* +* (i) Receive data FIFO size = RAM for setup packets + +* OUT endpoint control information + +* data OUT packets + miscellaneous +* Space = ONE 32-bits words +* --> RAM for setup packets = 10 spaces +* (n is the nbr of CTRL EPs the device core supports) +* --> OUT EP CTRL info = 1 space +* (one space for status information written to the FIFO along with each +* received packet) +* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces +* (MINIMUM to receive packets) +* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces +* (if high-bandwidth EP is enabled or multiple isochronous EPs) +* --> miscellaneous = 1 space per OUT EP +* (one space for transfer complete status information also pushed to the +* FIFO with each endpoint's last packet) +* +* (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for +* that particular IN EP. More space allocated in the IN EP Tx FIFO results +* in a better performance on the USB and can hide latencies on the AHB. +* +* (iii) TXn min size = 16 words. (n : Transmit FIFO index) +* (iv) When a TxFIFO is not used, the Configuration should be as follows: +* case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes) +* --> Txm can use the space allocated for Txn. +* case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes) +* --> Txn should be configured with the minimum space of 16 words +* (v) The FIFO is used optimally when used TxFIFOs are allocated in the top +* of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones. +*******************************************************************************/ + +/******************************************************************************* +* FIFO Size Configuration in Host mode +* +* (i) Receive data FIFO size = (Largest Packet Size / 4) + 1 or +* 2x (Largest Packet Size / 4) + 1, If a +* high-bandwidth channel or multiple isochronous +* channels are enabled +* +* (ii) For the host nonperiodic Transmit FIFO is the largest maximum packet size +* for all supported nonperiodic OUT channels. Typically, a space +* corresponding to two Largest Packet Size is recommended. +* +* (iii) The minimum amount of RAM required for Host periodic Transmit FIFO is +* the largest maximum packet size for all supported periodic OUT channels. +* If there is at least one High Bandwidth Isochronous OUT endpoint, +* then the space must be at least two times the maximum packet size for +* that channel. +*******************************************************************************/ + +/****************** USB OTG HS CONFIGURATION **********************************/ +#ifdef USB_OTG_HS_CORE + #define RX_FIFO_HS_SIZE 512 + #define TX0_FIFO_HS_SIZE 512 + #define TX1_FIFO_HS_SIZE 512 + #define TX2_FIFO_HS_SIZE 0 + #define TX3_FIFO_HS_SIZE 0 + #define TX4_FIFO_HS_SIZE 0 + #define TX5_FIFO_HS_SIZE 0 + #define TXH_NP_HS_FIFOSIZ 96 + #define TXH_P_HS_FIFOSIZ 96 + + //#define USB_OTG_HS_LOW_PWR_MGMT_SUPPORT + //#define USB_OTG_HS_SOF_OUTPUT_ENABLED + + //#define USB_OTG_INTERNAL_VBUS_ENABLED + #define USB_OTG_EXTERNAL_VBUS_ENABLED + + #ifdef USE_ULPI_PHY + #define USB_OTG_ULPI_PHY_ENABLED + #endif + #ifdef USE_EMBEDDED_PHY + #define USB_OTG_EMBEDDED_PHY_ENABLED + #endif + #ifdef USE_I2C_PHY + #define USB_OTG_I2C_PHY_ENABLED + #endif + #define USB_OTG_HS_INTERNAL_DMA_ENABLED + #define USB_OTG_HS_DEDICATED_EP1_ENABLED +#endif + +/****************** USB OTG FS CONFIGURATION **********************************/ +#ifdef USB_OTG_FS_CORE + #define RX_FIFO_FS_SIZE 128 + #define TX0_FIFO_FS_SIZE 64 + #define TX1_FIFO_FS_SIZE 128 + #define TX2_FIFO_FS_SIZE 0 + #define TX3_FIFO_FS_SIZE 0 + #define TXH_NP_HS_FIFOSIZ 96 + #define TXH_P_HS_FIFOSIZ 96 + + //#define USB_OTG_FS_LOW_PWR_MGMT_SUPPORT + //#define USB_OTG_FS_SOF_OUTPUT_ENABLED +#endif + +/****************** USB OTG MODE CONFIGURATION ********************************/ +//#define USE_HOST_MODE +#define USE_DEVICE_MODE +//#define USE_OTG_MODE + + +#ifndef USB_OTG_FS_CORE + #ifndef USB_OTG_HS_CORE + #error "USB_OTG_HS_CORE or USB_OTG_FS_CORE should be defined" + #endif +#endif + + +#ifndef USE_DEVICE_MODE + #ifndef USE_HOST_MODE + #error "USE_DEVICE_MODE or USE_HOST_MODE should be defined" + #endif +#endif + +#ifndef USE_USB_OTG_HS + #ifndef USE_USB_OTG_FS + #error "USE_USB_OTG_HS or USE_USB_OTG_FS should be defined" + #endif +#else //USE_USB_OTG_HS + #ifndef USE_ULPI_PHY + #ifndef USE_EMBEDDED_PHY + #ifndef USE_I2C_PHY + #error "USE_ULPI_PHY or USE_EMBEDDED_PHY or USE_I2C_PHY should be defined" + #endif + #endif + #endif +#endif + +/****************** C Compilers dependant keywords ****************************/ +/* In HS mode and when the DMA is used, all variables and data structures dealing + with the DMA during the transaction process should be 4-bytes aligned */ +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED + #if defined (__GNUC__) /* GNU Compiler */ + #define __ALIGN_END __attribute__ ((aligned (4))) + #define __ALIGN_BEGIN + #else + #define __ALIGN_END + #if defined (__CC_ARM) /* ARM Compiler */ + #define __ALIGN_BEGIN __align(4) + #elif defined (__ICCARM__) /* IAR Compiler */ + #define __ALIGN_BEGIN + #elif defined (__TASKING__) /* TASKING Compiler */ + #define __ALIGN_BEGIN __align(4) + #endif /* __CC_ARM */ + #endif /* __GNUC__ */ +#else + #define __ALIGN_BEGIN + #define __ALIGN_END +#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ + +/* __packed keyword used to decrease the data type alignment to 1-byte */ +#if defined (__CC_ARM) /* ARM Compiler */ + #define __packed __packed +#elif defined (__ICCARM__) /* IAR Compiler */ + #define __packed __packed +#elif defined ( __GNUC__ ) /* GNU Compiler */ + #define __packed __attribute__ ((__packed__)) +#elif defined (__TASKING__) /* TASKING Compiler */ + #define __packed __unaligned +#endif /* __CC_ARM */ + +/** + * @} + */ + + +/** @defgroup USB_CONF_Exported_Types + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_CONF_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_CONF_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_CONF_Exported_FunctionsPrototype + * @{ + */ +/** + * @} + */ + + +#endif //__USB_CONF__H__ + + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_core.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_core.h new file mode 100644 index 000000000..0a966a5d3 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_core.h @@ -0,0 +1,408 @@ +/** + ****************************************************************************** + * @file usb_core.h + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Header of the Core Layer + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_CORE_H__ +#define __USB_CORE_H__ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_conf.h" +#include "usb_regs.h" +#include "usb_defines.h" + + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_CORE + * @brief usb otg driver core layer + * @{ + */ + + +/** @defgroup USB_CORE_Exported_Defines + * @{ + */ + +#define USB_OTG_EP0_IDLE 0 +#define USB_OTG_EP0_SETUP 1 +#define USB_OTG_EP0_DATA_IN 2 +#define USB_OTG_EP0_DATA_OUT 3 +#define USB_OTG_EP0_STATUS_IN 4 +#define USB_OTG_EP0_STATUS_OUT 5 +#define USB_OTG_EP0_STALL 6 + +#define USB_OTG_EP_TX_DIS 0x0000 +#define USB_OTG_EP_TX_STALL 0x0010 +#define USB_OTG_EP_TX_NAK 0x0020 +#define USB_OTG_EP_TX_VALID 0x0030 + +#define USB_OTG_EP_RX_DIS 0x0000 +#define USB_OTG_EP_RX_STALL 0x1000 +#define USB_OTG_EP_RX_NAK 0x2000 +#define USB_OTG_EP_RX_VALID 0x3000 +/** + * @} + */ +#define MAX_DATA_LENGTH 0xFF + +/** @defgroup USB_CORE_Exported_Types + * @{ + */ + + +typedef enum { + USB_OTG_OK = 0, + USB_OTG_FAIL +}USB_OTG_STS; + +typedef enum { + HC_IDLE = 0, + HC_XFRC, + HC_HALTED, + HC_NAK, + HC_NYET, + HC_STALL, + HC_XACTERR, + HC_BBLERR, + HC_DATATGLERR, +}HC_STATUS; + +typedef enum { + URB_IDLE = 0, + URB_DONE, + URB_NOTREADY, + URB_ERROR, + URB_STALL +}URB_STATE; + +typedef enum { + CTRL_START = 0, + CTRL_XFRC, + CTRL_HALTED, + CTRL_NAK, + CTRL_STALL, + CTRL_XACTERR, + CTRL_BBLERR, + CTRL_DATATGLERR, + CTRL_FAIL +}CTRL_STATUS; + + +typedef struct USB_OTG_hc +{ + uint8_t dev_addr ; + uint8_t ep_num; + uint8_t ep_is_in; + uint8_t speed; + uint8_t do_ping; + uint8_t ep_type; + uint16_t max_packet; + uint8_t data_pid; + uint8_t *xfer_buff; + uint32_t xfer_len; + uint32_t xfer_count; + uint8_t toggle_in; + uint8_t toggle_out; + uint32_t dma_addr; +} +USB_OTG_HC , *PUSB_OTG_HC; + +typedef struct USB_OTG_ep +{ + uint8_t num; + uint8_t is_in; + uint8_t is_stall; + uint8_t type; + uint8_t data_pid_start; + uint8_t even_odd_frame; + uint16_t tx_fifo_num; + uint32_t maxpacket; + /* transaction level variables*/ + uint8_t *xfer_buff; + uint32_t dma_addr; + uint32_t xfer_len; + uint32_t xfer_count; + /* Transfer level variables*/ + uint32_t rem_data_len; + uint32_t total_data_len; + uint32_t ctl_data_len; + +} + +USB_OTG_EP , *PUSB_OTG_EP; + + + +typedef struct USB_OTG_core_cfg +{ + uint8_t host_channels; + uint8_t dev_endpoints; + uint8_t speed; + uint8_t dma_enable; + uint16_t mps; + uint16_t TotalFifoSize; + uint8_t phy_itface; + uint8_t Sof_output; + uint8_t low_power; + uint8_t coreID; + +} +USB_OTG_CORE_CFGS, *PUSB_OTG_CORE_CFGS; + + + +typedef struct usb_setup_req { + + uint8_t bmRequest; + uint8_t bRequest; + uint16_t wValue; + uint16_t wIndex; + uint16_t wLength; +} USB_SETUP_REQ; + +typedef struct _Device_TypeDef +{ + const uint8_t *(*GetDeviceDescriptor)( uint8_t speed , uint16_t *length); + const uint8_t *(*GetLangIDStrDescriptor)( uint8_t speed , uint16_t *length); + const uint8_t *(*GetManufacturerStrDescriptor)( uint8_t speed , uint16_t *length); + const uint8_t *(*GetProductStrDescriptor)( uint8_t speed , uint16_t *length); + const uint8_t *(*GetSerialStrDescriptor)( uint8_t speed , uint16_t *length); + const uint8_t *(*GetConfigurationStrDescriptor)( uint8_t speed , uint16_t *length); + const uint8_t *(*GetInterfaceStrDescriptor)( uint8_t speed , uint16_t *length); +} USBD_DEVICE, *pUSBD_DEVICE; + +typedef struct USB_OTG_hPort +{ + void (*Disconnect) (void *phost); + void (*Connect) (void *phost); + uint8_t ConnStatus; + uint8_t DisconnStatus; + uint8_t ConnHandled; + uint8_t DisconnHandled; +} USB_OTG_hPort_TypeDef; + +typedef struct _Device_cb +{ + uint8_t (*Init) (void *pdev , uint8_t cfgidx); + uint8_t (*DeInit) (void *pdev , uint8_t cfgidx); + /* Control Endpoints*/ + uint8_t (*Setup) (void *pdev , USB_SETUP_REQ *req); + uint8_t (*EP0_TxSent) (void *pdev ); + uint8_t (*EP0_RxReady) (void *pdev ); + /* Class Specific Endpoints*/ + uint8_t (*DataIn) (void *pdev , uint8_t epnum); + uint8_t (*DataOut) (void *pdev , uint8_t epnum); + uint8_t (*SOF) (void *pdev); + uint8_t (*IsoINIncomplete) (void *pdev); + uint8_t (*IsoOUTIncomplete) (void *pdev); + + const uint8_t *(*GetConfigDescriptor)( uint8_t speed , uint16_t *length); +#ifdef USB_OTG_HS_CORE + const uint8_t *(*GetOtherConfigDescriptor)( uint8_t speed , uint16_t *length); +#endif + +#ifdef USB_SUPPORT_USER_STRING_DESC + const uint8_t *(*GetUsrStrDescriptor)( uint8_t speed ,uint8_t index, uint16_t *length); +#endif + +} USBD_Class_cb_TypeDef; + + + +typedef struct _USBD_USR_PROP +{ + void (*Init)(void); + void (*DeviceReset)(uint8_t speed); + void (*DeviceConfigured)(void); + void (*DeviceSuspended)(void); + void (*DeviceResumed)(void); + + void (*DeviceConnected)(void); + void (*DeviceDisconnected)(void); + +} +USBD_Usr_cb_TypeDef; + +typedef struct _DCD +{ + uint8_t device_config; + uint8_t device_state; + uint8_t device_status; + uint8_t device_address; + uint32_t DevRemoteWakeup; + USB_OTG_EP in_ep [USB_OTG_MAX_TX_FIFOS]; + USB_OTG_EP out_ep [USB_OTG_MAX_TX_FIFOS]; + uint8_t setup_packet [8*3]; + USBD_Class_cb_TypeDef *class_cb; + USBD_Usr_cb_TypeDef *usr_cb; + USBD_DEVICE *usr_device; + const uint8_t *pConfig_descriptor; + } +DCD_DEV , *DCD_PDEV; + + +typedef struct _HCD +{ + uint8_t Rx_Buffer [MAX_DATA_LENGTH]; + __IO uint32_t ConnSts; + __IO uint32_t ErrCnt[USB_OTG_MAX_TX_FIFOS]; + __IO uint32_t XferCnt[USB_OTG_MAX_TX_FIFOS]; + __IO HC_STATUS HC_Status[USB_OTG_MAX_TX_FIFOS]; + __IO URB_STATE URB_State[USB_OTG_MAX_TX_FIFOS]; + USB_OTG_HC hc [USB_OTG_MAX_TX_FIFOS]; + uint16_t channel [USB_OTG_MAX_TX_FIFOS]; + USB_OTG_hPort_TypeDef *port_cb; +} +HCD_DEV , *USB_OTG_USBH_PDEV; + + +typedef struct _OTG +{ + uint8_t OTG_State; + uint8_t OTG_PrevState; + uint8_t OTG_Mode; +} +OTG_DEV , *USB_OTG_USBO_PDEV; + +typedef struct USB_OTG_handle +{ + USB_OTG_CORE_CFGS cfg; + USB_OTG_CORE_REGS regs; +#ifdef USE_DEVICE_MODE + DCD_DEV dev; +#endif +#ifdef USE_HOST_MODE + HCD_DEV host; +#endif +#ifdef USE_OTG_MODE + OTG_DEV otg; +#endif +} +USB_OTG_CORE_HANDLE , *PUSB_OTG_CORE_HANDLE; + +/** + * @} + */ + + +/** @defgroup USB_CORE_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup USB_CORE_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_CORE_Exported_FunctionsPrototype + * @{ + */ + + +USB_OTG_STS USB_OTG_CoreInit (USB_OTG_CORE_HANDLE *pdev); +USB_OTG_STS USB_OTG_SelectCore (USB_OTG_CORE_HANDLE *pdev, + USB_OTG_CORE_ID_TypeDef coreID); +USB_OTG_STS USB_OTG_EnableGlobalInt (USB_OTG_CORE_HANDLE *pdev); +USB_OTG_STS USB_OTG_DisableGlobalInt(USB_OTG_CORE_HANDLE *pdev); +void* USB_OTG_ReadPacket (USB_OTG_CORE_HANDLE *pdev , + uint8_t *dest, + uint16_t len); +USB_OTG_STS USB_OTG_WritePacket (USB_OTG_CORE_HANDLE *pdev , + uint8_t *src, + uint8_t ch_ep_num, + uint16_t len); +USB_OTG_STS USB_OTG_FlushTxFifo (USB_OTG_CORE_HANDLE *pdev , uint32_t num); +USB_OTG_STS USB_OTG_FlushRxFifo (USB_OTG_CORE_HANDLE *pdev); + +uint32_t USB_OTG_ReadCoreItr (USB_OTG_CORE_HANDLE *pdev); +uint32_t USB_OTG_ReadOtgItr (USB_OTG_CORE_HANDLE *pdev); +uint8_t USB_OTG_IsHostMode (USB_OTG_CORE_HANDLE *pdev); +uint8_t USB_OTG_IsDeviceMode (USB_OTG_CORE_HANDLE *pdev); +uint32_t USB_OTG_GetMode (USB_OTG_CORE_HANDLE *pdev); +USB_OTG_STS USB_OTG_PhyInit (USB_OTG_CORE_HANDLE *pdev); +USB_OTG_STS USB_OTG_SetCurrentMode (USB_OTG_CORE_HANDLE *pdev, + uint8_t mode); + +/*********************** HOST APIs ********************************************/ +#ifdef USE_HOST_MODE +USB_OTG_STS USB_OTG_CoreInitHost (USB_OTG_CORE_HANDLE *pdev); +USB_OTG_STS USB_OTG_EnableHostInt (USB_OTG_CORE_HANDLE *pdev); +USB_OTG_STS USB_OTG_HC_Init (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num); +USB_OTG_STS USB_OTG_HC_Halt (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num); +USB_OTG_STS USB_OTG_HC_StartXfer (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num); +USB_OTG_STS USB_OTG_HC_DoPing (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num); +uint32_t USB_OTG_ReadHostAllChannels_intr (USB_OTG_CORE_HANDLE *pdev); +uint32_t USB_OTG_ResetPort (USB_OTG_CORE_HANDLE *pdev); +uint32_t USB_OTG_ReadHPRT0 (USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_DriveVbus (USB_OTG_CORE_HANDLE *pdev, uint8_t state); +void USB_OTG_InitFSLSPClkSel (USB_OTG_CORE_HANDLE *pdev ,uint8_t freq); +uint8_t USB_OTG_IsEvenFrame (USB_OTG_CORE_HANDLE *pdev) ; +void USB_OTG_StopHost (USB_OTG_CORE_HANDLE *pdev); +#endif +/********************* DEVICE APIs ********************************************/ +#ifdef USE_DEVICE_MODE +USB_OTG_STS USB_OTG_CoreInitDev (USB_OTG_CORE_HANDLE *pdev); +USB_OTG_STS USB_OTG_EnableDevInt (USB_OTG_CORE_HANDLE *pdev); +uint32_t USB_OTG_ReadDevAllInEPItr (USB_OTG_CORE_HANDLE *pdev); +enum USB_OTG_SPEED USB_OTG_GetDeviceSpeed (USB_OTG_CORE_HANDLE *pdev); +USB_OTG_STS USB_OTG_EP0Activate (USB_OTG_CORE_HANDLE *pdev); +USB_OTG_STS USB_OTG_EPActivate (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep); +USB_OTG_STS USB_OTG_EPDeactivate(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep); +USB_OTG_STS USB_OTG_EPStartXfer (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep); +USB_OTG_STS USB_OTG_EP0StartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep); +USB_OTG_STS USB_OTG_EPSetStall (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep); +USB_OTG_STS USB_OTG_EPClearStall (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep); +uint32_t USB_OTG_ReadDevAllOutEp_itr (USB_OTG_CORE_HANDLE *pdev); +uint32_t USB_OTG_ReadDevOutEP_itr (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum); +uint32_t USB_OTG_ReadDevAllInEPItr (USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_InitDevSpeed (USB_OTG_CORE_HANDLE *pdev , uint8_t speed); +uint8_t USBH_IsEvenFrame (USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_EP0_OutStart(USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_ActiveRemoteWakeup(USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_UngateClock(USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_StopDevice(USB_OTG_CORE_HANDLE *pdev); +void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t Status); +uint32_t USB_OTG_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,USB_OTG_EP *ep); +#endif +/** + * @} + */ + +#endif /* __USB_CORE_H__ */ + + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_dcd.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_dcd.h new file mode 100644 index 000000000..a8dcdc197 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_dcd.h @@ -0,0 +1,158 @@ +/** + ****************************************************************************** + * @file usb_dcd.h + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Peripheral Driver Header file + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __DCD_H__ +#define __DCD_H__ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_core.h" + + +/** @addtogroup USB_OTG_DRIVER +* @{ +*/ + +/** @defgroup USB_DCD +* @brief This file is the +* @{ +*/ + + +/** @defgroup USB_DCD_Exported_Defines +* @{ +*/ +#define USB_OTG_EP_CONTROL 0 +#define USB_OTG_EP_ISOC 1 +#define USB_OTG_EP_BULK 2 +#define USB_OTG_EP_INT 3 +#define USB_OTG_EP_MASK 3 + +/* Device Status */ +#define USB_OTG_DEFAULT 1 +#define USB_OTG_ADDRESSED 2 +#define USB_OTG_CONFIGURED 3 +#define USB_OTG_SUSPENDED 4 + +/** +* @} +*/ + + +/** @defgroup USB_DCD_Exported_Types +* @{ +*/ +/******************************************************************************** +Data structure type +********************************************************************************/ +typedef struct +{ + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bEndpointAddress; + uint8_t bmAttributes; + uint16_t wMaxPacketSize; + uint8_t bInterval; +} +EP_DESCRIPTOR , *PEP_DESCRIPTOR; + +/** +* @} +*/ + + +/** @defgroup USB_DCD_Exported_Macros +* @{ +*/ +/** +* @} +*/ + +/** @defgroup USB_DCD_Exported_Variables +* @{ +*/ +/** +* @} +*/ + +/** @defgroup USB_DCD_Exported_FunctionsPrototype +* @{ +*/ +/******************************************************************************** +EXPORTED FUNCTION FROM THE USB-OTG LAYER +********************************************************************************/ +void DCD_Init(USB_OTG_CORE_HANDLE *pdev , + USB_OTG_CORE_ID_TypeDef coreID); + +void DCD_DevConnect (USB_OTG_CORE_HANDLE *pdev); +void DCD_DevDisconnect (USB_OTG_CORE_HANDLE *pdev); +void DCD_EP_SetAddress (USB_OTG_CORE_HANDLE *pdev, + uint8_t address); +uint32_t DCD_EP_Open(USB_OTG_CORE_HANDLE *pdev , + uint8_t ep_addr, + uint16_t ep_mps, + uint8_t ep_type); + +uint32_t DCD_EP_Close (USB_OTG_CORE_HANDLE *pdev, + uint8_t ep_addr); + + +uint32_t DCD_EP_PrepareRx ( USB_OTG_CORE_HANDLE *pdev, + uint8_t ep_addr, + uint8_t *pbuf, + uint16_t buf_len); + +uint32_t DCD_EP_Tx (USB_OTG_CORE_HANDLE *pdev, + uint8_t ep_addr, + const uint8_t *pbuf, + uint32_t buf_len); +uint32_t DCD_EP_Stall (USB_OTG_CORE_HANDLE *pdev, + uint8_t epnum); +uint32_t DCD_EP_ClrStall (USB_OTG_CORE_HANDLE *pdev, + uint8_t epnum); +uint32_t DCD_EP_Flush (USB_OTG_CORE_HANDLE *pdev, + uint8_t epnum); +uint32_t DCD_Handle_ISR(USB_OTG_CORE_HANDLE *pdev); + +uint32_t DCD_GetEPStatus(USB_OTG_CORE_HANDLE *pdev , + uint8_t epnum); + +void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , + uint8_t epnum , + uint32_t Status); + +/** +* @} +*/ + + +#endif //__DCD_H__ + + +/** +* @} +*/ + +/** +* @} +*/ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_dcd_int.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_dcd_int.h new file mode 100644 index 000000000..9df1a4172 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_dcd_int.h @@ -0,0 +1,121 @@ +/** + ****************************************************************************** + * @file usb_dcd_int.h + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Peripheral Device Interface Layer + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef USB_DCD_INT_H__ +#define USB_DCD_INT_H__ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_dcd.h" + + + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_DCD_INT + * @brief This file is the + * @{ + */ + + +/** @defgroup USB_DCD_INT_Exported_Defines + * @{ + */ + +typedef struct _USBD_DCD_INT +{ + uint8_t (* DataOutStage) (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum); + uint8_t (* DataInStage) (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum); + uint8_t (* SetupStage) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* SOF) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* Reset) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* Suspend) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* Resume) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* IsoINIncomplete) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* IsoOUTIncomplete) (USB_OTG_CORE_HANDLE *pdev); + + uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev); + uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev); + +}USBD_DCD_INT_cb_TypeDef; + +extern USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops; +/** + * @} + */ + + +/** @defgroup USB_DCD_INT_Exported_Types + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_DCD_INT_Exported_Macros + * @{ + */ + +#define CLEAR_IN_EP_INTR(epnum,intr) \ + diepint.d32=0; \ + diepint.b.intr = 1; \ + USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[epnum]->DIEPINT,diepint.d32); + +#define CLEAR_OUT_EP_INTR(epnum,intr) \ + doepint.d32=0; \ + doepint.b.intr = 1; \ + USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[epnum]->DOEPINT,doepint.d32); + +/** + * @} + */ + +/** @defgroup USB_DCD_INT_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_DCD_INT_Exported_FunctionsPrototype + * @{ + */ + +uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev); + +/** + * @} + */ + + +#endif // USB_DCD_INT_H__ + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_defines.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_defines.h new file mode 100644 index 000000000..b119c2586 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_defines.h @@ -0,0 +1,244 @@ +/** + ****************************************************************************** + * @file usb_defines.h + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Header of the Core Layer + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_DEF_H__ +#define __USB_DEF_H__ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_conf.h" + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_DEFINES + * @brief This file is the + * @{ + */ + + +/** @defgroup USB_DEFINES_Exported_Defines + * @{ + */ +/** + * @} + */ + + +/** @defgroup _CORE_DEFINES_ + * @{ + */ + +#define USB_OTG_SPEED_PARAM_HIGH 0 +#define USB_OTG_SPEED_PARAM_HIGH_IN_FULL 1 +#define USB_OTG_SPEED_PARAM_FULL 3 + +#define USB_OTG_SPEED_HIGH 0 +#define USB_OTG_SPEED_FULL 1 + +#define USB_OTG_ULPI_PHY 1 +#define USB_OTG_EMBEDDED_PHY 2 +#define USB_OTG_I2C_PHY 3 + +/** + * @} + */ + + +/** @defgroup _GLOBAL_DEFINES_ + * @{ + */ +#define GAHBCFG_TXFEMPTYLVL_EMPTY 1 +#define GAHBCFG_TXFEMPTYLVL_HALFEMPTY 0 +#define GAHBCFG_GLBINT_ENABLE 1 +#define GAHBCFG_INT_DMA_BURST_SINGLE 0 +#define GAHBCFG_INT_DMA_BURST_INCR 1 +#define GAHBCFG_INT_DMA_BURST_INCR4 3 +#define GAHBCFG_INT_DMA_BURST_INCR8 5 +#define GAHBCFG_INT_DMA_BURST_INCR16 7 +#define GAHBCFG_DMAENABLE 1 +#define GAHBCFG_TXFEMPTYLVL_EMPTY 1 +#define GAHBCFG_TXFEMPTYLVL_HALFEMPTY 0 +#define GRXSTS_PKTSTS_IN 2 +#define GRXSTS_PKTSTS_IN_XFER_COMP 3 +#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5 +#define GRXSTS_PKTSTS_CH_HALTED 7 +/** + * @} + */ + + +/** @defgroup _OnTheGo_DEFINES_ + * @{ + */ +#define MODE_HNP_SRP_CAPABLE 0 +#define MODE_SRP_ONLY_CAPABLE 1 +#define MODE_NO_HNP_SRP_CAPABLE 2 +#define MODE_SRP_CAPABLE_DEVICE 3 +#define MODE_NO_SRP_CAPABLE_DEVICE 4 +#define MODE_SRP_CAPABLE_HOST 5 +#define MODE_NO_SRP_CAPABLE_HOST 6 +#define A_HOST 1 +#define A_SUSPEND 2 +#define A_PERIPHERAL 3 +#define B_PERIPHERAL 4 +#define B_HOST 5 +#define DEVICE_MODE 0 +#define HOST_MODE 1 +#define OTG_MODE 2 +/** + * @} + */ + + +/** @defgroup __DEVICE_DEFINES_ + * @{ + */ +#define DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ 0 +#define DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ 1 +#define DSTS_ENUMSPD_LS_PHY_6MHZ 2 +#define DSTS_ENUMSPD_FS_PHY_48MHZ 3 + +#define DCFG_FRAME_INTERVAL_80 0 +#define DCFG_FRAME_INTERVAL_85 1 +#define DCFG_FRAME_INTERVAL_90 2 +#define DCFG_FRAME_INTERVAL_95 3 + +#define DEP0CTL_MPS_64 0 +#define DEP0CTL_MPS_32 1 +#define DEP0CTL_MPS_16 2 +#define DEP0CTL_MPS_8 3 + +#define EP_SPEED_LOW 0 +#define EP_SPEED_FULL 1 +#define EP_SPEED_HIGH 2 + +#define EP_TYPE_CTRL 0 +#define EP_TYPE_ISOC 1 +#define EP_TYPE_BULK 2 +#define EP_TYPE_INTR 3 +#define EP_TYPE_MSK 3 + +#define STS_GOUT_NAK 1 +#define STS_DATA_UPDT 2 +#define STS_XFER_COMP 3 +#define STS_SETUP_COMP 4 +#define STS_SETUP_UPDT 6 +/** + * @} + */ + + +/** @defgroup __HOST_DEFINES_ + * @{ + */ +#define HC_PID_DATA0 0 +#define HC_PID_DATA2 1 +#define HC_PID_DATA1 2 +#define HC_PID_SETUP 3 + +#define HPRT0_PRTSPD_HIGH_SPEED 0 +#define HPRT0_PRTSPD_FULL_SPEED 1 +#define HPRT0_PRTSPD_LOW_SPEED 2 + +#define HCFG_30_60_MHZ 0 +#define HCFG_48_MHZ 1 +#define HCFG_6_MHZ 2 + +#define HCCHAR_CTRL 0 +#define HCCHAR_ISOC 1 +#define HCCHAR_BULK 2 +#define HCCHAR_INTR 3 + +#define MIN(a, b) (((a) < (b)) ? (a) : (b)) + +/** + * @} + */ + + +/** @defgroup USB_DEFINES_Exported_Types + * @{ + */ + +typedef enum +{ + USB_OTG_HS_CORE_ID = 0, + USB_OTG_FS_CORE_ID = 1 +}USB_OTG_CORE_ID_TypeDef; +/** + * @} + */ + + +/** @defgroup USB_DEFINES_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_DEFINES_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_DEFINES_Exported_FunctionsPrototype + * @{ + */ +/** + * @} + */ + + +/** @defgroup Internal_Macro's + * @{ + */ +#define USB_OTG_READ_REG32(reg) (*(__IO uint32_t *)reg) +#define USB_OTG_WRITE_REG32(reg,value) (*(__IO uint32_t *)reg = value) +#define USB_OTG_MODIFY_REG32(reg,clear_mask,set_mask) \ + USB_OTG_WRITE_REG32(reg, (((USB_OTG_READ_REG32(reg)) & ~clear_mask) | set_mask ) ) + +/******************************************************************************** + ENUMERATION TYPE +********************************************************************************/ +enum USB_OTG_SPEED { + USB_SPEED_UNKNOWN = 0, + USB_SPEED_LOW, + USB_SPEED_FULL, + USB_SPEED_HIGH +}; + +#endif //__USB_DEFINES__H__ + + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_hcd.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_hcd.h new file mode 100644 index 000000000..15e8ab161 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_hcd.h @@ -0,0 +1,102 @@ +/** + ****************************************************************************** + * @file usb_hcd.h + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Host layer Header file + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_HCD_H__ +#define __USB_HCD_H__ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_regs.h" +#include "usb_core.h" + + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_HCD + * @brief This file is the + * @{ + */ + + +/** @defgroup USB_HCD_Exported_Defines + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_Exported_Types + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_HCD_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_HCD_Exported_FunctionsPrototype + * @{ + */ +uint32_t HCD_Init (USB_OTG_CORE_HANDLE *pdev , + USB_OTG_CORE_ID_TypeDef coreID); +uint32_t HCD_HC_Init (USB_OTG_CORE_HANDLE *pdev , + uint8_t hc_num); +uint32_t HCD_SubmitRequest (USB_OTG_CORE_HANDLE *pdev , + uint8_t hc_num) ; +uint32_t HCD_GetCurrentSpeed (USB_OTG_CORE_HANDLE *pdev); +uint32_t HCD_ResetPort (USB_OTG_CORE_HANDLE *pdev); +uint32_t HCD_IsDeviceConnected (USB_OTG_CORE_HANDLE *pdev); +uint32_t HCD_GetCurrentFrame (USB_OTG_CORE_HANDLE *pdev) ; +URB_STATE HCD_GetURB_State (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num); +uint32_t HCD_GetXferCnt (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num); +HC_STATUS HCD_GetHCState (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num) ; +/** + * @} + */ + +#endif //__USB_HCD_H__ + + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_hcd_int.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_hcd_int.h new file mode 100644 index 000000000..c95c59f82 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_hcd_int.h @@ -0,0 +1,126 @@ +/** + ****************************************************************************** + * @file usb_hcd_int.h + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Peripheral Device Interface Layer + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __HCD_INT_H__ +#define __HCD_INT_H__ + + +/* Includes ------------------------------------------------------------------*/ +#include "usb_hcd.h" + + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_HCD_INT + * @brief This file is the + * @{ + */ + + +/** @defgroup USB_HCD_INT_Exported_Defines + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_INT_Exported_Types + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_INT_Exported_Macros + * @{ + */ + +#define CLEAR_HC_INT(HC_REGS, intr) \ + {\ + USB_OTG_HCINTn_TypeDef hcint_clear; \ + hcint_clear.d32 = 0; \ + hcint_clear.b.intr = 1; \ + USB_OTG_WRITE_REG32(&((HC_REGS)->HCINT), hcint_clear.d32);\ + }\ + +#define MASK_HOST_INT_CHH(hc_num) { USB_OTG_HCGINTMSK_TypeDef GINTMSK; \ + GINTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK); \ + GINTMSK.b.chhltd = 0; \ + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, GINTMSK.d32);} + +#define UNMASK_HOST_INT_CHH(hc_num) { USB_OTG_HCGINTMSK_TypeDef GINTMSK; \ + GINTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK); \ + GINTMSK.b.chhltd = 1; \ + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, GINTMSK.d32);} + +#define MASK_HOST_INT_ACK(hc_num) { USB_OTG_HCGINTMSK_TypeDef GINTMSK; \ + GINTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK); \ + GINTMSK.b.ack = 0; \ + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, GINTMSK.d32);} + +#define UNMASK_HOST_INT_ACK(hc_num) { USB_OTG_HCGINTMSK_TypeDef GINTMSK; \ + GINTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK); \ + GINTMSK.b.ack = 1; \ + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, GINTMSK.d32);} + +/** + * @} + */ + +/** @defgroup USB_HCD_INT_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_HCD_INT_Exported_FunctionsPrototype + * @{ + */ +/* Callbacks handler */ +void ConnectCallback_Handler(USB_OTG_CORE_HANDLE *pdev); +void Disconnect_Callback_Handler(USB_OTG_CORE_HANDLE *pdev); +void Overcurrent_Callback_Handler(USB_OTG_CORE_HANDLE *pdev); +uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev); + +/** + * @} + */ + + + +#endif //__HCD_INT_H__ + + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_otg.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_otg.h new file mode 100644 index 000000000..54d61b827 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_otg.h @@ -0,0 +1,94 @@ +/** + ****************************************************************************** + * @file usb_otg.h + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief OTG Core Header + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_OTG__ +#define __USB_OTG__ + + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_OTG + * @brief This file is the + * @{ + */ + + +/** @defgroup USB_OTG_Exported_Defines + * @{ + */ + + +void USB_OTG_InitiateSRP(void); +void USB_OTG_InitiateHNP(uint8_t state , uint8_t mode); +void USB_OTG_Switchback (USB_OTG_CORE_HANDLE *pdev); +uint32_t USB_OTG_GetCurrentState (USB_OTG_CORE_HANDLE *pdev); + +uint32_t STM32_USBO_OTG_ISR_Handler(USB_OTG_CORE_HANDLE *pdev); +/** + * @} + */ + + +/** @defgroup USB_OTG_Exported_Types + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_OTG_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_OTG_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_OTG_Exported_FunctionsPrototype + * @{ + */ +/** + * @} + */ + + +#endif //__USB_OTG__ + + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_regs.h b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_regs.h new file mode 100644 index 000000000..cd71ddfaf --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/inc/usb_regs.h @@ -0,0 +1,1206 @@ +/** + ****************************************************************************** + * @file usb_regs.h + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief hardware registers + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_OTG_REGS_H__ +#define __USB_OTG_REGS_H__ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_conf.h" + + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_REGS + * @brief This file is the + * @{ + */ + + +/** @defgroup USB_REGS_Exported_Defines + * @{ + */ + +#define USB_OTG_HS_BASE_ADDR 0x40040000 +#define USB_OTG_FS_BASE_ADDR 0x50000000 + +#define USB_OTG_CORE_GLOBAL_REGS_OFFSET 0x000 +#define USB_OTG_DEV_GLOBAL_REG_OFFSET 0x800 +#define USB_OTG_DEV_IN_EP_REG_OFFSET 0x900 +#define USB_OTG_EP_REG_OFFSET 0x20 +#define USB_OTG_DEV_OUT_EP_REG_OFFSET 0xB00 +#define USB_OTG_HOST_GLOBAL_REG_OFFSET 0x400 +#define USB_OTG_HOST_PORT_REGS_OFFSET 0x440 +#define USB_OTG_HOST_CHAN_REGS_OFFSET 0x500 +#define USB_OTG_CHAN_REGS_OFFSET 0x20 +#define USB_OTG_PCGCCTL_OFFSET 0xE00 +#define USB_OTG_DATA_FIFO_OFFSET 0x1000 +#define USB_OTG_DATA_FIFO_SIZE 0x1000 + + +#define USB_OTG_MAX_TX_FIFOS 15 + +#define USB_OTG_HS_MAX_PACKET_SIZE 512 +#define USB_OTG_FS_MAX_PACKET_SIZE 64 +#define USB_OTG_MAX_EP0_SIZE 64 +/** + * @} + */ + +/** @defgroup USB_REGS_Exported_Types + * @{ + */ + +/** @defgroup __USB_OTG_Core_register + * @{ + */ +typedef struct _USB_OTG_GREGS //000h +{ + __IO uint32_t GOTGCTL; /* USB_OTG Control and Status Register 000h*/ + __IO uint32_t GOTGINT; /* USB_OTG Interrupt Register 004h*/ + __IO uint32_t GAHBCFG; /* Core AHB Configuration Register 008h*/ + __IO uint32_t GUSBCFG; /* Core USB Configuration Register 00Ch*/ + __IO uint32_t GRSTCTL; /* Core Reset Register 010h*/ + __IO uint32_t GINTSTS; /* Core Interrupt Register 014h*/ + __IO uint32_t GINTMSK; /* Core Interrupt Mask Register 018h*/ + __IO uint32_t GRXSTSR; /* Receive Sts Q Read Register 01Ch*/ + __IO uint32_t GRXSTSP; /* Receive Sts Q Read & POP Register 020h*/ + __IO uint32_t GRXFSIZ; /* Receive FIFO Size Register 024h*/ + __IO uint32_t DIEPTXF0_HNPTXFSIZ; /* EP0 / Non Periodic Tx FIFO Size Register 028h*/ + __IO uint32_t HNPTXSTS; /* Non Periodic Tx FIFO/Queue Sts reg 02Ch*/ + __IO uint32_t GI2CCTL; /* I2C Access Register 030h*/ + uint32_t Reserved34; /* PHY Vendor Control Register 034h*/ + __IO uint32_t GCCFG; /* General Purpose IO Register 038h*/ + __IO uint32_t CID; /* User ID Register 03Ch*/ + uint32_t Reserved40[48]; /* Reserved 040h-0FFh*/ + __IO uint32_t HPTXFSIZ; /* Host Periodic Tx FIFO Size Reg 100h*/ + __IO uint32_t DIEPTXF[USB_OTG_MAX_TX_FIFOS];/* dev Periodic Transmit FIFO */ +} +USB_OTG_GREGS; +/** + * @} + */ + + +/** @defgroup __device_Registers + * @{ + */ +typedef struct _USB_OTG_DREGS // 800h +{ + __IO uint32_t DCFG; /* dev Configuration Register 800h*/ + __IO uint32_t DCTL; /* dev Control Register 804h*/ + __IO uint32_t DSTS; /* dev Status Register (RO) 808h*/ + uint32_t Reserved0C; /* Reserved 80Ch*/ + __IO uint32_t DIEPMSK; /* dev IN Endpoint Mask 810h*/ + __IO uint32_t DOEPMSK; /* dev OUT Endpoint Mask 814h*/ + __IO uint32_t DAINT; /* dev All Endpoints Itr Reg 818h*/ + __IO uint32_t DAINTMSK; /* dev All Endpoints Itr Mask 81Ch*/ + uint32_t Reserved20; /* Reserved 820h*/ + uint32_t Reserved9; /* Reserved 824h*/ + __IO uint32_t DVBUSDIS; /* dev VBUS discharge Register 828h*/ + __IO uint32_t DVBUSPULSE; /* dev VBUS Pulse Register 82Ch*/ + __IO uint32_t DTHRCTL; /* dev thr 830h*/ + __IO uint32_t DIEPEMPMSK; /* dev empty msk 834h*/ + __IO uint32_t DEACHINT; /* dedicated EP interrupt 838h*/ + __IO uint32_t DEACHMSK; /* dedicated EP msk 83Ch*/ + uint32_t Reserved40; /* dedicated EP mask 840h*/ + __IO uint32_t DINEP1MSK; /* dedicated EP mask 844h*/ + uint32_t Reserved44[15]; /* Reserved 844-87Ch*/ + __IO uint32_t DOUTEP1MSK; /* dedicated EP msk 884h*/ +} +USB_OTG_DREGS; +/** + * @} + */ + + +/** @defgroup __IN_Endpoint-Specific_Register + * @{ + */ +typedef struct _USB_OTG_INEPREGS +{ + __IO uint32_t DIEPCTL; /* dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h*/ + uint32_t Reserved04; /* Reserved 900h + (ep_num * 20h) + 04h*/ + __IO uint32_t DIEPINT; /* dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h*/ + uint32_t Reserved0C; /* Reserved 900h + (ep_num * 20h) + 0Ch*/ + __IO uint32_t DIEPTSIZ; /* IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h*/ + __IO uint32_t DIEPDMA; /* IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h*/ + __IO uint32_t DTXFSTS;/*IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h*/ + uint32_t Reserved18; /* Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch*/ +} +USB_OTG_INEPREGS; +/** + * @} + */ + + +/** @defgroup __OUT_Endpoint-Specific_Registers + * @{ + */ +typedef struct _USB_OTG_OUTEPREGS +{ + __IO uint32_t DOEPCTL; /* dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h*/ + __IO uint32_t DOUTEPFRM; /* dev OUT Endpoint Frame number B00h + (ep_num * 20h) + 04h*/ + __IO uint32_t DOEPINT; /* dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h*/ + uint32_t Reserved0C; /* Reserved B00h + (ep_num * 20h) + 0Ch*/ + __IO uint32_t DOEPTSIZ; /* dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h*/ + __IO uint32_t DOEPDMA; /* dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h*/ + uint32_t Reserved18[2]; /* Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch*/ +} +USB_OTG_OUTEPREGS; +/** + * @} + */ + + +/** @defgroup __Host_Mode_Register_Structures + * @{ + */ +typedef struct _USB_OTG_HREGS +{ + __IO uint32_t HCFG; /* Host Configuration Register 400h*/ + __IO uint32_t HFIR; /* Host Frame Interval Register 404h*/ + __IO uint32_t HFNUM; /* Host Frame Nbr/Frame Remaining 408h*/ + uint32_t Reserved40C; /* Reserved 40Ch*/ + __IO uint32_t HPTXSTS; /* Host Periodic Tx FIFO/ Queue Status 410h*/ + __IO uint32_t HAINT; /* Host All Channels Interrupt Register 414h*/ + __IO uint32_t HAINTMSK; /* Host All Channels Interrupt Mask 418h*/ +} +USB_OTG_HREGS; +/** + * @} + */ + + +/** @defgroup __Host_Channel_Specific_Registers + * @{ + */ +typedef struct _USB_OTG_HC_REGS +{ + __IO uint32_t HCCHAR; + __IO uint32_t HCSPLT; + __IO uint32_t HCINT; + __IO uint32_t HCGINTMSK; + __IO uint32_t HCTSIZ; + __IO uint32_t HCDMA; + uint32_t Reserved[2]; +} +USB_OTG_HC_REGS; +/** + * @} + */ + + +/** @defgroup __otg_Core_registers + * @{ + */ +typedef struct USB_OTG_core_regs //000h +{ + USB_OTG_GREGS *GREGS; + USB_OTG_DREGS *DREGS; + USB_OTG_HREGS *HREGS; + USB_OTG_INEPREGS *INEP_REGS[USB_OTG_MAX_TX_FIFOS]; + USB_OTG_OUTEPREGS *OUTEP_REGS[USB_OTG_MAX_TX_FIFOS]; + USB_OTG_HC_REGS *HC_REGS[USB_OTG_MAX_TX_FIFOS]; + __IO uint32_t *HPRT0; + __IO uint32_t *DFIFO[USB_OTG_MAX_TX_FIFOS]; + __IO uint32_t *PCGCCTL; +} +USB_OTG_CORE_REGS , *PUSB_OTG_CORE_REGS; +typedef union _USB_OTG_OTGCTL_TypeDef +{ + uint32_t d32; + struct + { +uint32_t sesreqscs : + 1; +uint32_t sesreq : + 1; +uint32_t Reserved2_7 : + 6; +uint32_t hstnegscs : + 1; +uint32_t hnpreq : + 1; +uint32_t hstsethnpen : + 1; +uint32_t devhnpen : + 1; +uint32_t Reserved12_15 : + 4; +uint32_t conidsts : + 1; +uint32_t Reserved17 : + 1; +uint32_t asesvld : + 1; +uint32_t bsesvld : + 1; +uint32_t currmod : + 1; +uint32_t Reserved21_31 : + 11; + } + b; +} USB_OTG_OTGCTL_TypeDef ; +typedef union _USB_OTG_GOTGINT_TypeDef +{ + uint32_t d32; + struct + { +uint32_t Reserved0_1 : + 2; +uint32_t sesenddet : + 1; +uint32_t Reserved3_7 : + 5; +uint32_t sesreqsucstschng : + 1; +uint32_t hstnegsucstschng : + 1; +uint32_t reserver10_16 : + 7; +uint32_t hstnegdet : + 1; +uint32_t adevtoutchng : + 1; +uint32_t debdone : + 1; +uint32_t Reserved31_20 : + 12; + } + b; +} USB_OTG_GOTGINT_TypeDef ; +typedef union _USB_OTG_GAHBCFG_TypeDef +{ + uint32_t d32; + struct + { +uint32_t glblintrmsk : + 1; +uint32_t hburstlen : + 4; +uint32_t dmaenable : + 1; +uint32_t Reserved : + 1; +uint32_t nptxfemplvl_txfemplvl : + 1; +uint32_t ptxfemplvl : + 1; +uint32_t Reserved9_31 : + 23; + } + b; +} USB_OTG_GAHBCFG_TypeDef ; +typedef union _USB_OTG_GUSBCFG_TypeDef +{ + uint32_t d32; + struct + { +uint32_t toutcal : + 3; +uint32_t phyif : + 1; +uint32_t ulpi_utmi_sel : + 1; +uint32_t fsintf : + 1; +uint32_t physel : + 1; +uint32_t ddrsel : + 1; +uint32_t srpcap : + 1; +uint32_t hnpcap : + 1; +uint32_t usbtrdtim : + 4; +uint32_t nptxfrwnden : + 1; +uint32_t phylpwrclksel : + 1; +uint32_t otgutmifssel : + 1; +uint32_t ulpi_fsls : + 1; +uint32_t ulpi_auto_res : + 1; +uint32_t ulpi_clk_sus_m : + 1; +uint32_t ulpi_ext_vbus_drv : + 1; +uint32_t ulpi_int_vbus_indicator : + 1; +uint32_t term_sel_dl_pulse : + 1; +uint32_t Reserved : + 6; +uint32_t force_host : + 1; +uint32_t force_dev : + 1; +uint32_t corrupt_tx : + 1; + } + b; +} USB_OTG_GUSBCFG_TypeDef ; +typedef union _USB_OTG_GRSTCTL_TypeDef +{ + uint32_t d32; + struct + { +uint32_t csftrst : + 1; +uint32_t hsftrst : + 1; +uint32_t hstfrm : + 1; +uint32_t intknqflsh : + 1; +uint32_t rxfflsh : + 1; +uint32_t txfflsh : + 1; +uint32_t txfnum : + 5; +uint32_t Reserved11_29 : + 19; +uint32_t dmareq : + 1; +uint32_t ahbidle : + 1; + } + b; +} USB_OTG_GRSTCTL_TypeDef ; +typedef union _USB_OTG_GINTMSK_TypeDef +{ + uint32_t d32; + struct + { +uint32_t Reserved0 : + 1; +uint32_t modemismatch : + 1; +uint32_t otgintr : + 1; +uint32_t sofintr : + 1; +uint32_t rxstsqlvl : + 1; +uint32_t nptxfempty : + 1; +uint32_t ginnakeff : + 1; +uint32_t goutnakeff : + 1; +uint32_t Reserved8 : + 1; +uint32_t i2cintr : + 1; +uint32_t erlysuspend : + 1; +uint32_t usbsuspend : + 1; +uint32_t usbreset : + 1; +uint32_t enumdone : + 1; +uint32_t isooutdrop : + 1; +uint32_t eopframe : + 1; +uint32_t Reserved16 : + 1; +uint32_t epmismatch : + 1; +uint32_t inepintr : + 1; +uint32_t outepintr : + 1; +uint32_t incomplisoin : + 1; +uint32_t incomplisoout : + 1; +uint32_t Reserved22_23 : + 2; +uint32_t portintr : + 1; +uint32_t hcintr : + 1; +uint32_t ptxfempty : + 1; +uint32_t Reserved27 : + 1; +uint32_t conidstschng : + 1; +uint32_t disconnect : + 1; +uint32_t sessreqintr : + 1; +uint32_t wkupintr : + 1; + } + b; +} USB_OTG_GINTMSK_TypeDef ; +typedef union _USB_OTG_GINTSTS_TypeDef +{ + uint32_t d32; + struct + { +uint32_t curmode : + 1; +uint32_t modemismatch : + 1; +uint32_t otgintr : + 1; +uint32_t sofintr : + 1; +uint32_t rxstsqlvl : + 1; +uint32_t nptxfempty : + 1; +uint32_t ginnakeff : + 1; +uint32_t goutnakeff : + 1; +uint32_t Reserved8 : + 1; +uint32_t i2cintr : + 1; +uint32_t erlysuspend : + 1; +uint32_t usbsuspend : + 1; +uint32_t usbreset : + 1; +uint32_t enumdone : + 1; +uint32_t isooutdrop : + 1; +uint32_t eopframe : + 1; +uint32_t intimerrx : + 1; +uint32_t epmismatch : + 1; +uint32_t inepint: + 1; +uint32_t outepintr : + 1; +uint32_t incomplisoin : + 1; +uint32_t incomplisoout : + 1; +uint32_t Reserved22_23 : + 2; +uint32_t portintr : + 1; +uint32_t hcintr : + 1; +uint32_t ptxfempty : + 1; +uint32_t Reserved27 : + 1; +uint32_t conidstschng : + 1; +uint32_t disconnect : + 1; +uint32_t sessreqintr : + 1; +uint32_t wkupintr : + 1; + } + b; +} USB_OTG_GINTSTS_TypeDef ; +typedef union _USB_OTG_DRXSTS_TypeDef +{ + uint32_t d32; + struct + { +uint32_t epnum : + 4; +uint32_t bcnt : + 11; +uint32_t dpid : + 2; +uint32_t pktsts : + 4; +uint32_t fn : + 4; +uint32_t Reserved : + 7; + } + b; +} USB_OTG_DRXSTS_TypeDef ; +typedef union _USB_OTG_GRXSTS_TypeDef +{ + uint32_t d32; + struct + { +uint32_t chnum : + 4; +uint32_t bcnt : + 11; +uint32_t dpid : + 2; +uint32_t pktsts : + 4; +uint32_t Reserved : + 11; + } + b; +} USB_OTG_GRXFSTS_TypeDef ; +typedef union _USB_OTG_FSIZ_TypeDef +{ + uint32_t d32; + struct + { +uint32_t startaddr : + 16; +uint32_t depth : + 16; + } + b; +} USB_OTG_FSIZ_TypeDef ; +typedef union _USB_OTG_HNPTXSTS_TypeDef +{ + uint32_t d32; + struct + { +uint32_t nptxfspcavail : + 16; +uint32_t nptxqspcavail : + 8; +uint32_t nptxqtop_terminate : + 1; +uint32_t nptxqtop_timer : + 2; +uint32_t nptxqtop : + 2; +uint32_t chnum : + 2; +uint32_t Reserved : + 1; + } + b; +} USB_OTG_HNPTXSTS_TypeDef ; +typedef union _USB_OTG_DTXFSTSn_TypeDef +{ + uint32_t d32; + struct + { +uint32_t txfspcavail : + 16; +uint32_t Reserved : + 16; + } + b; +} USB_OTG_DTXFSTSn_TypeDef ; +typedef union _USB_OTG_GI2CCTL_TypeDef +{ + uint32_t d32; + struct + { +uint32_t rwdata : + 8; +uint32_t regaddr : + 8; +uint32_t addr : + 7; +uint32_t i2cen : + 1; +uint32_t ack : + 1; +uint32_t i2csuspctl : + 1; +uint32_t i2cdevaddr : + 2; +uint32_t dat_se0: + 1; +uint32_t Reserved : + 1; +uint32_t rw : + 1; +uint32_t bsydne : + 1; + } + b; +} USB_OTG_GI2CCTL_TypeDef ; +typedef union _USB_OTG_GCCFG_TypeDef +{ + uint32_t d32; + struct + { +uint32_t Reserved_in : + 16; +uint32_t pwdn : + 1; +uint32_t i2cifen : + 1; +uint32_t vbussensingA : + 1; +uint32_t vbussensingB : + 1; +uint32_t sofouten : + 1; +uint32_t disablevbussensing : + 1; +uint32_t Reserved_out : + 10; + } + b; +} USB_OTG_GCCFG_TypeDef ; + +typedef union _USB_OTG_DCFG_TypeDef +{ + uint32_t d32; + struct + { +uint32_t devspd : + 2; +uint32_t nzstsouthshk : + 1; +uint32_t Reserved3 : + 1; +uint32_t devaddr : + 7; +uint32_t perfrint : + 2; +uint32_t Reserved13_17 : + 5; +uint32_t epmscnt : + 4; + } + b; +} USB_OTG_DCFG_TypeDef ; +typedef union _USB_OTG_DCTL_TypeDef +{ + uint32_t d32; + struct + { +uint32_t rmtwkupsig : + 1; +uint32_t sftdiscon : + 1; +uint32_t gnpinnaksts : + 1; +uint32_t goutnaksts : + 1; +uint32_t tstctl : + 3; +uint32_t sgnpinnak : + 1; +uint32_t cgnpinnak : + 1; +uint32_t sgoutnak : + 1; +uint32_t cgoutnak : + 1; +uint32_t Reserved : + 21; + } + b; +} USB_OTG_DCTL_TypeDef ; +typedef union _USB_OTG_DSTS_TypeDef +{ + uint32_t d32; + struct + { +uint32_t suspsts : + 1; +uint32_t enumspd : + 2; +uint32_t errticerr : + 1; +uint32_t Reserved4_7: + 4; +uint32_t soffn : + 14; +uint32_t Reserved22_31 : + 10; + } + b; +} USB_OTG_DSTS_TypeDef ; +typedef union _USB_OTG_DIEPINTn_TypeDef +{ + uint32_t d32; + struct + { +uint32_t xfercompl : + 1; +uint32_t epdisabled : + 1; +uint32_t ahberr : + 1; +uint32_t timeout : + 1; +uint32_t intktxfemp : + 1; +uint32_t intknepmis : + 1; +uint32_t inepnakeff : + 1; +uint32_t emptyintr : + 1; +uint32_t txfifoundrn : + 1; +uint32_t Reserved08_31 : + 23; + } + b; +} USB_OTG_DIEPINTn_TypeDef ; +typedef union _USB_OTG_DIEPINTn_TypeDef USB_OTG_DIEPMSK_TypeDef ; +typedef union _USB_OTG_DOEPINTn_TypeDef +{ + uint32_t d32; + struct + { +uint32_t xfercompl : + 1; +uint32_t epdisabled : + 1; +uint32_t ahberr : + 1; +uint32_t setup : + 1; +uint32_t Reserved04_31 : + 28; + } + b; +} USB_OTG_DOEPINTn_TypeDef ; +typedef union _USB_OTG_DOEPINTn_TypeDef USB_OTG_DOEPMSK_TypeDef ; + +typedef union _USB_OTG_DAINT_TypeDef +{ + uint32_t d32; + struct + { +uint32_t in : + 16; +uint32_t out : + 16; + } + ep; +} USB_OTG_DAINT_TypeDef ; + +typedef union _USB_OTG_DTHRCTL_TypeDef +{ + uint32_t d32; + struct + { +uint32_t non_iso_thr_en : + 1; +uint32_t iso_thr_en : + 1; +uint32_t tx_thr_len : + 9; +uint32_t Reserved11_15 : + 5; +uint32_t rx_thr_en : + 1; +uint32_t rx_thr_len : + 9; +uint32_t Reserved26_31 : + 6; + } + b; +} USB_OTG_DTHRCTL_TypeDef ; +typedef union _USB_OTG_DEPCTL_TypeDef +{ + uint32_t d32; + struct + { +uint32_t mps : + 11; +uint32_t reserved : + 4; +uint32_t usbactep : + 1; +uint32_t dpid : + 1; +uint32_t naksts : + 1; +uint32_t eptype : + 2; +uint32_t snp : + 1; +uint32_t stall : + 1; +uint32_t txfnum : + 4; +uint32_t cnak : + 1; +uint32_t snak : + 1; +uint32_t setd0pid : + 1; +uint32_t setd1pid : + 1; +uint32_t epdis : + 1; +uint32_t epena : + 1; + } + b; +} USB_OTG_DEPCTL_TypeDef ; +typedef union _USB_OTG_DEPXFRSIZ_TypeDef +{ + uint32_t d32; + struct + { +uint32_t xfersize : + 19; +uint32_t pktcnt : + 10; +uint32_t mc : + 2; +uint32_t Reserved : + 1; + } + b; +} USB_OTG_DEPXFRSIZ_TypeDef ; +typedef union _USB_OTG_DEP0XFRSIZ_TypeDef +{ + uint32_t d32; + struct + { +uint32_t xfersize : + 7; +uint32_t Reserved7_18 : + 12; +uint32_t pktcnt : + 2; +uint32_t Reserved20_28 : + 9; +uint32_t supcnt : + 2; + uint32_t Reserved31; + } + b; +} USB_OTG_DEP0XFRSIZ_TypeDef ; +typedef union _USB_OTG_HCFG_TypeDef +{ + uint32_t d32; + struct + { +uint32_t fslspclksel : + 2; +uint32_t fslssupp : + 1; + } + b; +} USB_OTG_HCFG_TypeDef ; +typedef union _USB_OTG_HFRMINTRVL_TypeDef +{ + uint32_t d32; + struct + { +uint32_t frint : + 16; +uint32_t Reserved : + 16; + } + b; +} USB_OTG_HFRMINTRVL_TypeDef ; + +typedef union _USB_OTG_HFNUM_TypeDef +{ + uint32_t d32; + struct + { +uint32_t frnum : + 16; +uint32_t frrem : + 16; + } + b; +} USB_OTG_HFNUM_TypeDef ; +typedef union _USB_OTG_HPTXSTS_TypeDef +{ + uint32_t d32; + struct + { +uint32_t ptxfspcavail : + 16; +uint32_t ptxqspcavail : + 8; +uint32_t ptxqtop_terminate : + 1; +uint32_t ptxqtop_timer : + 2; +uint32_t ptxqtop : + 2; +uint32_t chnum : + 2; +uint32_t ptxqtop_odd : + 1; + } + b; +} USB_OTG_HPTXSTS_TypeDef ; +typedef union _USB_OTG_HPRT0_TypeDef +{ + uint32_t d32; + struct + { +uint32_t prtconnsts : + 1; +uint32_t prtconndet : + 1; +uint32_t prtena : + 1; +uint32_t prtenchng : + 1; +uint32_t prtovrcurract : + 1; +uint32_t prtovrcurrchng : + 1; +uint32_t prtres : + 1; +uint32_t prtsusp : + 1; +uint32_t prtrst : + 1; +uint32_t Reserved9 : + 1; +uint32_t prtlnsts : + 2; +uint32_t prtpwr : + 1; +uint32_t prttstctl : + 4; +uint32_t prtspd : + 2; +uint32_t Reserved19_31 : + 13; + } + b; +} USB_OTG_HPRT0_TypeDef ; +typedef union _USB_OTG_HAINT_TypeDef +{ + uint32_t d32; + struct + { +uint32_t chint : + 16; +uint32_t Reserved : + 16; + } + b; +} USB_OTG_HAINT_TypeDef ; +typedef union _USB_OTG_HAINTMSK_TypeDef +{ + uint32_t d32; + struct + { +uint32_t chint : + 16; +uint32_t Reserved : + 16; + } + b; +} USB_OTG_HAINTMSK_TypeDef ; +typedef union _USB_OTG_HCCHAR_TypeDef +{ + uint32_t d32; + struct + { +uint32_t mps : + 11; +uint32_t epnum : + 4; +uint32_t epdir : + 1; +uint32_t Reserved : + 1; +uint32_t lspddev : + 1; +uint32_t eptype : + 2; +uint32_t multicnt : + 2; +uint32_t devaddr : + 7; +uint32_t oddfrm : + 1; +uint32_t chdis : + 1; +uint32_t chen : + 1; + } + b; +} USB_OTG_HCCHAR_TypeDef ; +typedef union _USB_OTG_HCSPLT_TypeDef +{ + uint32_t d32; + struct + { +uint32_t prtaddr : + 7; +uint32_t hubaddr : + 7; +uint32_t xactpos : + 2; +uint32_t compsplt : + 1; +uint32_t Reserved : + 14; +uint32_t spltena : + 1; + } + b; +} USB_OTG_HCSPLT_TypeDef ; +typedef union _USB_OTG_HCINTn_TypeDef +{ + uint32_t d32; + struct + { +uint32_t xfercompl : + 1; +uint32_t chhltd : + 1; +uint32_t ahberr : + 1; +uint32_t stall : + 1; +uint32_t nak : + 1; +uint32_t ack : + 1; +uint32_t nyet : + 1; +uint32_t xacterr : + 1; +uint32_t bblerr : + 1; +uint32_t frmovrun : + 1; +uint32_t datatglerr : + 1; +uint32_t Reserved : + 21; + } + b; +} USB_OTG_HCINTn_TypeDef ; +typedef union _USB_OTG_HCTSIZn_TypeDef +{ + uint32_t d32; + struct + { +uint32_t xfersize : + 19; +uint32_t pktcnt : + 10; +uint32_t pid : + 2; +uint32_t dopng : + 1; + } + b; +} USB_OTG_HCTSIZn_TypeDef ; +typedef union _USB_OTG_HCGINTMSK_TypeDef +{ + uint32_t d32; + struct + { +uint32_t xfercompl : + 1; +uint32_t chhltd : + 1; +uint32_t ahberr : + 1; +uint32_t stall : + 1; +uint32_t nak : + 1; +uint32_t ack : + 1; +uint32_t nyet : + 1; +uint32_t xacterr : + 1; +uint32_t bblerr : + 1; +uint32_t frmovrun : + 1; +uint32_t datatglerr : + 1; +uint32_t Reserved : + 21; + } + b; +} USB_OTG_HCGINTMSK_TypeDef ; +typedef union _USB_OTG_PCGCCTL_TypeDef +{ + uint32_t d32; + struct + { +uint32_t stoppclk : + 1; +uint32_t gatehclk : + 1; +uint32_t Reserved : + 30; + } + b; +} USB_OTG_PCGCCTL_TypeDef ; + +/** + * @} + */ + + +/** @defgroup USB_REGS_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_REGS_Exported_Variables + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_REGS_Exported_FunctionsPrototype + * @{ + */ +/** + * @} + */ + + +#endif //__USB_OTG_REGS_H__ + + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_bsp_template.c b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_bsp_template.c new file mode 100644 index 000000000..ebd89b909 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_bsp_template.c @@ -0,0 +1,200 @@ +/** + ****************************************************************************** + * @file usb_bsp.c + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief This file is responsible to offer board support package and is + * configurable by user. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_bsp.h" + +/** @addtogroup USB_OTG_DRIVER +* @{ +*/ + +/** @defgroup USB_BSP + * @brief This file is responsible to offer board support package + * @{ + */ + +/** @defgroup USB_BSP_Private_Defines + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_BSP_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + + + + + +/** @defgroup USB_BSP_Private_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USBH_BSP_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup USBH_BSP_Private_FunctionPrototypes + * @{ + */ +/** + * @} + */ + +/** @defgroup USB_BSP_Private_Functions + * @{ + */ + + +/** + * @brief USB_OTG_BSP_Init + * Initilizes BSP configurations + * @param None + * @retval None + */ + +void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev) +{ + +} +/** + * @brief USB_OTG_BSP_EnableInterrupt + * Enabele USB Global interrupt + * @param None + * @retval None + */ +void USB_OTG_BSP_EnableInterrupt(USB_OTG_CORE_HANDLE *pdev) +{ + +} + +/** + * @brief BSP_Drive_VBUS + * Drives the Vbus signal through IO + * @param speed : Full, Low + * @param state : VBUS states + * @retval None + */ + +void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev, uint8_t state) +{ + +} + +/** + * @brief USB_OTG_BSP_ConfigVBUS + * Configures the IO for the Vbus and OverCurrent + * @param Speed : Full, Low + * @retval None + */ + +void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev) +{ + +} + +/** + * @brief USB_OTG_BSP_TimeInit + * Initialises delay unit Systick timer /Timer2 + * @param None + * @retval None + */ +void USB_OTG_BSP_TimeInit ( void ) +{ + +} + +/** + * @brief USB_OTG_BSP_uDelay + * This function provides delay time in micro sec + * @param usec : Value of delay required in micro sec + * @retval None + */ +void USB_OTG_BSP_uDelay (const uint32_t usec) +{ + + uint32_t count = 0; + const uint32_t utime = (120 * usec / 7); + do + { + if ( ++count > utime ) + { + return ; + } + } + while (1); + +} + + +/** + * @brief USB_OTG_BSP_mDelay + * This function provides delay time in milli sec + * @param msec : Value of delay required in milli sec + * @retval None + */ +void USB_OTG_BSP_mDelay (const uint32_t msec) +{ + + USB_OTG_BSP_uDelay(msec * 1000); + +} + + +/** + * @brief USB_OTG_BSP_TimerIRQ + * Time base IRQ + * @param None + * @retval None + */ + +void USB_OTG_BSP_TimerIRQ (void) +{ + +} + +/** +* @} +*/ + +/** +* @} +*/ + +/** +* @} +*/ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_core.c b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_core.c new file mode 100644 index 000000000..74e432ac2 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_core.c @@ -0,0 +1,2187 @@ +/** + ****************************************************************************** + * @file usb_core.c + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief USB-OTG Core Layer + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_core.h" +#include "usb_bsp.h" + + +/** @addtogroup USB_OTG_DRIVER +* @{ +*/ + +/** @defgroup USB_CORE +* @brief This file includes the USB-OTG Core Layer +* @{ +*/ + + +/** @defgroup USB_CORE_Private_Defines +* @{ +*/ + +/** +* @} +*/ + + +/** @defgroup USB_CORE_Private_TypesDefinitions +* @{ +*/ +/** +* @} +*/ + + + +/** @defgroup USB_CORE_Private_Macros +* @{ +*/ +/** +* @} +*/ + + +/** @defgroup USB_CORE_Private_Variables +* @{ +*/ +/** +* @} +*/ + + +/** @defgroup USB_CORE_Private_FunctionPrototypes +* @{ +*/ +/** +* @} +*/ + + +/** @defgroup USB_CORE_Private_Functions +* @{ +*/ + +/** +* @brief USB_OTG_EnableCommonInt +* Initializes the commmon interrupts, used in both device and modes +* @param pdev : Selected device +* @retval None +*/ +static void USB_OTG_EnableCommonInt(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTMSK_TypeDef int_mask; + + int_mask.d32 = 0; + /* Clear any pending USB_OTG Interrupts */ +#ifndef USE_OTG_MODE + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GOTGINT, 0xFFFFFFFF); +#endif + /* Clear any pending interrupts */ + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xFFFFFFFF); + /* Enable the interrupts in the INTMSK */ + int_mask.b.wkupintr = 1; + int_mask.b.usbsuspend = 1; + +#ifdef USE_OTG_MODE + int_mask.b.otgintr = 1; + int_mask.b.sessreqintr = 1; + int_mask.b.conidstschng = 1; +#endif + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTMSK, int_mask.d32); +} + +/** +* @brief USB_OTG_CoreReset : Soft reset of the core +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +static USB_OTG_STS USB_OTG_CoreReset(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_STS status = USB_OTG_OK; + __IO USB_OTG_GRSTCTL_TypeDef greset; + uint32_t count = 0; + + greset.d32 = 0; + /* Wait for AHB master IDLE state. */ + do + { + USB_OTG_BSP_uDelay(3); + greset.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GRSTCTL); + if (++count > 200000) + { + return USB_OTG_OK; + } + } + while (greset.b.ahbidle == 0); + /* Core Soft Reset */ + count = 0; + greset.b.csftrst = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRSTCTL, greset.d32 ); + do + { + greset.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GRSTCTL); + if (++count > 200000) + { + break; + } + } + while (greset.b.csftrst == 1); + /* Wait for 3 PHY Clocks*/ + USB_OTG_BSP_uDelay(3); + return status; +} + +/** +* @brief USB_OTG_WritePacket : Writes a packet into the Tx FIFO associated +* with the EP +* @param pdev : Selected device +* @param src : source pointer +* @param ch_ep_num : end point number +* @param bytes : No. of bytes +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_WritePacket(USB_OTG_CORE_HANDLE *pdev, + uint8_t *src, + uint8_t ch_ep_num, + uint16_t len) +{ + USB_OTG_STS status = USB_OTG_OK; + if (pdev->cfg.dma_enable == 0) + { + uint32_t count32b= 0 , i= 0; + __IO uint32_t *fifo; + + count32b = (len + 3) / 4; + fifo = pdev->regs.DFIFO[ch_ep_num]; + for (i = 0; i < count32b; i++, src+=4) + { + USB_OTG_WRITE_REG32( fifo, *((__packed uint32_t *)src) ); + } + } + return status; +} + + +/** +* @brief USB_OTG_ReadPacket : Reads a packet from the Rx FIFO +* @param pdev : Selected device +* @param dest : Destination Pointer +* @param bytes : No. of bytes +* @retval None +*/ +void *USB_OTG_ReadPacket(USB_OTG_CORE_HANDLE *pdev, + uint8_t *dest, + uint16_t len) +{ + uint32_t i=0; + uint32_t count32b = (len + 3) / 4; + + __IO uint32_t *fifo = pdev->regs.DFIFO[0]; + + for ( i = 0; i < count32b; i++, dest += 4 ) + { + *(__packed uint32_t *)dest = USB_OTG_READ_REG32(fifo); + + } + return ((void *)dest); +} + +/** +* @brief USB_OTG_SelectCore +* Initialize core registers address. +* @param pdev : Selected device +* @param coreID : USB OTG Core ID +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_SelectCore(USB_OTG_CORE_HANDLE *pdev, + USB_OTG_CORE_ID_TypeDef coreID) +{ + uint32_t i , baseAddress = 0; + USB_OTG_STS status = USB_OTG_OK; + + pdev->cfg.dma_enable = 0; + + /* at startup the core is in FS mode */ + pdev->cfg.speed = USB_OTG_SPEED_FULL; + pdev->cfg.mps = USB_OTG_FS_MAX_PACKET_SIZE ; + + /* initialize device cfg following its address */ + if (coreID == USB_OTG_FS_CORE_ID) + { + baseAddress = USB_OTG_FS_BASE_ADDR; + pdev->cfg.coreID = USB_OTG_FS_CORE_ID; + pdev->cfg.host_channels = 8 ; + pdev->cfg.dev_endpoints = 4 ; + pdev->cfg.TotalFifoSize = 320; /* in 32-bits */ + pdev->cfg.phy_itface = USB_OTG_EMBEDDED_PHY; + +#ifdef USB_OTG_FS_SOF_OUTPUT_ENABLED + pdev->cfg.Sof_output = 1; +#endif + +#ifdef USB_OTG_FS_LOW_PWR_MGMT_SUPPORT + pdev->cfg.low_power = 1; +#endif + } + else if (coreID == USB_OTG_HS_CORE_ID) + { + baseAddress = USB_OTG_HS_BASE_ADDR; + pdev->cfg.coreID = USB_OTG_HS_CORE_ID; + pdev->cfg.host_channels = 12 ; + pdev->cfg.dev_endpoints = 6 ; + pdev->cfg.TotalFifoSize = 1280;/* in 32-bits */ + +#ifdef USB_OTG_ULPI_PHY_ENABLED + pdev->cfg.phy_itface = USB_OTG_ULPI_PHY; +#else + #ifdef USB_OTG_EMBEDDED_PHY_ENABLED + pdev->cfg.phy_itface = USB_OTG_EMBEDDED_PHY; + #else + #ifdef USB_OTG_I2C_PHY_ENABLED + pdev->cfg.phy_itface = USB_OTG_I2C_PHY; + #endif + #endif +#endif + +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED + pdev->cfg.dma_enable = 1; +#endif + +#ifdef USB_OTG_HS_SOF_OUTPUT_ENABLED + pdev->cfg.Sof_output = 1; +#endif + +#ifdef USB_OTG_HS_LOW_PWR_MGMT_SUPPORT + pdev->cfg.low_power = 1; +#endif + + } + + pdev->regs.GREGS = (USB_OTG_GREGS *)(baseAddress + \ + USB_OTG_CORE_GLOBAL_REGS_OFFSET); + pdev->regs.DREGS = (USB_OTG_DREGS *) (baseAddress + \ + USB_OTG_DEV_GLOBAL_REG_OFFSET); + + for (i = 0; i < pdev->cfg.dev_endpoints; i++) + { + pdev->regs.INEP_REGS[i] = (USB_OTG_INEPREGS *) \ + (baseAddress + USB_OTG_DEV_IN_EP_REG_OFFSET + \ + (i * USB_OTG_EP_REG_OFFSET)); + pdev->regs.OUTEP_REGS[i] = (USB_OTG_OUTEPREGS *) \ + (baseAddress + USB_OTG_DEV_OUT_EP_REG_OFFSET + \ + (i * USB_OTG_EP_REG_OFFSET)); + } + pdev->regs.HREGS = (USB_OTG_HREGS *)(baseAddress + \ + USB_OTG_HOST_GLOBAL_REG_OFFSET); + pdev->regs.HPRT0 = (uint32_t *)(baseAddress + USB_OTG_HOST_PORT_REGS_OFFSET); + + for (i = 0; i < pdev->cfg.host_channels; i++) + { + pdev->regs.HC_REGS[i] = (USB_OTG_HC_REGS *)(baseAddress + \ + USB_OTG_HOST_CHAN_REGS_OFFSET + \ + (i * USB_OTG_CHAN_REGS_OFFSET)); + } + for (i = 0; i < pdev->cfg.host_channels; i++) + { + pdev->regs.DFIFO[i] = (uint32_t *)(baseAddress + USB_OTG_DATA_FIFO_OFFSET +\ + (i * USB_OTG_DATA_FIFO_SIZE)); + } + pdev->regs.PCGCCTL = (uint32_t *)(baseAddress + USB_OTG_PCGCCTL_OFFSET); + + return status; +} + + +/** +* @brief USB_OTG_CoreInit +* Initializes the USB_OTG controller registers and prepares the core +* device mode or host mode operation. +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_GUSBCFG_TypeDef usbcfg; + USB_OTG_GCCFG_TypeDef gccfg; + USB_OTG_GI2CCTL_TypeDef i2cctl; + USB_OTG_GAHBCFG_TypeDef ahbcfg; + + usbcfg.d32 = 0; + gccfg.d32 = 0; + ahbcfg.d32 = 0; + + + + if (pdev->cfg.phy_itface == USB_OTG_ULPI_PHY) + { + gccfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GCCFG); + gccfg.b.pwdn = 0; + + if (pdev->cfg.Sof_output) + { + gccfg.b.sofouten = 1; + } + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GCCFG, gccfg.d32); + + /* Init The ULPI Interface */ + usbcfg.d32 = 0; + usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG); + + usbcfg.b.physel = 0; /* HS Interface */ +#ifdef USB_OTG_INTERNAL_VBUS_ENABLED + usbcfg.b.ulpi_ext_vbus_drv = 0; /* Use internal VBUS */ +#else + #ifdef USB_OTG_EXTERNAL_VBUS_ENABLED + usbcfg.b.ulpi_ext_vbus_drv = 1; /* Use external VBUS */ + #endif +#endif + usbcfg.b.term_sel_dl_pulse = 0; /* Data line pulsing using utmi_txvalid */ + usbcfg.b.ulpi_utmi_sel = 1; /* ULPI seleInterfacect */ + + usbcfg.b.phyif = 0; /* 8 bits */ + usbcfg.b.ddrsel = 0; /* single data rate */ + + usbcfg.b.ulpi_fsls = 0; + usbcfg.b.ulpi_clk_sus_m = 0; + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GUSBCFG, usbcfg.d32); + + /* Reset after a PHY select */ + USB_OTG_CoreReset(pdev); + + if(pdev->cfg.dma_enable == 1) + { + + ahbcfg.b.hburstlen = 5; /* 64 x 32-bits*/ + ahbcfg.b.dmaenable = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GAHBCFG, ahbcfg.d32); + + } + } + else /* FS interface (embedded Phy or I2C Phy) */ + { + + usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);; + usbcfg.b.physel = 1; /* FS Interface */ + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GUSBCFG, usbcfg.d32); + /* Reset after a PHY select and set Host mode */ + USB_OTG_CoreReset(pdev); + /* Enable the I2C interface and deactivate the power down*/ + gccfg.d32 = 0; + gccfg.b.pwdn = 1; + + if(pdev->cfg.phy_itface == USB_OTG_I2C_PHY) + { + gccfg.b.i2cifen = 1; + } + gccfg.b.vbussensingA = 1 ; + gccfg.b.vbussensingB = 1 ; +#ifndef VBUS_SENSING_ENABLED + gccfg.b.disablevbussensing = 1; +#endif + + if(pdev->cfg.Sof_output) + { + gccfg.b.sofouten = 1; + } + + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GCCFG, gccfg.d32); + USB_OTG_BSP_mDelay(20); + /* Program GUSBCFG.OtgUtmifsSel to I2C*/ + usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG); + + if(pdev->cfg.phy_itface == USB_OTG_I2C_PHY) + { + usbcfg.b.otgutmifssel = 1; + } + + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GUSBCFG, usbcfg.d32); + + if(pdev->cfg.phy_itface == USB_OTG_I2C_PHY) + { + /*Program GI2CCTL.I2CEn*/ + i2cctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GI2CCTL); + i2cctl.b.i2cdevaddr = 1; + i2cctl.b.i2cen = 0; + i2cctl.b.dat_se0 = 1; + i2cctl.b.addr = 0x2D; + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GI2CCTL, i2cctl.d32); + + USB_OTG_BSP_mDelay(200); + + i2cctl.b.i2cen = 1; + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GI2CCTL, i2cctl.d32); + USB_OTG_BSP_mDelay(200); + } + } + /* case the HS core is working in FS mode */ + if(pdev->cfg.dma_enable == 1) + { + + ahbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GAHBCFG); + ahbcfg.b.hburstlen = 5; /* 64 x 32-bits*/ + ahbcfg.b.dmaenable = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GAHBCFG, ahbcfg.d32); + + } + /* initialize OTG features */ +#ifdef USE_OTG_MODE + usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG); + usbcfg.b.hnpcap = 1; + usbcfg.b.srpcap = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, usbcfg.d32); + USB_OTG_EnableCommonInt(pdev); +#endif + return status; +} +/** +* @brief USB_OTG_EnableGlobalInt +* Enables the controller's Global Int in the AHB Config reg +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_EnableGlobalInt(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_GAHBCFG_TypeDef ahbcfg; + + ahbcfg.d32 = 0; + ahbcfg.b.glblintrmsk = 1; /* Enable interrupts */ + USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GAHBCFG, 0, ahbcfg.d32); + return status; +} + + +/** +* @brief USB_OTG_DisableGlobalInt +* Enables the controller's Global Int in the AHB Config reg +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_DisableGlobalInt(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_GAHBCFG_TypeDef ahbcfg; + ahbcfg.d32 = 0; + ahbcfg.b.glblintrmsk = 1; /* Enable interrupts */ + USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GAHBCFG, ahbcfg.d32, 0); + return status; +} + + +/** +* @brief USB_OTG_FlushTxFifo : Flush a Tx FIFO +* @param pdev : Selected device +* @param num : FO num +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_FlushTxFifo (USB_OTG_CORE_HANDLE *pdev , uint32_t num ) +{ + USB_OTG_STS status = USB_OTG_OK; + __IO USB_OTG_GRSTCTL_TypeDef greset; + + uint32_t count = 0; + greset.d32 = 0; + greset.b.txfflsh = 1; + greset.b.txfnum = num; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GRSTCTL, greset.d32 ); + do + { + greset.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GRSTCTL); + if (++count > 200000) + { + break; + } + } + while (greset.b.txfflsh == 1); + /* Wait for 3 PHY Clocks*/ + USB_OTG_BSP_uDelay(3); + return status; +} + + +/** +* @brief USB_OTG_FlushRxFifo : Flush a Rx FIFO +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_FlushRxFifo( USB_OTG_CORE_HANDLE *pdev ) +{ + USB_OTG_STS status = USB_OTG_OK; + __IO USB_OTG_GRSTCTL_TypeDef greset; + uint32_t count = 0; + + greset.d32 = 0; + greset.b.rxfflsh = 1; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GRSTCTL, greset.d32 ); + do + { + greset.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GRSTCTL); + if (++count > 200000) + { + break; + } + } + while (greset.b.rxfflsh == 1); + /* Wait for 3 PHY Clocks*/ + USB_OTG_BSP_uDelay(3); + return status; +} + + +/** +* @brief USB_OTG_SetCurrentMode : Set ID line +* @param pdev : Selected device +* @param mode : (Host/device) +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_SetCurrentMode(USB_OTG_CORE_HANDLE *pdev , uint8_t mode) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_GUSBCFG_TypeDef usbcfg; + + usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG); + + usbcfg.b.force_host = 0; + usbcfg.b.force_dev = 0; + + if ( mode == HOST_MODE) + { + usbcfg.b.force_host = 1; + } + else if ( mode == DEVICE_MODE) + { + usbcfg.b.force_dev = 1; + } + + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, usbcfg.d32); + USB_OTG_BSP_mDelay(50); + return status; +} + + +/** +* @brief USB_OTG_GetMode : Get current mode +* @param pdev : Selected device +* @retval current mode +*/ +uint32_t USB_OTG_GetMode(USB_OTG_CORE_HANDLE *pdev) +{ + return (USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTSTS ) & 0x1); +} + + +/** +* @brief USB_OTG_IsDeviceMode : Check if it is device mode +* @param pdev : Selected device +* @retval num_in_ep +*/ +uint8_t USB_OTG_IsDeviceMode(USB_OTG_CORE_HANDLE *pdev) +{ + return (USB_OTG_GetMode(pdev) != HOST_MODE); +} + + +/** +* @brief USB_OTG_IsHostMode : Check if it is host mode +* @param pdev : Selected device +* @retval num_in_ep +*/ +uint8_t USB_OTG_IsHostMode(USB_OTG_CORE_HANDLE *pdev) +{ + return (USB_OTG_GetMode(pdev) == HOST_MODE); +} + + +/** +* @brief USB_OTG_ReadCoreItr : returns the Core Interrupt register +* @param pdev : Selected device +* @retval Status +*/ +uint32_t USB_OTG_ReadCoreItr(USB_OTG_CORE_HANDLE *pdev) +{ + uint32_t v = 0; + v = USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTSTS); + v &= USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTMSK); + return v; +} + + +/** +* @brief USB_OTG_ReadOtgItr : returns the USB_OTG Interrupt register +* @param pdev : Selected device +* @retval Status +*/ +uint32_t USB_OTG_ReadOtgItr (USB_OTG_CORE_HANDLE *pdev) +{ + return (USB_OTG_READ_REG32 (&pdev->regs.GREGS->GOTGINT)); +} + +#ifdef USE_HOST_MODE +/** +* @brief USB_OTG_CoreInitHost : Initializes USB_OTG controller for host mode +* @param pdev : Selected device +* @retval status +*/ +USB_OTG_STS USB_OTG_CoreInitHost(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_FSIZ_TypeDef nptxfifosize; + USB_OTG_FSIZ_TypeDef ptxfifosize; + USB_OTG_HCFG_TypeDef hcfg; + +#ifdef USE_OTG_MODE + USB_OTG_OTGCTL_TypeDef gotgctl; +#endif + + uint32_t i = 0; + + nptxfifosize.d32 = 0; + ptxfifosize.d32 = 0; +#ifdef USE_OTG_MODE + gotgctl.d32 = 0; +#endif + hcfg.d32 = 0; + + + /* configure charge pump IO */ + USB_OTG_BSP_ConfigVBUS(pdev); + + /* Restart the Phy Clock */ + USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, 0); + + /* Initialize Host Configuration Register */ + USB_OTG_InitFSLSPClkSel(pdev , HCFG_48_MHZ); /* in init phase */ + + hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG); + hcfg.b.fslssupp = 0; + USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HCFG, hcfg.d32); + + /* Configure data FIFO sizes */ + /* Rx FIFO */ +#ifdef USB_OTG_FS_CORE + if(pdev->cfg.coreID == USB_OTG_FS_CORE_ID) + { + /* set Rx FIFO size */ + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRXFSIZ, RX_FIFO_FS_SIZE); + nptxfifosize.b.startaddr = RX_FIFO_FS_SIZE; + nptxfifosize.b.depth = TXH_NP_FS_FIFOSIZ; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->DIEPTXF0_HNPTXFSIZ, nptxfifosize.d32); + + ptxfifosize.b.startaddr = RX_FIFO_FS_SIZE + TXH_NP_FS_FIFOSIZ; + ptxfifosize.b.depth = TXH_P_FS_FIFOSIZ; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->HPTXFSIZ, ptxfifosize.d32); + } +#endif +#ifdef USB_OTG_HS_CORE + if (pdev->cfg.coreID == USB_OTG_HS_CORE_ID) + { + /* set Rx FIFO size */ + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRXFSIZ, RX_FIFO_HS_SIZE); + nptxfifosize.b.startaddr = RX_FIFO_HS_SIZE; + nptxfifosize.b.depth = TXH_NP_HS_FIFOSIZ; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->DIEPTXF0_HNPTXFSIZ, nptxfifosize.d32); + + ptxfifosize.b.startaddr = RX_FIFO_HS_SIZE + TXH_NP_HS_FIFOSIZ; + ptxfifosize.b.depth = TXH_P_HS_FIFOSIZ; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->HPTXFSIZ, ptxfifosize.d32); + } +#endif + +#ifdef USE_OTG_MODE + /* Clear Host Set HNP Enable in the USB_OTG Control Register */ + gotgctl.b.hstsethnpen = 1; + USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GOTGCTL, gotgctl.d32, 0); +#endif + + /* Make sure the FIFOs are flushed. */ + USB_OTG_FlushTxFifo(pdev, 0x10 ); /* all Tx FIFOs */ + USB_OTG_FlushRxFifo(pdev); + + + /* Clear all pending HC Interrupts */ + for (i = 0; i < pdev->cfg.host_channels; i++) + { + USB_OTG_WRITE_REG32( &pdev->regs.HC_REGS[i]->HCINT, 0xFFFFFFFF ); + USB_OTG_WRITE_REG32( &pdev->regs.HC_REGS[i]->HCGINTMSK, 0 ); + } +#ifndef USE_OTG_MODE + USB_OTG_DriveVbus(pdev, 1); +#endif + + USB_OTG_EnableHostInt(pdev); + return status; +} + +/** +* @brief USB_OTG_IsEvenFrame +* This function returns the frame number for sof packet +* @param pdev : Selected device +* @retval Frame number +*/ +uint8_t USB_OTG_IsEvenFrame (USB_OTG_CORE_HANDLE *pdev) +{ + return !(USB_OTG_READ_REG32(&pdev->regs.HREGS->HFNUM) & 0x1); +} + +/** +* @brief USB_OTG_DriveVbus : set/reset vbus +* @param pdev : Selected device +* @param state : VBUS state +* @retval None +*/ +void USB_OTG_DriveVbus (USB_OTG_CORE_HANDLE *pdev, uint8_t state) +{ + USB_OTG_HPRT0_TypeDef hprt0; + + hprt0.d32 = 0; + + /* enable disable the external charge pump */ + USB_OTG_BSP_DriveVBUS(pdev, state); + + /* Turn on the Host port power. */ + hprt0.d32 = USB_OTG_ReadHPRT0(pdev); + if ((hprt0.b.prtpwr == 0 ) && (state == 1 )) + { + hprt0.b.prtpwr = 1; + USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32); + } + if ((hprt0.b.prtpwr == 1 ) && (state == 0 )) + { + hprt0.b.prtpwr = 0; + USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32); + } + + USB_OTG_BSP_mDelay(200); +} +/** +* @brief USB_OTG_EnableHostInt: Enables the Host mode interrupts +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_EnableHostInt(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_GINTMSK_TypeDef intmsk; + intmsk.d32 = 0; + /* Disable all interrupts. */ + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTMSK, 0); + + /* Clear any pending interrupts. */ + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, 0xFFFFFFFF); + + /* Enable the common interrupts */ + USB_OTG_EnableCommonInt(pdev); + + if (pdev->cfg.dma_enable == 0) + { + intmsk.b.rxstsqlvl = 1; + } + intmsk.b.portintr = 1; + intmsk.b.hcintr = 1; + intmsk.b.disconnect = 1; + intmsk.b.sofintr = 1; + intmsk.b.incomplisoout = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, intmsk.d32, intmsk.d32); + return status; +} + +/** +* @brief USB_OTG_InitFSLSPClkSel : Initializes the FSLSPClkSel field of the +* HCFG register on the PHY type +* @param pdev : Selected device +* @param freq : clock frequency +* @retval None +*/ +void USB_OTG_InitFSLSPClkSel(USB_OTG_CORE_HANDLE *pdev , uint8_t freq) +{ + USB_OTG_HCFG_TypeDef hcfg; + + hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG); + hcfg.b.fslspclksel = freq; + USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HCFG, hcfg.d32); +} + + +/** +* @brief USB_OTG_ReadHPRT0 : Reads HPRT0 to modify later +* @param pdev : Selected device +* @retval HPRT0 value +*/ +uint32_t USB_OTG_ReadHPRT0(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_HPRT0_TypeDef hprt0; + + hprt0.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0); + hprt0.b.prtena = 0; + hprt0.b.prtconndet = 0; + hprt0.b.prtenchng = 0; + hprt0.b.prtovrcurrchng = 0; + return hprt0.d32; +} + + +/** +* @brief USB_OTG_ReadHostAllChannels_intr : Register PCD Callbacks +* @param pdev : Selected device +* @retval Status +*/ +uint32_t USB_OTG_ReadHostAllChannels_intr (USB_OTG_CORE_HANDLE *pdev) +{ + return (USB_OTG_READ_REG32 (&pdev->regs.HREGS->HAINT)); +} + + +/** +* @brief USB_OTG_ResetPort : Reset Host Port +* @param pdev : Selected device +* @retval status +* @note : (1)The application must wait at least 10 ms (+ 10 ms security) +* before clearing the reset bit. +*/ +uint32_t USB_OTG_ResetPort(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_HPRT0_TypeDef hprt0; + + hprt0.d32 = USB_OTG_ReadHPRT0(pdev); + hprt0.b.prtrst = 1; + USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32); + USB_OTG_BSP_mDelay (10); /* See Note #1 */ + hprt0.b.prtrst = 0; + USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32); + USB_OTG_BSP_mDelay (20); + return 1; +} + + +/** +* @brief USB_OTG_HC_Init : Prepares a host channel for transferring packets +* @param pdev : Selected device +* @param hc_num : channel number +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_HC_Init(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) +{ + USB_OTG_STS status = USB_OTG_OK; + uint32_t intr_enable = 0; + USB_OTG_HCGINTMSK_TypeDef hcintmsk; + USB_OTG_GINTMSK_TypeDef gintmsk; + USB_OTG_HCCHAR_TypeDef hcchar; + USB_OTG_HCINTn_TypeDef hcint; + + + gintmsk.d32 = 0; + hcintmsk.d32 = 0; + hcchar.d32 = 0; + + /* Clear old interrupt conditions for this host channel. */ + hcint.d32 = 0xFFFFFFFF; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINT, hcint.d32); + + /* Enable channel interrupts required for this transfer. */ + hcintmsk.d32 = 0; + + if (pdev->cfg.dma_enable == 1) + { + hcintmsk.b.ahberr = 1; + } + + switch (pdev->host.hc[hc_num].ep_type) + { + case EP_TYPE_CTRL: + case EP_TYPE_BULK: + hcintmsk.b.xfercompl = 1; + hcintmsk.b.stall = 1; + hcintmsk.b.xacterr = 1; + hcintmsk.b.datatglerr = 1; + hcintmsk.b.nak = 1; + if (pdev->host.hc[hc_num].ep_is_in) + { + hcintmsk.b.bblerr = 1; + } + else + { + hcintmsk.b.nyet = 1; + if (pdev->host.hc[hc_num].do_ping) + { + hcintmsk.b.ack = 1; + } + } + break; + case EP_TYPE_INTR: + hcintmsk.b.xfercompl = 1; + hcintmsk.b.nak = 1; + hcintmsk.b.stall = 1; + hcintmsk.b.xacterr = 1; + hcintmsk.b.datatglerr = 1; + hcintmsk.b.frmovrun = 1; + + if (pdev->host.hc[hc_num].ep_is_in) + { + hcintmsk.b.bblerr = 1; + } + + break; + case EP_TYPE_ISOC: + hcintmsk.b.xfercompl = 1; + hcintmsk.b.frmovrun = 1; + hcintmsk.b.ack = 1; + + if (pdev->host.hc[hc_num].ep_is_in) + { + hcintmsk.b.xacterr = 1; + hcintmsk.b.bblerr = 1; + } + break; + } + + + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, hcintmsk.d32); + + + /* Enable the top level host channel interrupt. */ + intr_enable = (1 << hc_num); + USB_OTG_MODIFY_REG32(&pdev->regs.HREGS->HAINTMSK, 0, intr_enable); + + /* Make sure host channel interrupts are enabled. */ + gintmsk.b.hcintr = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, 0, gintmsk.d32); + + /* Program the HCCHAR register */ + hcchar.d32 = 0; + hcchar.b.devaddr = pdev->host.hc[hc_num].dev_addr; + hcchar.b.epnum = pdev->host.hc[hc_num].ep_num; + hcchar.b.epdir = pdev->host.hc[hc_num].ep_is_in; + hcchar.b.lspddev = (pdev->host.hc[hc_num].speed == HPRT0_PRTSPD_LOW_SPEED); + hcchar.b.eptype = pdev->host.hc[hc_num].ep_type; + hcchar.b.mps = pdev->host.hc[hc_num].max_packet; + if (pdev->host.hc[hc_num].ep_type == HCCHAR_INTR) + { + hcchar.b.oddfrm = 1; + } + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32); + return status; +} + + +/** +* @brief USB_OTG_HC_StartXfer : Start transfer +* @param pdev : Selected device +* @param hc_num : channel number +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_HC_StartXfer(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_HCCHAR_TypeDef hcchar; + USB_OTG_HCTSIZn_TypeDef hctsiz; + USB_OTG_HNPTXSTS_TypeDef hnptxsts; + USB_OTG_HPTXSTS_TypeDef hptxsts; + USB_OTG_GINTMSK_TypeDef intmsk; + uint16_t len_words = 0; + + uint16_t num_packets; + uint16_t max_hc_pkt_count; + + max_hc_pkt_count = 256; + hctsiz.d32 = 0; + hcchar.d32 = 0; + intmsk.d32 = 0; + + /* Compute the expected number of packets associated to the transfer */ + if (pdev->host.hc[hc_num].xfer_len > 0) + { + num_packets = (pdev->host.hc[hc_num].xfer_len + \ + pdev->host.hc[hc_num].max_packet - 1) / pdev->host.hc[hc_num].max_packet; + + if (num_packets > max_hc_pkt_count) + { + num_packets = max_hc_pkt_count; + pdev->host.hc[hc_num].xfer_len = num_packets * \ + pdev->host.hc[hc_num].max_packet; + } + } + else + { + num_packets = 1; + } + if (pdev->host.hc[hc_num].ep_is_in) + { + pdev->host.hc[hc_num].xfer_len = num_packets * \ + pdev->host.hc[hc_num].max_packet; + } + /* Initialize the HCTSIZn register */ + hctsiz.b.xfersize = pdev->host.hc[hc_num].xfer_len; + hctsiz.b.pktcnt = num_packets; + hctsiz.b.pid = pdev->host.hc[hc_num].data_pid; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCTSIZ, hctsiz.d32); + + if (pdev->cfg.dma_enable == 1) + { + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCDMA, (unsigned int)pdev->host.hc[hc_num].xfer_buff); + } + + + hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR); + hcchar.b.oddfrm = USB_OTG_IsEvenFrame(pdev); + + /* Set host channel enable */ + hcchar.b.chen = 1; + hcchar.b.chdis = 0; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32); + + if (pdev->cfg.dma_enable == 0) /* Slave mode */ + { + if((pdev->host.hc[hc_num].ep_is_in == 0) && + (pdev->host.hc[hc_num].xfer_len > 0)) + { + switch(pdev->host.hc[hc_num].ep_type) + { + /* Non periodic transfer */ + case EP_TYPE_CTRL: + case EP_TYPE_BULK: + + hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS); + len_words = (pdev->host.hc[hc_num].xfer_len + 3) / 4; + + /* check if there is enough space in FIFO space */ + if(len_words > hnptxsts.b.nptxfspcavail) + { + /* need to process data in nptxfempty interrupt */ + intmsk.b.nptxfempty = 1; + USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, 0, intmsk.d32); + } + + break; + /* Periodic transfer */ + case EP_TYPE_INTR: + case EP_TYPE_ISOC: + hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS); + len_words = (pdev->host.hc[hc_num].xfer_len + 3) / 4; + /* check if there is enough space in FIFO space */ + if(len_words > hptxsts.b.ptxfspcavail) /* split the transfer */ + { + /* need to process data in ptxfempty interrupt */ + intmsk.b.ptxfempty = 1; + USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, 0, intmsk.d32); + } + break; + + default: + break; + } + + /* Write packet into the Tx FIFO. */ + USB_OTG_WritePacket(pdev, + pdev->host.hc[hc_num].xfer_buff , + hc_num, pdev->host.hc[hc_num].xfer_len); + } + } + return status; +} + + +/** +* @brief USB_OTG_HC_Halt : Halt channel +* @param pdev : Selected device +* @param hc_num : channel number +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_HC_Halt(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_HNPTXSTS_TypeDef nptxsts; + USB_OTG_HPTXSTS_TypeDef hptxsts; + USB_OTG_HCCHAR_TypeDef hcchar; + + nptxsts.d32 = 0; + hptxsts.d32 = 0; + hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR); + hcchar.b.chen = 1; + hcchar.b.chdis = 1; + + /* Check for space in the request queue to issue the halt. */ + if (hcchar.b.eptype == HCCHAR_CTRL || hcchar.b.eptype == HCCHAR_BULK) + { + nptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS); + if (nptxsts.b.nptxqspcavail == 0) + { + hcchar.b.chen = 0; + } + } + else + { + hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS); + if (hptxsts.b.ptxqspcavail == 0) + { + hcchar.b.chen = 0; + } + } + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32); + return status; +} + +/** +* @brief Issue a ping token +* @param None +* @retval : None +*/ +USB_OTG_STS USB_OTG_HC_DoPing(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_HCCHAR_TypeDef hcchar; + USB_OTG_HCTSIZn_TypeDef hctsiz; + + hctsiz.d32 = 0; + hctsiz.b.dopng = 1; + hctsiz.b.pktcnt = 1; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCTSIZ, hctsiz.d32); + + hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR); + hcchar.b.chen = 1; + hcchar.b.chdis = 0; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32); + return status; +} + +/** +* @brief Stop the device and clean up fifo's +* @param None +* @retval : None +*/ +void USB_OTG_StopHost(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_HCCHAR_TypeDef hcchar; + uint32_t i; + + USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HAINTMSK , 0); + USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HAINT, 0xFFFFFFFF); + /* Flush out any leftover queued requests. */ + + for (i = 0; i < pdev->cfg.host_channels; i++) + { + hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[i]->HCCHAR); + hcchar.b.chen = 0; + hcchar.b.chdis = 1; + hcchar.b.epdir = 0; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[i]->HCCHAR, hcchar.d32); + } + + /* Flush the FIFO */ + USB_OTG_FlushRxFifo(pdev); + USB_OTG_FlushTxFifo(pdev , 0x10 ); +} +#endif +#ifdef USE_DEVICE_MODE +/* PCD Core Layer */ + +/** +* @brief USB_OTG_InitDevSpeed :Initializes the DevSpd field of DCFG register +* depending the PHY type and the enumeration speed of the device. +* @param pdev : Selected device +* @retval : None +*/ +void USB_OTG_InitDevSpeed(USB_OTG_CORE_HANDLE *pdev , uint8_t speed) +{ + USB_OTG_DCFG_TypeDef dcfg; + + dcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCFG); + dcfg.b.devspd = speed; + USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCFG, dcfg.d32); +} + + +/** +* @brief USB_OTG_CoreInitDev : Initializes the USB_OTG controller registers +* for device mode +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_CoreInitDev (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_DEPCTL_TypeDef depctl; + uint32_t i; + USB_OTG_DCFG_TypeDef dcfg; + USB_OTG_FSIZ_TypeDef nptxfifosize; + USB_OTG_FSIZ_TypeDef txfifosize; + USB_OTG_DIEPMSK_TypeDef msk; + USB_OTG_DTHRCTL_TypeDef dthrctl; + + depctl.d32 = 0; + dcfg.d32 = 0; + nptxfifosize.d32 = 0; + txfifosize.d32 = 0; + msk.d32 = 0; + + /* Restart the Phy Clock */ + USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, 0); + /* Device configuration register */ + dcfg.d32 = USB_OTG_READ_REG32( &pdev->regs.DREGS->DCFG); + dcfg.b.perfrint = DCFG_FRAME_INTERVAL_80; + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DCFG, dcfg.d32 ); + +#ifdef USB_OTG_FS_CORE + if(pdev->cfg.coreID == USB_OTG_FS_CORE_ID ) + { + + /* Set Full speed phy */ + USB_OTG_InitDevSpeed (pdev , USB_OTG_SPEED_PARAM_FULL); + + /* set Rx FIFO size */ + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRXFSIZ, RX_FIFO_FS_SIZE); + + /* EP0 TX*/ + nptxfifosize.b.depth = TX0_FIFO_FS_SIZE; + nptxfifosize.b.startaddr = RX_FIFO_FS_SIZE; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF0_HNPTXFSIZ, nptxfifosize.d32 ); + + + /* EP1 TX*/ + txfifosize.b.startaddr = nptxfifosize.b.startaddr + nptxfifosize.b.depth; + txfifosize.b.depth = TX1_FIFO_FS_SIZE; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[0], txfifosize.d32 ); + + + /* EP2 TX*/ + txfifosize.b.startaddr += txfifosize.b.depth; + txfifosize.b.depth = TX2_FIFO_FS_SIZE; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[1], txfifosize.d32 ); + + + /* EP3 TX*/ + txfifosize.b.startaddr += txfifosize.b.depth; + txfifosize.b.depth = TX3_FIFO_FS_SIZE; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[2], txfifosize.d32 ); + } +#endif +#ifdef USB_OTG_HS_CORE + if(pdev->cfg.coreID == USB_OTG_HS_CORE_ID ) + { + + /* Set High speed phy */ + + if(pdev->cfg.phy_itface == USB_OTG_ULPI_PHY) + { + USB_OTG_InitDevSpeed (pdev , USB_OTG_SPEED_PARAM_HIGH); + } + else /* set High speed phy in Full speed mode */ + { + USB_OTG_InitDevSpeed (pdev , USB_OTG_SPEED_PARAM_HIGH_IN_FULL); + } + + /* set Rx FIFO size */ + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRXFSIZ, RX_FIFO_HS_SIZE); + + /* EP0 TX*/ + nptxfifosize.b.depth = TX0_FIFO_HS_SIZE; + nptxfifosize.b.startaddr = RX_FIFO_HS_SIZE; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF0_HNPTXFSIZ, nptxfifosize.d32 ); + + + /* EP1 TX*/ + txfifosize.b.startaddr = nptxfifosize.b.startaddr + nptxfifosize.b.depth; + txfifosize.b.depth = TX1_FIFO_HS_SIZE; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[0], txfifosize.d32 ); + + + /* EP2 TX*/ + txfifosize.b.startaddr += txfifosize.b.depth; + txfifosize.b.depth = TX2_FIFO_HS_SIZE; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[1], txfifosize.d32 ); + + + /* EP3 TX*/ + txfifosize.b.startaddr += txfifosize.b.depth; + txfifosize.b.depth = TX3_FIFO_HS_SIZE; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[2], txfifosize.d32 ); + + /* EP4 TX*/ + txfifosize.b.startaddr += txfifosize.b.depth; + txfifosize.b.depth = TX4_FIFO_HS_SIZE; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[3], txfifosize.d32 ); + + + /* EP5 TX*/ + txfifosize.b.startaddr += txfifosize.b.depth; + txfifosize.b.depth = TX5_FIFO_HS_SIZE; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[4], txfifosize.d32 ); + } +#endif + /* Flush the FIFOs */ + USB_OTG_FlushTxFifo(pdev , 0x10); /* all Tx FIFOs */ + USB_OTG_FlushRxFifo(pdev); + /* Clear all pending Device Interrupts */ + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, 0 ); + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, 0 ); + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINT, 0xFFFFFFFF ); + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, 0 ); + + for (i = 0; i < pdev->cfg.dev_endpoints; i++) + { + depctl.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[i]->DIEPCTL); + if (depctl.b.epena) + { + depctl.d32 = 0; + depctl.b.epdis = 1; + depctl.b.snak = 1; + } + else + { + depctl.d32 = 0; + } + USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPCTL, depctl.d32); + USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPTSIZ, 0); + USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPINT, 0xFF); + } + for (i = 0; i < pdev->cfg.dev_endpoints; i++) + { + USB_OTG_DEPCTL_TypeDef depctl; + depctl.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[i]->DOEPCTL); + if (depctl.b.epena) + { + depctl.d32 = 0; + depctl.b.epdis = 1; + depctl.b.snak = 1; + } + else + { + depctl.d32 = 0; + } + USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPCTL, depctl.d32); + USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPTSIZ, 0); + USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xFF); + } + msk.d32 = 0; + msk.b.txfifoundrn = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPMSK, msk.d32, msk.d32); + + if (pdev->cfg.dma_enable == 1) + { + dthrctl.d32 = 0; + dthrctl.b.non_iso_thr_en = 1; + dthrctl.b.iso_thr_en = 1; + dthrctl.b.tx_thr_len = 64; + dthrctl.b.rx_thr_en = 1; + dthrctl.b.rx_thr_len = 64; + USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DTHRCTL, dthrctl.d32); + } + USB_OTG_EnableDevInt(pdev); + return status; +} + + +/** +* @brief USB_OTG_EnableDevInt : Enables the Device mode interrupts +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_EnableDevInt(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_GINTMSK_TypeDef intmsk; + + intmsk.d32 = 0; + + /* Disable all interrupts. */ + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTMSK, 0); + /* Clear any pending interrupts */ + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xFFFFFFFF); + /* Enable the common interrupts */ + USB_OTG_EnableCommonInt(pdev); + + if (pdev->cfg.dma_enable == 0) + { + intmsk.b.rxstsqlvl = 1; + } + + /* Enable interrupts matching to the Device mode ONLY */ + intmsk.b.usbsuspend = 1; + intmsk.b.usbreset = 1; + intmsk.b.enumdone = 1; + intmsk.b.inepintr = 1; + intmsk.b.outepintr = 1; + intmsk.b.sofintr = 1; + + intmsk.b.incomplisoin = 1; + intmsk.b.incomplisoout = 1; +#ifdef VBUS_SENSING_ENABLED + intmsk.b.sessreqintr = 1; + intmsk.b.otgintr = 1; +#endif + USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, intmsk.d32); + return status; +} + + +/** +* @brief USB_OTG_GetDeviceSpeed +* Get the device speed from the device status register +* @param None +* @retval status +*/ +enum USB_OTG_SPEED USB_OTG_GetDeviceSpeed (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_DSTS_TypeDef dsts; + enum USB_OTG_SPEED speed = USB_SPEED_UNKNOWN; + + + dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS); + + switch (dsts.b.enumspd) + { + case DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ: + speed = USB_SPEED_HIGH; + break; + case DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ: + case DSTS_ENUMSPD_FS_PHY_48MHZ: + speed = USB_SPEED_FULL; + break; + + case DSTS_ENUMSPD_LS_PHY_6MHZ: + speed = USB_SPEED_LOW; + break; + } + + return speed; +} +/** +* @brief enables EP0 OUT to receive SETUP packets and configures EP0 +* for transmitting packets +* @param None +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_EP0Activate(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_DSTS_TypeDef dsts; + USB_OTG_DEPCTL_TypeDef diepctl; + USB_OTG_DCTL_TypeDef dctl; + + dctl.d32 = 0; + /* Read the Device Status and Endpoint 0 Control registers */ + dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS); + diepctl.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[0]->DIEPCTL); + /* Set the MPS of the IN EP based on the enumeration speed */ + switch (dsts.b.enumspd) + { + case DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ: + case DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ: + case DSTS_ENUMSPD_FS_PHY_48MHZ: + diepctl.b.mps = DEP0CTL_MPS_64; + break; + case DSTS_ENUMSPD_LS_PHY_6MHZ: + diepctl.b.mps = DEP0CTL_MPS_8; + break; + } + USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[0]->DIEPCTL, diepctl.d32); + dctl.b.cgnpinnak = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, dctl.d32, dctl.d32); + return status; +} + + +/** +* @brief USB_OTG_EPActivate : Activates an EP +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_EPActivate(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_DEPCTL_TypeDef depctl; + USB_OTG_DAINT_TypeDef daintmsk; + __IO uint32_t *addr; + + + depctl.d32 = 0; + daintmsk.d32 = 0; + /* Read DEPCTLn register */ + if (ep->is_in == 1) + { + addr = &pdev->regs.INEP_REGS[ep->num]->DIEPCTL; + daintmsk.ep.in = 1 << ep->num; + } + else + { + addr = &pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL; + daintmsk.ep.out = 1 << ep->num; + } + /* If the EP is already active don't change the EP Control + * register. */ + depctl.d32 = USB_OTG_READ_REG32(addr); + if (!depctl.b.usbactep) + { + depctl.b.mps = ep->maxpacket; + depctl.b.eptype = ep->type; + depctl.b.txfnum = ep->tx_fifo_num; + depctl.b.setd0pid = 1; + depctl.b.usbactep = 1; + USB_OTG_WRITE_REG32(addr, depctl.d32); + } + /* Enable the Interrupt for this EP */ +#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED + if((ep->num == 1)&&(pdev->cfg.coreID == USB_OTG_HS_CORE_ID)) + { + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DEACHMSK, 0, daintmsk.d32); + } + else +#endif + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DAINTMSK, 0, daintmsk.d32); + return status; +} + + +/** +* @brief USB_OTG_EPDeactivate : Deactivates an EP +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_EPDeactivate(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_DEPCTL_TypeDef depctl; + USB_OTG_DAINT_TypeDef daintmsk; + __IO uint32_t *addr; + + depctl.d32 = 0; + daintmsk.d32 = 0; + /* Read DEPCTLn register */ + if (ep->is_in == 1) + { + addr = &pdev->regs.INEP_REGS[ep->num]->DIEPCTL; + daintmsk.ep.in = 1 << ep->num; + } + else + { + addr = &pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL; + daintmsk.ep.out = 1 << ep->num; + } + depctl.b.usbactep = 0; + USB_OTG_WRITE_REG32(addr, depctl.d32); + /* Disable the Interrupt for this EP */ + +#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED + if((ep->num == 1)&&(pdev->cfg.coreID == USB_OTG_HS_CORE_ID)) + { + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DEACHMSK, daintmsk.d32, 0); + } + else +#endif + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DAINTMSK, daintmsk.d32, 0); + return status; +} + + +/** +* @brief USB_OTG_EPStartXfer : Handle the setup for data xfer for an EP and +* starts the xfer +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_EPStartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_DEPCTL_TypeDef depctl; + USB_OTG_DEPXFRSIZ_TypeDef deptsiz; + USB_OTG_DSTS_TypeDef dsts; + uint32_t fifoemptymsk = 0; + + depctl.d32 = 0; + deptsiz.d32 = 0; + /* IN endpoint */ + if (ep->is_in == 1) + { + depctl.d32 = USB_OTG_READ_REG32(&(pdev->regs.INEP_REGS[ep->num]->DIEPCTL)); + deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.INEP_REGS[ep->num]->DIEPTSIZ)); + /* Zero Length Packet? */ + if (ep->xfer_len == 0) + { + deptsiz.b.xfersize = 0; + deptsiz.b.pktcnt = 1; + } + else + { + /* Program the transfer size and packet count + * as follows: xfersize = N * maxpacket + + * short_packet pktcnt = N + (short_packet + * exist ? 1 : 0) + */ + deptsiz.b.xfersize = ep->xfer_len; + deptsiz.b.pktcnt = (ep->xfer_len - 1 + ep->maxpacket) / ep->maxpacket; + + if (ep->type == EP_TYPE_ISOC) + { + deptsiz.b.mc = 1; + } + } + USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[ep->num]->DIEPTSIZ, deptsiz.d32); + + if (pdev->cfg.dma_enable == 1) + { + USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[ep->num]->DIEPDMA, ep->dma_addr); + } + else + { + if (ep->type != EP_TYPE_ISOC) + { + /* Enable the Tx FIFO Empty Interrupt for this EP */ + if (ep->xfer_len > 0) + { + fifoemptymsk = 1 << ep->num; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, 0, fifoemptymsk); + } + } + } + + + if (ep->type == EP_TYPE_ISOC) + { + dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS); + + if (((dsts.b.soffn)&0x1) == 0) + { + depctl.b.setd1pid = 1; + } + else + { + depctl.b.setd0pid = 1; + } + } + + /* EP enable, IN data in FIFO */ + depctl.b.cnak = 1; + depctl.b.epena = 1; + USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[ep->num]->DIEPCTL, depctl.d32); + + if (ep->type == EP_TYPE_ISOC) + { + USB_OTG_WritePacket(pdev, ep->xfer_buff, ep->num, ep->xfer_len); + } + } + else + { + /* OUT endpoint */ + depctl.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL)); + deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[ep->num]->DOEPTSIZ)); + /* Program the transfer size and packet count as follows: + * pktcnt = N + * xfersize = N * maxpacket + */ + if (ep->xfer_len == 0) + { + deptsiz.b.xfersize = ep->maxpacket; + deptsiz.b.pktcnt = 1; + } + else + { + deptsiz.b.pktcnt = (ep->xfer_len + (ep->maxpacket - 1)) / ep->maxpacket; + deptsiz.b.xfersize = deptsiz.b.pktcnt * ep->maxpacket; + } + USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPTSIZ, deptsiz.d32); + + if (pdev->cfg.dma_enable == 1) + { + USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPDMA, ep->dma_addr); + } + + if (ep->type == EP_TYPE_ISOC) + { + if (ep->even_odd_frame) + { + depctl.b.setd1pid = 1; + } + else + { + depctl.b.setd0pid = 1; + } + } + /* EP enable */ + depctl.b.cnak = 1; + depctl.b.epena = 1; + USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL, depctl.d32); + } + return status; +} + + +/** +* @brief USB_OTG_EP0StartXfer : Handle the setup for a data xfer for EP0 and +* starts the xfer +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_EP0StartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_DEPCTL_TypeDef depctl; + USB_OTG_DEP0XFRSIZ_TypeDef deptsiz; + USB_OTG_INEPREGS *in_regs; + uint32_t fifoemptymsk = 0; + + depctl.d32 = 0; + deptsiz.d32 = 0; + /* IN endpoint */ + if (ep->is_in == 1) + { + in_regs = pdev->regs.INEP_REGS[0]; + depctl.d32 = USB_OTG_READ_REG32(&in_regs->DIEPCTL); + deptsiz.d32 = USB_OTG_READ_REG32(&in_regs->DIEPTSIZ); + /* Zero Length Packet? */ + if (ep->xfer_len == 0) + { + deptsiz.b.xfersize = 0; + deptsiz.b.pktcnt = 1; + + } + else + { + if (ep->xfer_len > ep->maxpacket) + { + ep->xfer_len = ep->maxpacket; + deptsiz.b.xfersize = ep->maxpacket; + } + else + { + deptsiz.b.xfersize = ep->xfer_len; + } + deptsiz.b.pktcnt = 1; + } + USB_OTG_WRITE_REG32(&in_regs->DIEPTSIZ, deptsiz.d32); + + if (pdev->cfg.dma_enable == 1) + { + USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[ep->num]->DIEPDMA, ep->dma_addr); + } + + /* EP enable, IN data in FIFO */ + depctl.b.cnak = 1; + depctl.b.epena = 1; + USB_OTG_WRITE_REG32(&in_regs->DIEPCTL, depctl.d32); + + + + if (pdev->cfg.dma_enable == 0) + { + /* Enable the Tx FIFO Empty Interrupt for this EP */ + if (ep->xfer_len > 0) + { + { + fifoemptymsk |= 1 << ep->num; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, 0, fifoemptymsk); + } + } + } + } + else + { + /* OUT endpoint */ + depctl.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL); + deptsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPTSIZ); + /* Program the transfer size and packet count as follows: + * xfersize = N * (maxpacket + 4 - (maxpacket % 4)) + * pktcnt = N */ + if (ep->xfer_len == 0) + { + deptsiz.b.xfersize = ep->maxpacket; + deptsiz.b.pktcnt = 1; + } + else + { + ep->xfer_len = ep->maxpacket; + deptsiz.b.xfersize = ep->maxpacket; + deptsiz.b.pktcnt = 1; + } + USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPTSIZ, deptsiz.d32); + if (pdev->cfg.dma_enable == 1) + { + USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPDMA, ep->dma_addr); + } + /* EP enable */ + depctl.b.cnak = 1; + depctl.b.epena = 1; + USB_OTG_WRITE_REG32 (&(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL), depctl.d32); + + } + return status; +} + + +/** +* @brief USB_OTG_EPSetStall : Set the EP STALL +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_EPSetStall(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_DEPCTL_TypeDef depctl; + __IO uint32_t *depctl_addr; + + depctl.d32 = 0; + if (ep->is_in == 1) + { + depctl_addr = &(pdev->regs.INEP_REGS[ep->num]->DIEPCTL); + depctl.d32 = USB_OTG_READ_REG32(depctl_addr); + /* set the disable and stall bits */ + if (depctl.b.epena) + { + depctl.b.epdis = 1; + } + depctl.b.stall = 1; + USB_OTG_WRITE_REG32(depctl_addr, depctl.d32); + } + else + { + depctl_addr = &(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL); + depctl.d32 = USB_OTG_READ_REG32(depctl_addr); + /* set the stall bit */ + depctl.b.stall = 1; + USB_OTG_WRITE_REG32(depctl_addr, depctl.d32); + } + return status; +} + + +/** +* @brief Clear the EP STALL +* @param pdev : Selected device +* @retval USB_OTG_STS : status +*/ +USB_OTG_STS USB_OTG_EPClearStall(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep) +{ + USB_OTG_STS status = USB_OTG_OK; + USB_OTG_DEPCTL_TypeDef depctl; + __IO uint32_t *depctl_addr; + + depctl.d32 = 0; + + if (ep->is_in == 1) + { + depctl_addr = &(pdev->regs.INEP_REGS[ep->num]->DIEPCTL); + } + else + { + depctl_addr = &(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL); + } + depctl.d32 = USB_OTG_READ_REG32(depctl_addr); + /* clear the stall bits */ + depctl.b.stall = 0; + if (ep->type == EP_TYPE_INTR || ep->type == EP_TYPE_BULK) + { + depctl.b.setd0pid = 1; /* DATA0 */ + } + USB_OTG_WRITE_REG32(depctl_addr, depctl.d32); + return status; +} + + +/** +* @brief USB_OTG_ReadDevAllOutEp_itr : returns OUT endpoint interrupt bits +* @param pdev : Selected device +* @retval OUT endpoint interrupt bits +*/ +uint32_t USB_OTG_ReadDevAllOutEp_itr(USB_OTG_CORE_HANDLE *pdev) +{ + uint32_t v; + v = USB_OTG_READ_REG32(&pdev->regs.DREGS->DAINT); + v &= USB_OTG_READ_REG32(&pdev->regs.DREGS->DAINTMSK); + return ((v & 0xffff0000) >> 16); +} + + +/** +* @brief USB_OTG_ReadDevOutEP_itr : returns Device OUT EP Interrupt register +* @param pdev : Selected device +* @param ep : end point number +* @retval Device OUT EP Interrupt register +*/ +uint32_t USB_OTG_ReadDevOutEP_itr(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum) +{ + uint32_t v; + v = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[epnum]->DOEPINT); + v &= USB_OTG_READ_REG32(&pdev->regs.DREGS->DOEPMSK); + return v; +} + + +/** +* @brief USB_OTG_ReadDevAllInEPItr : Get int status register +* @param pdev : Selected device +* @retval int status register +*/ +uint32_t USB_OTG_ReadDevAllInEPItr(USB_OTG_CORE_HANDLE *pdev) +{ + uint32_t v; + v = USB_OTG_READ_REG32(&pdev->regs.DREGS->DAINT); + v &= USB_OTG_READ_REG32(&pdev->regs.DREGS->DAINTMSK); + return (v & 0xffff); +} + +/** +* @brief configures EPO to receive SETUP packets +* @param None +* @retval : None +*/ +void USB_OTG_EP0_OutStart(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_DEP0XFRSIZ_TypeDef doeptsize0; + doeptsize0.d32 = 0; + doeptsize0.b.supcnt = 3; + doeptsize0.b.pktcnt = 1; + doeptsize0.b.xfersize = 8 * 3; + USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[0]->DOEPTSIZ, doeptsize0.d32 ); + + if (pdev->cfg.dma_enable == 1) + { + USB_OTG_DEPCTL_TypeDef doepctl; + doepctl.d32 = 0; + USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[0]->DOEPDMA, + (uint32_t)&pdev->dev.setup_packet); + + /* EP enable */ + doepctl.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[0]->DOEPCTL); + doepctl.b.epena = 1; + doepctl.d32 = 0x80008000; + USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[0]->DOEPCTL, doepctl.d32); + } +} + +/** +* @brief USB_OTG_RemoteWakeup : active remote wakeup signalling +* @param None +* @retval : None +*/ +void USB_OTG_ActiveRemoteWakeup(USB_OTG_CORE_HANDLE *pdev) +{ + + USB_OTG_DCTL_TypeDef dctl; + USB_OTG_DSTS_TypeDef dsts; + USB_OTG_PCGCCTL_TypeDef power; + + if (pdev->dev.DevRemoteWakeup) + { + dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS); + if(dsts.b.suspsts == 1) + { + if(pdev->cfg.low_power) + { + /* un-gate USB Core clock */ + power.d32 = USB_OTG_READ_REG32(&pdev->regs.PCGCCTL); + power.b.gatehclk = 0; + power.b.stoppclk = 0; + USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, power.d32); + } + /* active Remote wakeup signaling */ + dctl.d32 = 0; + dctl.b.rmtwkupsig = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, 0, dctl.d32); + USB_OTG_BSP_mDelay(5); + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, dctl.d32, 0 ); + } + } +} + + +/** +* @brief USB_OTG_UngateClock : active USB Core clock +* @param None +* @retval : None +*/ +void USB_OTG_UngateClock(USB_OTG_CORE_HANDLE *pdev) +{ + if(pdev->cfg.low_power) + { + + USB_OTG_DSTS_TypeDef dsts; + USB_OTG_PCGCCTL_TypeDef power; + + dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS); + + if(dsts.b.suspsts == 1) + { + /* un-gate USB Core clock */ + power.d32 = USB_OTG_READ_REG32(&pdev->regs.PCGCCTL); + power.b.gatehclk = 0; + power.b.stoppclk = 0; + USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, power.d32); + + } + } +} + +/** +* @brief Stop the device and clean up fifo's +* @param None +* @retval : None +*/ +void USB_OTG_StopDevice(USB_OTG_CORE_HANDLE *pdev) +{ + uint32_t i; + + pdev->dev.device_status = 1; + + for (i = 0; i < pdev->cfg.dev_endpoints ; i++) + { + USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPINT, 0xFF); + USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xFF); + } + + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, 0 ); + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, 0 ); + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, 0 ); + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINT, 0xFFFFFFFF ); + + /* Flush the FIFO */ + USB_OTG_FlushRxFifo(pdev); + USB_OTG_FlushTxFifo(pdev , 0x10 ); +} + +/** +* @brief returns the EP Status +* @param pdev : Selected device +* ep : endpoint structure +* @retval : EP status +*/ + +uint32_t USB_OTG_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,USB_OTG_EP *ep) +{ + USB_OTG_DEPCTL_TypeDef depctl; + __IO uint32_t *depctl_addr; + uint32_t Status = 0; + + depctl.d32 = 0; + if (ep->is_in == 1) + { + depctl_addr = &(pdev->regs.INEP_REGS[ep->num]->DIEPCTL); + depctl.d32 = USB_OTG_READ_REG32(depctl_addr); + + if (depctl.b.stall == 1) + Status = USB_OTG_EP_TX_STALL; + else if (depctl.b.naksts == 1) + Status = USB_OTG_EP_TX_NAK; + else + Status = USB_OTG_EP_TX_VALID; + + } + else + { + depctl_addr = &(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL); + depctl.d32 = USB_OTG_READ_REG32(depctl_addr); + if (depctl.b.stall == 1) + Status = USB_OTG_EP_RX_STALL; + else if (depctl.b.naksts == 1) + Status = USB_OTG_EP_RX_NAK; + else + Status = USB_OTG_EP_RX_VALID; + } + + /* Return the current status */ + return Status; +} + +/** +* @brief Set the EP Status +* @param pdev : Selected device +* Status : new Status +* ep : EP structure +* @retval : None +*/ +void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t Status) +{ + USB_OTG_DEPCTL_TypeDef depctl; + __IO uint32_t *depctl_addr; + + depctl.d32 = 0; + + /* Process for IN endpoint */ + if (ep->is_in == 1) + { + depctl_addr = &(pdev->regs.INEP_REGS[ep->num]->DIEPCTL); + depctl.d32 = USB_OTG_READ_REG32(depctl_addr); + + if (Status == USB_OTG_EP_TX_STALL) + { + USB_OTG_EPSetStall(pdev, ep); return; + } + else if (Status == USB_OTG_EP_TX_NAK) + depctl.b.snak = 1; + else if (Status == USB_OTG_EP_TX_VALID) + { + if (depctl.b.stall == 1) + { + ep->even_odd_frame = 0; + USB_OTG_EPClearStall(pdev, ep); + return; + } + depctl.b.cnak = 1; + depctl.b.usbactep = 1; + depctl.b.epena = 1; + } + else if (Status == USB_OTG_EP_TX_DIS) + depctl.b.usbactep = 0; + } + else /* Process for OUT endpoint */ + { + depctl_addr = &(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL); + depctl.d32 = USB_OTG_READ_REG32(depctl_addr); + + if (Status == USB_OTG_EP_RX_STALL) { + depctl.b.stall = 1; + } + else if (Status == USB_OTG_EP_RX_NAK) + depctl.b.snak = 1; + else if (Status == USB_OTG_EP_RX_VALID) + { + if (depctl.b.stall == 1) + { + ep->even_odd_frame = 0; + USB_OTG_EPClearStall(pdev, ep); + return; + } + depctl.b.cnak = 1; + depctl.b.usbactep = 1; + depctl.b.epena = 1; + } + else if (Status == USB_OTG_EP_RX_DIS) + { + depctl.b.usbactep = 0; + } + } + + USB_OTG_WRITE_REG32(depctl_addr, depctl.d32); +} + +#endif +/** +* @} +*/ + +/** +* @} +*/ + +/** +* @} +*/ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_dcd.c b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_dcd.c new file mode 100644 index 000000000..d323e7dcb --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_dcd.c @@ -0,0 +1,472 @@ +/** + ****************************************************************************** + * @file usb_dcd.c + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Peripheral Device Interface Layer + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_dcd.h" +#include "usb_bsp.h" + + +/** @addtogroup USB_OTG_DRIVER +* @{ +*/ + +/** @defgroup USB_DCD +* @brief This file is the interface between EFSL ans Host mass-storage class +* @{ +*/ + + +/** @defgroup USB_DCD_Private_Defines +* @{ +*/ +/** +* @} +*/ + + +/** @defgroup USB_DCD_Private_TypesDefinitions +* @{ +*/ +/** +* @} +*/ + + + +/** @defgroup USB_DCD_Private_Macros +* @{ +*/ +/** +* @} +*/ + + +/** @defgroup USB_DCD_Private_Variables +* @{ +*/ +/** +* @} +*/ + + +/** @defgroup USB_DCD_Private_FunctionPrototypes +* @{ +*/ + +/** +* @} +*/ + + +/** @defgroup USB_DCD_Private_Functions +* @{ +*/ + + + +void DCD_Init(USB_OTG_CORE_HANDLE *pdev , + USB_OTG_CORE_ID_TypeDef coreID) +{ + uint32_t i; + USB_OTG_EP *ep; + + USB_OTG_SelectCore (pdev , coreID); + + pdev->dev.device_status = USB_OTG_DEFAULT; + pdev->dev.device_address = 0; + + /* Init ep structure */ + for (i = 0; i < pdev->cfg.dev_endpoints ; i++) + { + ep = &pdev->dev.in_ep[i]; + /* Init ep structure */ + ep->is_in = 1; + ep->num = i; + ep->tx_fifo_num = i; + /* Control until ep is actvated */ + ep->type = EP_TYPE_CTRL; + ep->maxpacket = USB_OTG_MAX_EP0_SIZE; + ep->xfer_buff = 0; + ep->xfer_len = 0; + } + + for (i = 0; i < pdev->cfg.dev_endpoints; i++) + { + ep = &pdev->dev.out_ep[i]; + /* Init ep structure */ + ep->is_in = 0; + ep->num = i; + ep->tx_fifo_num = i; + /* Control until ep is activated */ + ep->type = EP_TYPE_CTRL; + ep->maxpacket = USB_OTG_MAX_EP0_SIZE; + ep->xfer_buff = 0; + ep->xfer_len = 0; + } + + USB_OTG_DisableGlobalInt(pdev); + + /*Init the Core (common init.) */ + USB_OTG_CoreInit(pdev); + + + /* Force Device Mode*/ + USB_OTG_SetCurrentMode(pdev, DEVICE_MODE); + + /* Init Device */ + USB_OTG_CoreInitDev(pdev); + + + /* Enable USB Global interrupt */ + USB_OTG_EnableGlobalInt(pdev); +} + + +/** +* @brief Configure an EP +* @param pdev : Device instance +* @param epdesc : Endpoint Descriptor +* @retval : status +*/ +uint32_t DCD_EP_Open(USB_OTG_CORE_HANDLE *pdev , + uint8_t ep_addr, + uint16_t ep_mps, + uint8_t ep_type) +{ + USB_OTG_EP *ep; + + if ((ep_addr & 0x80) == 0x80) + { + ep = &pdev->dev.in_ep[ep_addr & 0x7F]; + } + else + { + ep = &pdev->dev.out_ep[ep_addr & 0x7F]; + } + ep->num = ep_addr & 0x7F; + + ep->is_in = (0x80 & ep_addr) != 0; + ep->maxpacket = ep_mps; + ep->type = ep_type; + if (ep->is_in) + { + /* Assign a Tx FIFO */ + ep->tx_fifo_num = ep->num; + } + /* Set initial data PID. */ + if (ep_type == USB_OTG_EP_BULK ) + { + ep->data_pid_start = 0; + } + USB_OTG_EPActivate(pdev , ep ); + return 0; +} +/** +* @brief called when an EP is disabled +* @param pdev: device instance +* @param ep_addr: endpoint address +* @retval : status +*/ +uint32_t DCD_EP_Close(USB_OTG_CORE_HANDLE *pdev , uint8_t ep_addr) +{ + USB_OTG_EP *ep; + + if ((ep_addr&0x80) == 0x80) + { + ep = &pdev->dev.in_ep[ep_addr & 0x7F]; + } + else + { + ep = &pdev->dev.out_ep[ep_addr & 0x7F]; + } + ep->num = ep_addr & 0x7F; + ep->is_in = (0x80 & ep_addr) != 0; + USB_OTG_EPDeactivate(pdev , ep ); + return 0; +} + + +/** +* @brief DCD_EP_PrepareRx +* @param pdev: device instance +* @param ep_addr: endpoint address +* @param pbuf: pointer to Rx buffer +* @param buf_len: data length +* @retval : status +*/ +uint32_t DCD_EP_PrepareRx( USB_OTG_CORE_HANDLE *pdev, + uint8_t ep_addr, + uint8_t *pbuf, + uint16_t buf_len) +{ + USB_OTG_EP *ep; + + ep = &pdev->dev.out_ep[ep_addr & 0x7F]; + + /*setup and start the Xfer */ + ep->xfer_buff = pbuf; + ep->xfer_len = buf_len; + ep->xfer_count = 0; + ep->is_in = 0; + ep->num = ep_addr & 0x7F; + + if (pdev->cfg.dma_enable == 1) + { + ep->dma_addr = (uint32_t)pbuf; + } + + if ( ep->num == 0 ) + { + USB_OTG_EP0StartXfer(pdev , ep); + } + else + { + USB_OTG_EPStartXfer(pdev, ep ); + } + return 0; +} + +/** +* @brief Transmit data over USB +* @param pdev: device instance +* @param ep_addr: endpoint address +* @param pbuf: pointer to Tx buffer +* @param buf_len: data length +* @retval : status +*/ +uint32_t DCD_EP_Tx ( USB_OTG_CORE_HANDLE *pdev, + uint8_t ep_addr, + const uint8_t *pbuf, + uint32_t buf_len) +{ + USB_OTG_EP *ep; + + ep = &pdev->dev.in_ep[ep_addr & 0x7F]; + + /* Setup and start the Transfer */ + ep->is_in = 1; + ep->num = ep_addr & 0x7F; + ep->xfer_buff = pbuf; + ep->dma_addr = (uint32_t)pbuf; + ep->xfer_count = 0; + ep->xfer_len = buf_len; + + if ( ep->num == 0 ) + { + USB_OTG_EP0StartXfer(pdev , ep); + } + else + { + USB_OTG_EPStartXfer(pdev, ep ); + } + return 0; +} + + +/** +* @brief Stall an endpoint. +* @param pdev: device instance +* @param epnum: endpoint address +* @retval : status +*/ +uint32_t DCD_EP_Stall (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum) +{ + USB_OTG_EP *ep; + if ((0x80 & epnum) == 0x80) + { + ep = &pdev->dev.in_ep[epnum & 0x7F]; + } + else + { + ep = &pdev->dev.out_ep[epnum]; + } + + ep->is_stall = 1; + ep->num = epnum & 0x7F; + ep->is_in = ((epnum & 0x80) == 0x80); + + USB_OTG_EPSetStall(pdev , ep); + return (0); +} + + +/** +* @brief Clear stall condition on endpoints. +* @param pdev: device instance +* @param epnum: endpoint address +* @retval : status +*/ +uint32_t DCD_EP_ClrStall (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum) +{ + USB_OTG_EP *ep; + if ((0x80 & epnum) == 0x80) + { + ep = &pdev->dev.in_ep[epnum & 0x7F]; + } + else + { + ep = &pdev->dev.out_ep[epnum]; + } + + ep->is_stall = 0; + ep->num = epnum & 0x7F; + ep->is_in = ((epnum & 0x80) == 0x80); + + USB_OTG_EPClearStall(pdev , ep); + return (0); +} + + +/** +* @brief This Function flushes the FIFOs. +* @param pdev: device instance +* @param epnum: endpoint address +* @retval : status +*/ +uint32_t DCD_EP_Flush (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum) +{ + + if ((epnum & 0x80) == 0x80) + { + USB_OTG_FlushTxFifo(pdev, epnum & 0x7F); + } + else + { + USB_OTG_FlushRxFifo(pdev); + } + + return (0); +} + + +/** +* @brief This Function set USB device address +* @param pdev: device instance +* @param address: new device address +* @retval : status +*/ +void DCD_EP_SetAddress (USB_OTG_CORE_HANDLE *pdev, uint8_t address) +{ + USB_OTG_DCFG_TypeDef dcfg; + dcfg.d32 = 0; + dcfg.b.devaddr = address; + USB_OTG_MODIFY_REG32( &pdev->regs.DREGS->DCFG, 0, dcfg.d32); +} + +/** +* @brief Connect device (enable internal pull-up) +* @param pdev: device instance +* @retval : None +*/ +void DCD_DevConnect (USB_OTG_CORE_HANDLE *pdev) +{ +#ifndef USE_OTG_MODE + USB_OTG_DCTL_TypeDef dctl; + dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL); + /* Connect device */ + dctl.b.sftdiscon = 0; + USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32); + USB_OTG_BSP_mDelay(3); +#endif +} + + +/** +* @brief Disconnect device (disable internal pull-up) +* @param pdev: device instance +* @retval : None +*/ +void DCD_DevDisconnect (USB_OTG_CORE_HANDLE *pdev) +{ +#ifndef USE_OTG_MODE + USB_OTG_DCTL_TypeDef dctl; + dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL); + /* Disconnect device for 3ms */ + dctl.b.sftdiscon = 1; + USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32); + USB_OTG_BSP_mDelay(3); +#endif +} + + +/** +* @brief returns the EP Status +* @param pdev : Selected device +* epnum : endpoint address +* @retval : EP status +*/ + +uint32_t DCD_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,uint8_t epnum) +{ + USB_OTG_EP *ep; + uint32_t Status = 0; + + if ((0x80 & epnum) == 0x80) + { + ep = &pdev->dev.in_ep[epnum & 0x7F]; + } + else + { + ep = &pdev->dev.out_ep[epnum]; + } + + Status = USB_OTG_GetEPStatus(pdev ,ep); + + /* Return the current status */ + return Status; +} + +/** +* @brief Set the EP Status +* @param pdev : Selected device +* Status : new Status +* epnum : EP address +* @retval : None +*/ +void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum , uint32_t Status) +{ + USB_OTG_EP *ep; + + if ((0x80 & epnum) == 0x80) + { + ep = &pdev->dev.in_ep[epnum & 0x7F]; + } + else + { + ep = &pdev->dev.out_ep[epnum]; + } + + USB_OTG_SetEPStatus(pdev ,ep , Status); +} + +/** +* @} +*/ + +/** +* @} +*/ + +/** +* @} +*/ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_dcd_int.c b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_dcd_int.c new file mode 100644 index 000000000..bb1c609f8 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_dcd_int.c @@ -0,0 +1,891 @@ +/** + ****************************************************************************** + * @file usb_dcd_int.c + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Peripheral Device interrupt subroutines + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_dcd_int.h" +/** @addtogroup USB_OTG_DRIVER +* @{ +*/ + +/** @defgroup USB_DCD_INT +* @brief This file contains the interrupt subroutines for the Device mode. +* @{ +*/ + + +/** @defgroup USB_DCD_INT_Private_Defines +* @{ +*/ +/** +* @} +*/ + + +/** @defgroup USB_DCD_INT_Private_TypesDefinitions +* @{ +*/ +/** +* @} +*/ + + + +/** @defgroup USB_DCD_INT_Private_Macros +* @{ +*/ +/** +* @} +*/ + + +/** @defgroup USB_DCD_INT_Private_Variables +* @{ +*/ +/** +* @} +*/ + + +/** @defgroup USB_DCD_INT_Private_FunctionPrototypes +* @{ +*/ +/* static functions */ +static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum); + +/* Interrupt Handlers */ +static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t DCD_HandleSof_ISR(USB_OTG_CORE_HANDLE *pdev); + +static uint32_t DCD_HandleRxStatusQueueLevel_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev , uint32_t epnum); + +static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t DCD_HandleResume_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev); + +static uint32_t DCD_IsoINIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t DCD_IsoOUTIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev); +#ifdef VBUS_SENSING_ENABLED +static uint32_t DCD_SessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t DCD_OTG_ISR(USB_OTG_CORE_HANDLE *pdev); +#endif + +/** +* @} +*/ + + +/** @defgroup USB_DCD_INT_Private_Functions +* @{ +*/ + + +#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED +/** +* @brief USBD_OTG_EP1OUT_ISR_Handler +* handles all USB Interrupts +* @param pdev: device instance +* @retval status +*/ +uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) +{ + + USB_OTG_DOEPINTn_TypeDef doepint; + USB_OTG_DEPXFRSIZ_TypeDef deptsiz; + + doepint.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[1]->DOEPINT); + doepint.d32&= USB_OTG_READ_REG32(&pdev->regs.DREGS->DOUTEP1MSK); + + /* Transfer complete */ + if ( doepint.b.xfercompl ) + { + /* Clear the bit in DOEPINTn for this interrupt */ + CLEAR_OUT_EP_INTR(1, xfercompl); + if (pdev->cfg.dma_enable == 1) + { + deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[1]->DOEPTSIZ)); + /*ToDo : handle more than one single MPS size packet */ + pdev->dev.out_ep[1].xfer_count = pdev->dev.out_ep[1].maxpacket - \ + deptsiz.b.xfersize; + } + /* Inform upper layer: data ready */ + /* RX COMPLETE */ + USBD_DCD_INT_fops->DataOutStage(pdev , 1); + + } + + /* Endpoint disable */ + if ( doepint.b.epdisabled ) + { + /* Clear the bit in DOEPINTn for this interrupt */ + CLEAR_OUT_EP_INTR(1, epdisabled); + } + /* AHB Error */ + if ( doepint.b.ahberr ) + { + CLEAR_OUT_EP_INTR(1, ahberr); + } + return 1; +} + +/** +* @brief USBD_OTG_EP1IN_ISR_Handler +* handles all USB Interrupts +* @param pdev: device instance +* @retval status +*/ +uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) +{ + + USB_OTG_DIEPINTn_TypeDef diepint; + uint32_t fifoemptymsk, msk, emp; + + msk = USB_OTG_READ_REG32(&pdev->regs.DREGS->DINEP1MSK); + emp = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPEMPMSK); + msk |= ((emp >> 1 ) & 0x1) << 7; + diepint.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[1]->DIEPINT) & msk; + + if ( diepint.b.xfercompl ) + { + fifoemptymsk = 0x1 << 1; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0); + CLEAR_IN_EP_INTR(1, xfercompl); + /* TX COMPLETE */ + USBD_DCD_INT_fops->DataInStage(pdev , 1); + } + if ( diepint.b.ahberr ) + { + CLEAR_IN_EP_INTR(1, ahberr); + } + if ( diepint.b.epdisabled ) + { + CLEAR_IN_EP_INTR(1, epdisabled); + } + if ( diepint.b.timeout ) + { + CLEAR_IN_EP_INTR(1, timeout); + } + if (diepint.b.intktxfemp) + { + CLEAR_IN_EP_INTR(1, intktxfemp); + } + if (diepint.b.intknepmis) + { + CLEAR_IN_EP_INTR(1, intknepmis); + } + if (diepint.b.inepnakeff) + { + CLEAR_IN_EP_INTR(1, inepnakeff); + } + if (diepint.b.emptyintr) + { + DCD_WriteEmptyTxFifo(pdev , 1); + CLEAR_IN_EP_INTR(1, emptyintr); + } + return 1; +} +#endif + +/** +* @brief STM32_USBF_OTG_ISR_Handler +* handles all USB Interrupts +* @param pdev: device instance +* @retval status +*/ +uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintr_status; + uint32_t retval = 0; + + if (USB_OTG_IsDeviceMode(pdev)) /* ensure that we are in device mode */ + { + gintr_status.d32 = USB_OTG_ReadCoreItr(pdev); + if (!gintr_status.d32) /* avoid spurious interrupt */ + { + return 0; + } + + if (gintr_status.b.outepintr) + { + retval |= DCD_HandleOutEP_ISR(pdev); + } + + if (gintr_status.b.inepint) + { + retval |= DCD_HandleInEP_ISR(pdev); + } + + if (gintr_status.b.modemismatch) + { + USB_OTG_GINTSTS_TypeDef gintsts; + + /* Clear interrupt */ + gintsts.d32 = 0; + gintsts.b.modemismatch = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); + } + + if (gintr_status.b.wkupintr) + { + retval |= DCD_HandleResume_ISR(pdev); + } + + if (gintr_status.b.usbsuspend) + { + retval |= DCD_HandleUSBSuspend_ISR(pdev); + } + if (gintr_status.b.sofintr) + { + retval |= DCD_HandleSof_ISR(pdev); + + } + + if (gintr_status.b.rxstsqlvl) + { + retval |= DCD_HandleRxStatusQueueLevel_ISR(pdev); + + } + + if (gintr_status.b.usbreset) + { + retval |= DCD_HandleUsbReset_ISR(pdev); + + } + if (gintr_status.b.enumdone) + { + retval |= DCD_HandleEnumDone_ISR(pdev); + } + + if (gintr_status.b.incomplisoin) + { + retval |= DCD_IsoINIncomplete_ISR(pdev); + } + + if (gintr_status.b.incomplisoout) + { + retval |= DCD_IsoOUTIncomplete_ISR(pdev); + } +#ifdef VBUS_SENSING_ENABLED + if (gintr_status.b.sessreqintr) + { + retval |= DCD_SessionRequest_ISR(pdev); + } + + if (gintr_status.b.otgintr) + { + retval |= DCD_OTG_ISR(pdev); + } +#endif + } + return retval; +} + +#ifdef VBUS_SENSING_ENABLED +/** +* @brief DCD_SessionRequest_ISR +* Indicates that the USB_OTG controller has detected a connection +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_SessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + USBD_DCD_INT_fops->DevConnected (pdev); + + /* Clear interrupt */ + gintsts.d32 = 0; + gintsts.b.sessreqintr = 1; + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32); + return 1; +} + +/** +* @brief DCD_OTG_ISR +* Indicates that the USB_OTG controller has detected an OTG event: +* used to detect the end of session i.e. disconnection +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_OTG_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + + USB_OTG_GOTGINT_TypeDef gotgint; + + gotgint.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGINT); + + if (gotgint.b.sesenddet) + { + USBD_DCD_INT_fops->DevDisconnected (pdev); + } + /* Clear OTG interrupt */ + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGINT, gotgint.d32); + return 1; +} +#endif +/** +* @brief DCD_HandleResume_ISR +* Indicates that the USB_OTG controller has detected a resume or +* remote Wake-up sequence +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_HandleResume_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + USB_OTG_DCTL_TypeDef devctl; + USB_OTG_PCGCCTL_TypeDef power; + + if(pdev->cfg.low_power) + { + /* un-gate USB Core clock */ + power.d32 = USB_OTG_READ_REG32(&pdev->regs.PCGCCTL); + power.b.gatehclk = 0; + power.b.stoppclk = 0; + USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, power.d32); + } + + /* Clear the Remote Wake-up Signaling */ + devctl.d32 = 0; + devctl.b.rmtwkupsig = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, devctl.d32, 0); + + /* Inform upper layer by the Resume Event */ + USBD_DCD_INT_fops->Resume (pdev); + + /* Clear interrupt */ + gintsts.d32 = 0; + gintsts.b.wkupintr = 1; + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32); + return 1; +} + +/** +* @brief USB_OTG_HandleUSBSuspend_ISR +* Indicates that SUSPEND state has been detected on the USB +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + USB_OTG_PCGCCTL_TypeDef power; + USB_OTG_DSTS_TypeDef dsts; + + USBD_DCD_INT_fops->Suspend (pdev); + + dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS); + + /* Clear interrupt */ + gintsts.d32 = 0; + gintsts.b.usbsuspend = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); + + if((pdev->cfg.low_power) && (dsts.b.suspsts == 1)) + { + /* switch-off the clocks */ + power.d32 = 0; + power.b.stoppclk = 1; + USB_OTG_MODIFY_REG32(pdev->regs.PCGCCTL, 0, power.d32); + + power.b.gatehclk = 1; + USB_OTG_MODIFY_REG32(pdev->regs.PCGCCTL, 0, power.d32); + + /* Request to enter Sleep mode after exit from current ISR */ + SCB->SCR |= (SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk); + } + return 1; +} + +/** +* @brief DCD_HandleInEP_ISR +* Indicates that an IN EP has a pending Interrupt +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_DIEPINTn_TypeDef diepint; + + uint32_t ep_intr; + uint32_t epnum = 0; + uint32_t fifoemptymsk; + diepint.d32 = 0; + ep_intr = USB_OTG_ReadDevAllInEPItr(pdev); + + while ( ep_intr ) + { + if (ep_intr&0x1) /* In ITR */ + { + diepint.d32 = DCD_ReadDevInEP(pdev , epnum); /* Get In ITR status */ + if ( diepint.b.xfercompl ) + { + fifoemptymsk = 0x1 << epnum; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0); + CLEAR_IN_EP_INTR(epnum, xfercompl); + /* TX COMPLETE */ + USBD_DCD_INT_fops->DataInStage(pdev , epnum); + + if (pdev->cfg.dma_enable == 1) + { + if((epnum == 0) && (pdev->dev.device_state == USB_OTG_EP0_STATUS_IN)) + { + /* prepare to rx more setup packets */ + USB_OTG_EP0_OutStart(pdev); + } + } + } + if ( diepint.b.ahberr ) + { + CLEAR_IN_EP_INTR(epnum, ahberr); + } + if ( diepint.b.timeout ) + { + CLEAR_IN_EP_INTR(epnum, timeout); + } + if (diepint.b.intktxfemp) + { + CLEAR_IN_EP_INTR(epnum, intktxfemp); + } + if (diepint.b.intknepmis) + { + CLEAR_IN_EP_INTR(epnum, intknepmis); + } + if (diepint.b.inepnakeff) + { + CLEAR_IN_EP_INTR(epnum, inepnakeff); + } + if ( diepint.b.epdisabled ) + { + CLEAR_IN_EP_INTR(epnum, epdisabled); + } + if (diepint.b.emptyintr) + { + + DCD_WriteEmptyTxFifo(pdev , epnum); + + CLEAR_IN_EP_INTR(epnum, emptyintr); + } + } + epnum++; + ep_intr >>= 1; + } + + return 1; +} + +/** +* @brief DCD_HandleOutEP_ISR +* Indicates that an OUT EP has a pending Interrupt +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + uint32_t ep_intr; + USB_OTG_DOEPINTn_TypeDef doepint; + USB_OTG_DEPXFRSIZ_TypeDef deptsiz; + uint32_t epnum = 0; + + doepint.d32 = 0; + + /* Read in the device interrupt bits */ + ep_intr = USB_OTG_ReadDevAllOutEp_itr(pdev); + + while ( ep_intr ) + { + if (ep_intr&0x1) + { + + doepint.d32 = USB_OTG_ReadDevOutEP_itr(pdev, epnum); + + /* Transfer complete */ + if ( doepint.b.xfercompl ) + { + /* Clear the bit in DOEPINTn for this interrupt */ + CLEAR_OUT_EP_INTR(epnum, xfercompl); + if (pdev->cfg.dma_enable == 1) + { + deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[epnum]->DOEPTSIZ)); + /*ToDo : handle more than one single MPS size packet */ + pdev->dev.out_ep[epnum].xfer_count = pdev->dev.out_ep[epnum].maxpacket - \ + deptsiz.b.xfersize; + } + /* Inform upper layer: data ready */ + /* RX COMPLETE */ + USBD_DCD_INT_fops->DataOutStage(pdev , epnum); + + if (pdev->cfg.dma_enable == 1) + { + if((epnum == 0) && (pdev->dev.device_state == USB_OTG_EP0_STATUS_OUT)) + { + /* prepare to rx more setup packets */ + USB_OTG_EP0_OutStart(pdev); + } + } + } + /* Endpoint disable */ + if ( doepint.b.epdisabled ) + { + /* Clear the bit in DOEPINTn for this interrupt */ + CLEAR_OUT_EP_INTR(epnum, epdisabled); + } + /* AHB Error */ + if ( doepint.b.ahberr ) + { + CLEAR_OUT_EP_INTR(epnum, ahberr); + } + /* Setup Phase Done (control EPs) */ + if ( doepint.b.setup ) + { + + /* inform the upper layer that a setup packet is available */ + /* SETUP COMPLETE */ + USBD_DCD_INT_fops->SetupStage(pdev); + CLEAR_OUT_EP_INTR(epnum, setup); + } + } + epnum++; + ep_intr >>= 1; + } + return 1; +} + +/** +* @brief DCD_HandleSof_ISR +* Handles the SOF Interrupts +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_HandleSof_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef GINTSTS; + + + USBD_DCD_INT_fops->SOF(pdev); + + /* Clear interrupt */ + GINTSTS.d32 = 0; + GINTSTS.b.sofintr = 1; + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, GINTSTS.d32); + + return 1; +} + +/** +* @brief DCD_HandleRxStatusQueueLevel_ISR +* Handles the Rx Status Queue Level Interrupt +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_HandleRxStatusQueueLevel_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTMSK_TypeDef int_mask; + USB_OTG_DRXSTS_TypeDef status; + USB_OTG_EP *ep; + + /* Disable the Rx Status Queue Level interrupt */ + int_mask.d32 = 0; + int_mask.b.rxstsqlvl = 1; + USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, int_mask.d32, 0); + + /* Get the Status from the top of the FIFO */ + status.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GRXSTSP ); + + ep = &pdev->dev.out_ep[status.b.epnum]; + + switch (status.b.pktsts) + { + case STS_GOUT_NAK: + break; + case STS_DATA_UPDT: + if (status.b.bcnt) + { + USB_OTG_ReadPacket(pdev,ep->xfer_buff, status.b.bcnt); + ep->xfer_buff += status.b.bcnt; + ep->xfer_count += status.b.bcnt; + } + break; + case STS_XFER_COMP: + break; + case STS_SETUP_COMP: + break; + case STS_SETUP_UPDT: + /* Copy the setup packet received in FIFO into the setup buffer in RAM */ + USB_OTG_ReadPacket(pdev , pdev->dev.setup_packet, 8); + ep->xfer_count += status.b.bcnt; + break; + default: + break; + } + + /* Enable the Rx Status Queue Level interrupt */ + USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, 0, int_mask.d32); + + return 1; +} + +/** +* @brief DCD_WriteEmptyTxFifo +* check FIFO for the next packet to be loaded +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum) +{ + USB_OTG_DTXFSTSn_TypeDef txstatus; + USB_OTG_EP *ep; + uint32_t len = 0; + uint32_t len32b; + txstatus.d32 = 0; + + ep = &pdev->dev.in_ep[epnum]; + + len = ep->xfer_len - ep->xfer_count; + + if (len > ep->maxpacket) + { + len = ep->maxpacket; + } + + len32b = (len + 3) / 4; + txstatus.d32 = USB_OTG_READ_REG32( &pdev->regs.INEP_REGS[epnum]->DTXFSTS); + + while (txstatus.b.txfspcavail > len32b && + ep->xfer_count < ep->xfer_len && + ep->xfer_len != 0) + { + /* Write the FIFO */ + len = ep->xfer_len - ep->xfer_count; + + if (len > ep->maxpacket) + { + len = ep->maxpacket; + } + len32b = (len + 3) / 4; + + USB_OTG_WritePacket (pdev , ep->xfer_buff, epnum, len); + + ep->xfer_buff += len; + ep->xfer_count += len; + + txstatus.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DTXFSTS); + } + + if (ep->xfer_count == ep->xfer_len || ep->xfer_len == 0) { + /* Turn off the Fifo Empty Interrupt */ + uint32_t fifoemptymsk; + + fifoemptymsk = 0x1 << epnum; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0); + } + return 1; +} + +/** +* @brief DCD_HandleUsbReset_ISR +* This interrupt occurs when a USB Reset is detected +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_DAINT_TypeDef daintmsk; + USB_OTG_DOEPMSK_TypeDef doepmsk; + USB_OTG_DIEPMSK_TypeDef diepmsk; + USB_OTG_DCFG_TypeDef dcfg; + USB_OTG_DCTL_TypeDef dctl; + USB_OTG_GINTSTS_TypeDef gintsts; + uint32_t i; + + dctl.d32 = 0; + daintmsk.d32 = 0; + doepmsk.d32 = 0; + diepmsk.d32 = 0; + dcfg.d32 = 0; + gintsts.d32 = 0; + + /* Clear the Remote Wake-up Signaling */ + dctl.b.rmtwkupsig = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, dctl.d32, 0 ); + + /* Flush the Tx FIFO */ + USB_OTG_FlushTxFifo(pdev , 0 ); + + for (i = 0; i < pdev->cfg.dev_endpoints ; i++) + { + USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPINT, 0xFF); + USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xFF); + } + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINT, 0xFFFFFFFF ); + + daintmsk.ep.in = 1; + daintmsk.ep.out = 1; + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, daintmsk.d32 ); + + doepmsk.b.setup = 1; + doepmsk.b.xfercompl = 1; + doepmsk.b.ahberr = 1; + doepmsk.b.epdisabled = 1; + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, doepmsk.d32 ); +#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOUTEP1MSK, doepmsk.d32 ); +#endif + diepmsk.b.xfercompl = 1; + diepmsk.b.timeout = 1; + diepmsk.b.epdisabled = 1; + diepmsk.b.ahberr = 1; + diepmsk.b.intknepmis = 1; + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, diepmsk.d32 ); +#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DINEP1MSK, diepmsk.d32 ); +#endif + /* Reset Device Address */ + dcfg.d32 = USB_OTG_READ_REG32( &pdev->regs.DREGS->DCFG); + dcfg.b.devaddr = 0; + USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DCFG, dcfg.d32); + + + /* setup EP0 to receive SETUP packets */ + USB_OTG_EP0_OutStart(pdev); + + /* Clear interrupt */ + gintsts.d32 = 0; + gintsts.b.usbreset = 1; + USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32); + + /*Reset internal state machine */ + USBD_DCD_INT_fops->Reset(pdev); + return 1; +} + +/** +* @brief DCD_HandleEnumDone_ISR +* Read the device status register and set the device speed +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + USB_OTG_GUSBCFG_TypeDef gusbcfg; + + USB_OTG_EP0Activate(pdev); + + /* Set USB turn-around time based on device speed and PHY interface. */ + gusbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG); + + /* Full or High speed */ + if ( USB_OTG_GetDeviceSpeed(pdev) == USB_SPEED_HIGH) + { + pdev->cfg.speed = USB_OTG_SPEED_HIGH; + pdev->cfg.mps = USB_OTG_HS_MAX_PACKET_SIZE ; + gusbcfg.b.usbtrdtim = 9; + } + else + { + pdev->cfg.speed = USB_OTG_SPEED_FULL; + pdev->cfg.mps = USB_OTG_FS_MAX_PACKET_SIZE ; + gusbcfg.b.usbtrdtim = 5; + } + + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, gusbcfg.d32); + + /* Clear interrupt */ + gintsts.d32 = 0; + gintsts.b.enumdone = 1; + USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, gintsts.d32 ); + return 1; +} + + +/** +* @brief DCD_IsoINIncomplete_ISR +* handle the ISO IN incomplete interrupt +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_IsoINIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + + gintsts.d32 = 0; + + USBD_DCD_INT_fops->IsoINIncomplete (pdev); + + /* Clear interrupt */ + gintsts.b.incomplisoin = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); + + return 1; +} + +/** +* @brief DCD_IsoOUTIncomplete_ISR +* handle the ISO OUT incomplete interrupt +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_IsoOUTIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + + gintsts.d32 = 0; + + USBD_DCD_INT_fops->IsoOUTIncomplete (pdev); + + /* Clear interrupt */ + gintsts.b.incomplisoout = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); + return 1; +} +/** +* @brief DCD_ReadDevInEP +* Reads ep flags +* @param pdev: device instance +* @retval status +*/ +static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum) +{ + uint32_t v, msk, emp; + msk = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPMSK); + emp = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPEMPMSK); + msk |= ((emp >> epnum) & 0x1) << 7; + v = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DIEPINT) & msk; + return v; +} + + + +/** +* @} +*/ + +/** +* @} +*/ + +/** +* @} +*/ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_hcd.c b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_hcd.c new file mode 100644 index 000000000..689d061ae --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_hcd.c @@ -0,0 +1,256 @@ +/** + ****************************************************************************** + * @file usb_hcd.c + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Host Interface Layer + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_core.h" +#include "usb_hcd.h" +#include "usb_conf.h" +#include "usb_bsp.h" + + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_HCD + * @brief This file is the interface between EFSL ans Host mass-storage class + * @{ + */ + + +/** @defgroup USB_HCD_Private_Defines + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + + + +/** @defgroup USB_HCD_Private_Macros + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_Private_Variables + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_Private_FunctionPrototypes + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_Private_Functions + * @{ + */ + +/** + * @brief HCD_Init + * Initialize the HOST portion of the driver. + * @param pdev: Selected device + * @param base_address: OTG base address + * @retval Status + */ +uint32_t HCD_Init(USB_OTG_CORE_HANDLE *pdev , + USB_OTG_CORE_ID_TypeDef coreID) +{ + uint8_t i = 0; + pdev->host.ConnSts = 0; + + for (i= 0; i< USB_OTG_MAX_TX_FIFOS; i++) + { + pdev->host.ErrCnt[i] = 0; + pdev->host.XferCnt[i] = 0; + pdev->host.HC_Status[i] = HC_IDLE; + } + pdev->host.hc[0].max_packet = 8; + + USB_OTG_SelectCore(pdev, coreID); +#ifndef DUAL_ROLE_MODE_ENABLED + USB_OTG_DisableGlobalInt(pdev); + USB_OTG_CoreInit(pdev); + + /* Force Host Mode*/ + USB_OTG_SetCurrentMode(pdev , HOST_MODE); + USB_OTG_CoreInitHost(pdev); + USB_OTG_EnableGlobalInt(pdev); +#endif + + return 0; +} + + +/** + * @brief HCD_GetCurrentSpeed + * Get Current device Speed. + * @param pdev : Selected device + * @retval Status + */ + +uint32_t HCD_GetCurrentSpeed (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_HPRT0_TypeDef HPRT0; + HPRT0.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0); + + return HPRT0.b.prtspd; +} + +/** + * @brief HCD_ResetPort + * Issues the reset command to device + * @param pdev : Selected device + * @retval Status + */ +uint32_t HCD_ResetPort(USB_OTG_CORE_HANDLE *pdev) +{ + /* + Before starting to drive a USB reset, the application waits for the OTG + interrupt triggered by the debounce done bit (DBCDNE bit in OTG_FS_GOTGINT), + which indicates that the bus is stable again after the electrical debounce + caused by the attachment of a pull-up resistor on DP (FS) or DM (LS). + */ + + USB_OTG_ResetPort(pdev); + return 0; +} + +/** + * @brief HCD_IsDeviceConnected + * Check if the device is connected. + * @param pdev : Selected device + * @retval Device connection status. 1 -> connected and 0 -> disconnected + * + */ +uint32_t HCD_IsDeviceConnected(USB_OTG_CORE_HANDLE *pdev) +{ + return (pdev->host.ConnSts); +} + +/** + * @brief HCD_GetCurrentFrame + * This function returns the frame number for sof packet + * @param pdev : Selected device + * @retval Frame number + * + */ +uint32_t HCD_GetCurrentFrame (USB_OTG_CORE_HANDLE *pdev) +{ + return (USB_OTG_READ_REG32(&pdev->regs.HREGS->HFNUM) & 0xFFFF) ; +} + +/** + * @brief HCD_GetURB_State + * This function returns the last URBstate + * @param pdev: Selected device + * @retval URB_STATE + * + */ +URB_STATE HCD_GetURB_State (USB_OTG_CORE_HANDLE *pdev , uint8_t ch_num) +{ + return pdev->host.URB_State[ch_num] ; +} + +/** + * @brief HCD_GetXferCnt + * This function returns the last URBstate + * @param pdev: Selected device + * @retval No. of data bytes transferred + * + */ +uint32_t HCD_GetXferCnt (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num) +{ + return pdev->host.XferCnt[ch_num] ; +} + + + +/** + * @brief HCD_GetHCState + * This function returns the HC Status + * @param pdev: Selected device + * @retval HC_STATUS + * + */ +HC_STATUS HCD_GetHCState (USB_OTG_CORE_HANDLE *pdev , uint8_t ch_num) +{ + return pdev->host.HC_Status[ch_num] ; +} + +/** + * @brief HCD_HC_Init + * This function prepare a HC and start a transfer + * @param pdev: Selected device + * @param hc_num: Channel number + * @retval status + */ +uint32_t HCD_HC_Init (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) +{ + return USB_OTG_HC_Init(pdev, hc_num); +} + +/** + * @brief HCD_SubmitRequest + * This function prepare a HC and start a transfer + * @param pdev: Selected device + * @param hc_num: Channel number + * @retval status + */ +uint32_t HCD_SubmitRequest (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) +{ + + pdev->host.URB_State[hc_num] = URB_IDLE; + pdev->host.hc[hc_num].xfer_count = 0 ; + return USB_OTG_HC_StartXfer(pdev, hc_num); +} + + +/** +* @} +*/ + +/** +* @} +*/ + +/** +* @} +*/ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_hcd_int.c b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_hcd_int.c new file mode 100644 index 000000000..bd4081fb3 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_hcd_int.c @@ -0,0 +1,832 @@ +/** + ****************************************************************************** + * @file usb_hcd_int.c + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief Host driver interrupt subroutines + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_core.h" +#include "usb_defines.h" +#include "usb_hcd_int.h" + +#if defined (__CC_ARM) /*!< ARM Compiler */ + #pragma O0 +#elif defined ( __ICCARM__ ) /*!< IAR Compiler */ + #pragma O0 +#elif defined (__GNUC__) /*!< GNU Compiler */ + #pragma GCC optimize ("O0") +#elif defined (__TASKING__) /*!< TASKING Compiler */ + #pragma optimize=0 + +#endif /* __CC_ARM */ + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_HCD_INT + * @brief This file contains the interrupt subroutines for the Host mode. + * @{ + */ + + +/** @defgroup USB_HCD_INT_Private_Defines + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_INT_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + + + +/** @defgroup USB_HCD_INT_Private_Macros + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_INT_Private_Variables + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_HCD_INT_Private_FunctionPrototypes + * @{ + */ + +static uint32_t USB_OTG_USBH_handle_sof_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t USB_OTG_USBH_handle_port_ISR(USB_OTG_CORE_HANDLE *pdev); +static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev); +static uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , + uint32_t num); +static uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , + uint32_t num); +static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev); +static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev); +static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev); +static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev); +static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HANDLE *pdev); + +/** + * @} + */ + + +/** @defgroup USB_HCD_INT_Private_Functions + * @{ + */ + +/** + * @brief HOST_Handle_ISR + * This function handles all USB Host Interrupts + * @param pdev: Selected device + * @retval status + */ + +uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + uint32_t retval = 0; + + gintsts.d32 = 0; + + /* Check if HOST Mode */ + if (USB_OTG_IsHostMode(pdev)) + { + gintsts.d32 = USB_OTG_ReadCoreItr(pdev); + if (!gintsts.d32) + { + return 0; + } + + if (gintsts.b.sofintr) + { + retval |= USB_OTG_USBH_handle_sof_ISR (pdev); + } + + if (gintsts.b.rxstsqlvl) + { + retval |= USB_OTG_USBH_handle_rx_qlvl_ISR (pdev); + } + + if (gintsts.b.nptxfempty) + { + retval |= USB_OTG_USBH_handle_nptxfempty_ISR (pdev); + } + + if (gintsts.b.ptxfempty) + { + retval |= USB_OTG_USBH_handle_ptxfempty_ISR (pdev); + } + + if (gintsts.b.hcintr) + { + retval |= USB_OTG_USBH_handle_hc_ISR (pdev); + } + + if (gintsts.b.portintr) + { + retval |= USB_OTG_USBH_handle_port_ISR (pdev); + } + + if (gintsts.b.disconnect) + { + retval |= USB_OTG_USBH_handle_Disconnect_ISR (pdev); + + } + + if (gintsts.b.incomplisoout) + { + retval |= USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (pdev); + } + + + } + return retval; +} + +/** + * @brief USB_OTG_USBH_handle_hc_ISR + * This function indicates that one or more host channels has a pending + * @param pdev: Selected device + * @retval status + */ +static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_HAINT_TypeDef haint; + USB_OTG_HCCHAR_TypeDef hcchar; + uint32_t i = 0; + uint32_t retval = 0; + + /* Clear appropriate bits in HCINTn to clear the interrupt bit in + * GINTSTS */ + + haint.d32 = USB_OTG_ReadHostAllChannels_intr(pdev); + + for (i = 0; i < pdev->cfg.host_channels ; i++) + { + if (haint.b.chint & (1 << i)) + { + hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[i]->HCCHAR); + + if (hcchar.b.epdir) + { + retval |= USB_OTG_USBH_handle_hc_n_In_ISR (pdev, i); + } + else + { + retval |= USB_OTG_USBH_handle_hc_n_Out_ISR (pdev, i); + } + } + } + + return retval; +} + +/** + * @brief USB_OTG_otg_hcd_handle_sof_intr + * Handles the start-of-frame interrupt in host mode. + * @param pdev: Selected device + * @retval status + */ +static uint32_t USB_OTG_USBH_handle_sof_ISR (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + + + gintsts.d32 = 0; + /* Clear interrupt */ + gintsts.b.sofintr = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); + + return 1; +} + +/** + * @brief USB_OTG_USBH_handle_Disconnect_ISR + * Handles disconnect event. + * @param pdev: Selected device + * @retval status + */ +static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + + pdev->host.ConnSts = 0; + gintsts.d32 = 0; + + pdev->host.port_cb->Disconnect(pdev); + + /* Clear interrupt */ + gintsts.b.disconnect = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); + + return 1; +} + +/** + * @brief USB_OTG_USBH_handle_nptxfempty_ISR + * Handles non periodic tx fifo empty. + * @param pdev: Selected device + * @retval status + */ +static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTMSK_TypeDef intmsk; + USB_OTG_HNPTXSTS_TypeDef hnptxsts; + uint16_t len_words , len; + + hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS); + + len_words = (pdev->host.hc[hnptxsts.b.chnum].xfer_len + 3) / 4; + + while ((hnptxsts.b.nptxfspcavail > len_words)&& + (pdev->host.hc[hnptxsts.b.chnum].xfer_len != 0)) + { + + len = hnptxsts.b.nptxfspcavail * 4; + + if (len > pdev->host.hc[hnptxsts.b.chnum].xfer_len) + { + /* Last packet */ + len = pdev->host.hc[hnptxsts.b.chnum].xfer_len; + + intmsk.d32 = 0; + intmsk.b.nptxfempty = 1; + USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0); + } + + len_words = (pdev->host.hc[hnptxsts.b.chnum].xfer_len + 3) / 4; + + USB_OTG_WritePacket (pdev , pdev->host.hc[hnptxsts.b.chnum].xfer_buff, hnptxsts.b.chnum, len); + + pdev->host.hc[hnptxsts.b.chnum].xfer_buff += len; + pdev->host.hc[hnptxsts.b.chnum].xfer_len -= len; + pdev->host.hc[hnptxsts.b.chnum].xfer_count += len; + + hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS); + } + + return 1; +} + +/** + * @brief USB_OTG_USBH_handle_ptxfempty_ISR + * Handles periodic tx fifo empty + * @param pdev: Selected device + * @retval status + */ +static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTMSK_TypeDef intmsk; + USB_OTG_HPTXSTS_TypeDef hptxsts; + uint16_t len_words , len; + + hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS); + + len_words = (pdev->host.hc[hptxsts.b.chnum].xfer_len + 3) / 4; + + while ((hptxsts.b.ptxfspcavail > len_words)&& + (pdev->host.hc[hptxsts.b.chnum].xfer_len != 0)) + { + + len = hptxsts.b.ptxfspcavail * 4; + + if (len > pdev->host.hc[hptxsts.b.chnum].xfer_len) + { + len = pdev->host.hc[hptxsts.b.chnum].xfer_len; + /* Last packet */ + intmsk.d32 = 0; + intmsk.b.ptxfempty = 1; + USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0); + } + + len_words = (pdev->host.hc[hptxsts.b.chnum].xfer_len + 3) / 4; + + USB_OTG_WritePacket (pdev , pdev->host.hc[hptxsts.b.chnum].xfer_buff, hptxsts.b.chnum, len); + + pdev->host.hc[hptxsts.b.chnum].xfer_buff += len; + pdev->host.hc[hptxsts.b.chnum].xfer_len -= len; + pdev->host.hc[hptxsts.b.chnum].xfer_count += len; + + hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS); + } + + return 1; +} + +/** + * @brief USB_OTG_USBH_handle_port_ISR + * This function determines which interrupt conditions have occurred + * @param pdev: Selected device + * @retval status + */ +static uint32_t USB_OTG_USBH_handle_port_ISR (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_HPRT0_TypeDef hprt0; + USB_OTG_HPRT0_TypeDef hprt0_dup; + USB_OTG_HCFG_TypeDef hcfg; + uint32_t do_reset = 0; + uint32_t retval = 0; + + hcfg.d32 = 0; + hprt0.d32 = 0; + hprt0_dup.d32 = 0; + + hprt0.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0); + hprt0_dup.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0); + + /* Clear the interrupt bits in GINTSTS */ + + hprt0_dup.b.prtena = 0; + hprt0_dup.b.prtconndet = 0; + hprt0_dup.b.prtenchng = 0; + hprt0_dup.b.prtovrcurrchng = 0; + + /* Port Connect Detected */ + if (hprt0.b.prtconndet) + { + pdev->host.port_cb->Connect(pdev); + hprt0_dup.b.prtconndet = 1; + do_reset = 1; + retval |= 1; + } + + /* Port Enable Changed */ + if (hprt0.b.prtenchng) + { + hprt0_dup.b.prtenchng = 1; + if (hprt0.b.prtena == 1) + { + pdev->host.ConnSts = 1; + + if ((hprt0.b.prtspd == HPRT0_PRTSPD_LOW_SPEED) || + (hprt0.b.prtspd == HPRT0_PRTSPD_FULL_SPEED)) + { + + hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG); + + if (hprt0.b.prtspd == HPRT0_PRTSPD_LOW_SPEED) + { + USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 6000 ); + if (hcfg.b.fslspclksel != HCFG_6_MHZ) + { + if(pdev->cfg.coreID == USB_OTG_FS_CORE_ID) + { + USB_OTG_InitFSLSPClkSel(pdev ,HCFG_6_MHZ ); + } + do_reset = 1; + } + } + else + { + + USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 48000 ); + if (hcfg.b.fslspclksel != HCFG_48_MHZ) + { + USB_OTG_InitFSLSPClkSel(pdev ,HCFG_48_MHZ ); + do_reset = 1; + } + } + } + else + { + do_reset = 1; + } + } + } + /* Overcurrent Change Interrupt */ + if (hprt0.b.prtovrcurrchng) + { + hprt0_dup.b.prtovrcurrchng = 1; + retval |= 1; + } + if (do_reset) + { + USB_OTG_ResetPort(pdev); + + } + /* Clear Port Interrupts */ + USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0_dup.d32); + + return retval; +} + +/** + * @brief USB_OTG_USBH_handle_hc_n_Out_ISR + * Handles interrupt for a specific Host Channel + * @param pdev: Selected device + * @param hc_num: Channel number + * @retval status + */ +uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t num) +{ + + USB_OTG_HCINTn_TypeDef hcint; + USB_OTG_HCGINTMSK_TypeDef hcintmsk; + USB_OTG_HC_REGS *hcreg; + USB_OTG_HCCHAR_TypeDef hcchar; + + hcreg = pdev->regs.HC_REGS[num]; + hcint.d32 = USB_OTG_READ_REG32(&hcreg->HCINT); + hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCGINTMSK); + hcint.d32 = hcint.d32 & hcintmsk.d32; + + hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR); + + if (hcint.b.ahberr) + { + CLEAR_HC_INT(hcreg ,ahberr); + UNMASK_HOST_INT_CHH (num); + } + else if (hcint.b.ack) + { + CLEAR_HC_INT(hcreg , ack); + } + + else if (hcint.b.xfercompl) + { + pdev->host.ErrCnt[num] = 0; + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg , xfercompl); + pdev->host.HC_Status[num] = HC_XFRC; + } + + else if (hcint.b.stall) + { + CLEAR_HC_INT(hcreg , stall); + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + pdev->host.HC_Status[num] = HC_STALL; + } + + else if (hcint.b.nak) + { + pdev->host.ErrCnt[num] = 0; + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg , nak); + pdev->host.HC_Status[num] = HC_NAK; + } + + else if (hcint.b.xacterr) + { + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + pdev->host.ErrCnt[num] ++; + pdev->host.HC_Status[num] = HC_XACTERR; + CLEAR_HC_INT(hcreg , xacterr); + } + else if (hcint.b.nyet) + { + pdev->host.ErrCnt[num] = 0; + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg , nyet); + pdev->host.HC_Status[num] = HC_NYET; + } + else if (hcint.b.datatglerr) + { + + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg , nak); + pdev->host.HC_Status[num] = HC_DATATGLERR; + + CLEAR_HC_INT(hcreg , datatglerr); + } + else if (hcint.b.chhltd) + { + MASK_HOST_INT_CHH (num); + + if(pdev->host.HC_Status[num] == HC_XFRC) + { + pdev->host.URB_State[num] = URB_DONE; + + if (hcchar.b.eptype == EP_TYPE_BULK) + { + pdev->host.hc[num].toggle_out ^= 1; + } + } + else if(pdev->host.HC_Status[num] == HC_NAK) + { + pdev->host.URB_State[num] = URB_NOTREADY; + } + else if(pdev->host.HC_Status[num] == HC_NYET) + { + if(pdev->host.hc[num].do_ping == 1) + { + USB_OTG_HC_DoPing(pdev, num); + } + pdev->host.URB_State[num] = URB_NOTREADY; + } + else if(pdev->host.HC_Status[num] == HC_STALL) + { + pdev->host.URB_State[num] = URB_STALL; + } + else if(pdev->host.HC_Status[num] == HC_XACTERR) + { + if (pdev->host.ErrCnt[num] == 3) + { + pdev->host.URB_State[num] = URB_ERROR; + pdev->host.ErrCnt[num] = 0; + } + } + CLEAR_HC_INT(hcreg , chhltd); + } + + + return 1; +} + +/** + * @brief USB_OTG_USBH_handle_hc_n_In_ISR + * Handles interrupt for a specific Host Channel + * @param pdev: Selected device + * @param hc_num: Channel number + * @retval status + */ +uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t num) +{ + USB_OTG_HCINTn_TypeDef hcint; + USB_OTG_HCGINTMSK_TypeDef hcintmsk; + USB_OTG_HCCHAR_TypeDef hcchar; + USB_OTG_HCTSIZn_TypeDef hctsiz; + USB_OTG_HC_REGS *hcreg; + + + hcreg = pdev->regs.HC_REGS[num]; + hcint.d32 = USB_OTG_READ_REG32(&hcreg->HCINT); + hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCGINTMSK); + hcint.d32 = hcint.d32 & hcintmsk.d32; + hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR); + hcintmsk.d32 = 0; + + + if (hcint.b.ahberr) + { + CLEAR_HC_INT(hcreg ,ahberr); + UNMASK_HOST_INT_CHH (num); + } + else if (hcint.b.ack) + { + CLEAR_HC_INT(hcreg ,ack); + } + + else if (hcint.b.stall) + { + UNMASK_HOST_INT_CHH (num); + pdev->host.HC_Status[num] = HC_STALL; + CLEAR_HC_INT(hcreg , nak); /* Clear the NAK Condition */ + CLEAR_HC_INT(hcreg , stall); /* Clear the STALL Condition */ + hcint.b.nak = 0; /* NOTE: When there is a 'stall', reset also nak, + else, the pdev->host.HC_Status = HC_STALL + will be overwritten by 'nak' in code below */ + USB_OTG_HC_Halt(pdev, num); + } + else if (hcint.b.datatglerr) + { + + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg , nak); + pdev->host.HC_Status[num] = HC_DATATGLERR; + CLEAR_HC_INT(hcreg , datatglerr); + } + + if (hcint.b.frmovrun) + { + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg ,frmovrun); + } + + else if (hcint.b.xfercompl) + { + + if (pdev->cfg.dma_enable == 1) + { + hctsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCTSIZ); + pdev->host.XferCnt[num] = pdev->host.hc[num].xfer_len - hctsiz.b.xfersize; + } + + pdev->host.HC_Status[num] = HC_XFRC; + pdev->host.ErrCnt [num]= 0; + CLEAR_HC_INT(hcreg , xfercompl); + + if ((hcchar.b.eptype == EP_TYPE_CTRL)|| + (hcchar.b.eptype == EP_TYPE_BULK)) + { + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg , nak); + pdev->host.hc[num].toggle_in ^= 1; + + } + else if(hcchar.b.eptype == EP_TYPE_INTR) + { + hcchar.b.oddfrm = 1; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[num]->HCCHAR, hcchar.d32); + pdev->host.URB_State[num] = URB_DONE; + } + + } + else if (hcint.b.chhltd) + { + MASK_HOST_INT_CHH (num); + + if(pdev->host.HC_Status[num] == HC_XFRC) + { + pdev->host.URB_State[num] = URB_DONE; + } + + else if (pdev->host.HC_Status[num] == HC_STALL) + { + pdev->host.URB_State[num] = URB_STALL; + } + + else if((pdev->host.HC_Status[num] == HC_XACTERR) || + (pdev->host.HC_Status[num] == HC_DATATGLERR)) + { + pdev->host.ErrCnt[num] = 0; + pdev->host.URB_State[num] = URB_ERROR; + + } + else if(hcchar.b.eptype == EP_TYPE_INTR) + { + pdev->host.hc[num].toggle_in ^= 1; + } + + CLEAR_HC_INT(hcreg , chhltd); + + } + else if (hcint.b.xacterr) + { + UNMASK_HOST_INT_CHH (num); + pdev->host.ErrCnt[num] ++; + pdev->host.HC_Status[num] = HC_XACTERR; + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg , xacterr); + + } + else if (hcint.b.nak) + { + if(hcchar.b.eptype == EP_TYPE_INTR) + { + UNMASK_HOST_INT_CHH (num); + USB_OTG_HC_Halt(pdev, num); + CLEAR_HC_INT(hcreg , nak); + } + else if ((hcchar.b.eptype == EP_TYPE_CTRL)|| + (hcchar.b.eptype == EP_TYPE_BULK)) + { + /* re-activate the channel */ + hcchar.b.chen = 1; + hcchar.b.chdis = 0; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[num]->HCCHAR, hcchar.d32); + } + pdev->host.HC_Status[num] = HC_NAK; + } + + + return 1; + +} + +/** + * @brief USB_OTG_USBH_handle_rx_qlvl_ISR + * Handles the Rx Status Queue Level Interrupt + * @param pdev: Selected device + * @retval status + */ + +static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GRXFSTS_TypeDef grxsts; + USB_OTG_GINTMSK_TypeDef intmsk; + USB_OTG_HCTSIZn_TypeDef hctsiz; + USB_OTG_HCCHAR_TypeDef hcchar; + __IO uint8_t channelnum =0; + uint32_t count; + + /* Disable the Rx Status Queue Level interrupt */ + intmsk.d32 = 0; + intmsk.b.rxstsqlvl = 1; + USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0); + + grxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GRXSTSP); + channelnum = grxsts.b.chnum; + hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[channelnum]->HCCHAR); + + switch (grxsts.b.pktsts) + { + case GRXSTS_PKTSTS_IN: + /* Read the data into the host buffer. */ + if ((grxsts.b.bcnt > 0) && (pdev->host.hc[channelnum].xfer_buff != (void *)0)) + { + + USB_OTG_ReadPacket(pdev, pdev->host.hc[channelnum].xfer_buff, grxsts.b.bcnt); + /*manage multiple Xfer */ + pdev->host.hc[grxsts.b.chnum].xfer_buff += grxsts.b.bcnt; + pdev->host.hc[grxsts.b.chnum].xfer_count += grxsts.b.bcnt; + + + count = pdev->host.hc[channelnum].xfer_count; + pdev->host.XferCnt[channelnum] = count; + + hctsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[channelnum]->HCTSIZ); + if(hctsiz.b.pktcnt > 0) + { + /* re-activate the channel when more packets are expected */ + hcchar.b.chen = 1; + hcchar.b.chdis = 0; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[channelnum]->HCCHAR, hcchar.d32); + } + } + break; + + case GRXSTS_PKTSTS_IN_XFER_COMP: + + case GRXSTS_PKTSTS_DATA_TOGGLE_ERR: + case GRXSTS_PKTSTS_CH_HALTED: + default: + break; + } + + /* Enable the Rx Status Queue Level interrupt */ + intmsk.b.rxstsqlvl = 1; + USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, 0, intmsk.d32); + return 1; +} + +/** + * @brief USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR + * Handles the incomplete Periodic transfer Interrupt + * @param pdev: Selected device + * @retval status + */ +static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HANDLE *pdev) +{ + + USB_OTG_GINTSTS_TypeDef gintsts; + USB_OTG_HCCHAR_TypeDef hcchar; + + + + + hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[0]->HCCHAR); + hcchar.b.chen = 1; + hcchar.b.chdis = 1; + USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[0]->HCCHAR, hcchar.d32); + + gintsts.d32 = 0; + /* Clear interrupt */ + gintsts.b.incomplisoout = 1; + USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32); + + return 1; +} + +/** +* @} +*/ + +/** +* @} +*/ + +/** +* @} +*/ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_otg.c b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_otg.c new file mode 100644 index 000000000..fbb71ecb4 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/STM32_USB_OTG_Driver/src/usb_otg.c @@ -0,0 +1,175 @@ +/** + ****************************************************************************** + * @file usb_otg.c + * @author MCD Application Team + * @version V2.0.0 + * @date 22-July-2011 + * @brief OTG Core Layer + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_defines.h" +#include "usb_regs.h" +#include "usb_core.h" +#include "usb_otg.h" + +/** @addtogroup USB_OTG_DRIVER + * @{ + */ + +/** @defgroup USB_OTG + * @brief This file is the interface between EFSL ans Host mass-storage class + * @{ + */ + + +/** @defgroup USB_OTG_Private_Defines + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_OTG_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + + + +/** @defgroup USB_OTG_Private_Macros + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_OTG_Private_Variables + * @{ + */ +/** + * @} + */ + + +/** @defgroup USB_OTG_Private_FunctionPrototypes + * @{ + */ + +static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev); + +/** + * @} + */ + + +/** @defgroup USB_OTG_Private_Functions + * @{ + */ + + +/* OTG Interrupt Handler */ + + +/** + * @brief STM32_USBO_OTG_ISR_Handler + * + * @param None + * @retval : None + */ +uint32_t STM32_USBO_OTG_ISR_Handler(USB_OTG_CORE_HANDLE *pdev) +{ + uint32_t retval = 0; + USB_OTG_GINTSTS_TypeDef gintsts ; + gintsts.d32 = 0; + + gintsts.d32 = USB_OTG_Read_itr(pdev); + if (gintsts.d32 == 0) + { + return 0; + } + if (gintsts.b.otgintr) + { + retval |= 1;//USB_OTG_HandleOTG_ISR(pdev); + } + if (gintsts.b.conidstschng) + { + retval |= 2;//USB_OTG_HandleConnectorIDStatusChange_ISR(pdev); + } + if (gintsts.b.sessreqintr) + { + retval |= 3;//USB_OTG_HandleSessionRequest_ISR(pdev); + } + return retval; +} + + +/** + * @brief USB_OTG_Read_itr + * returns the Core Interrupt register + * @param None + * @retval : status + */ +static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev) +{ + USB_OTG_GINTSTS_TypeDef gintsts; + USB_OTG_GINTMSK_TypeDef gintmsk; + USB_OTG_GINTMSK_TypeDef gintmsk_common; + + + gintsts.d32 = 0; + gintmsk.d32 = 0; + gintmsk_common.d32 = 0; + + /* OTG interrupts */ + gintmsk_common.b.sessreqintr = 1; + gintmsk_common.b.conidstschng = 1; + gintmsk_common.b.otgintr = 1; + + gintsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTSTS); + gintmsk.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTMSK); + return ((gintsts.d32 & gintmsk.d32 ) & gintmsk_common.d32); +} + + +/** + * @brief USB_OTG_GetCurrentState + * Return current OTG State + * @param None + * @retval : None + */ +uint32_t USB_OTG_GetCurrentState (USB_OTG_CORE_HANDLE *pdev) +{ + return pdev->otg.OTG_State; +} + + +/** +* @} +*/ + +/** +* @} +*/ + +/** +* @} +*/ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/inc/pios_i2c_config.h b/flight/PiOS/STM32F4xx/inc/pios_i2c_config.h new file mode 100644 index 000000000..e269c0fe4 --- /dev/null +++ b/flight/PiOS/STM32F4xx/inc/pios_i2c_config.h @@ -0,0 +1,67 @@ +/* + * pios_i2c_config.h + * + * Created on: May 8, 2011 + * Author: Michael Smith + */ + +#ifndef PIOS_I2C_CONFIG_H_ +#define PIOS_I2C_CONFIG_H_ + +/** + * Generic I2C configuration for the STM32F4xx + */ +#define I2C_CONFIG(_i2c, _scl_gpio, _scl_pin, _sda_gpio, _sda_pin) \ +{ \ + .regs = _i2c, \ + .remap = GPIO_AF_ ## _i2c, \ + .init = { \ + .I2C_ClockSpeed = 400000, /* bits/s */ \ + .I2C_Mode = I2C_Mode_I2C, \ + .I2C_DutyCycle = I2C_DutyCycle_2, \ + .I2C_OwnAddress1 = 0, \ + .I2C_Ack = I2C_Ack_Enable, \ + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, \ + }, \ + .transfer_timeout_ms = 50, \ + .scl = { \ + .gpio = _scl_gpio, \ + .init = { \ + .GPIO_Pin = _scl_pin, \ + .GPIO_Mode = GPIO_Mode_AF, \ + .GPIO_Speed = GPIO_Speed_50MHz, \ + .GPIO_OType = GPIO_OType_OD, \ + .GPIO_PuPd = GPIO_PuPd_NOPULL, \ + }, \ + }, \ + .sda = { \ + .gpio = _sda_gpio, \ + .init = { \ + .GPIO_Pin = _sda_pin, \ + .GPIO_Mode = GPIO_Mode_AF, \ + .GPIO_Speed = GPIO_Speed_50MHz, \ + .GPIO_OType = GPIO_OType_OD, \ + .GPIO_PuPd = GPIO_PuPd_NOPULL, \ + }, \ + }, \ + .event = { \ + .flags = 0, /* FIXME: check this */ \ + .init = { \ + .NVIC_IRQChannel = _i2c ## _EV_IRQn, \ + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, \ + .NVIC_IRQChannelSubPriority = 0, \ + .NVIC_IRQChannelCmd = ENABLE, \ + }, \ + }, \ + .error = { \ + .flags = 0, /* FIXME: check this */ \ + .init = { \ + .NVIC_IRQChannel = _i2c ## _ER_IRQn, \ + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, \ + .NVIC_IRQChannelSubPriority = 0, \ + .NVIC_IRQChannelCmd = ENABLE, \ + }, \ + }, \ +} + +#endif /* PIOS_I2C_CONFIG_H_ */ diff --git a/flight/PiOS/STM32F4xx/inc/pios_usart_config.h b/flight/PiOS/STM32F4xx/inc/pios_usart_config.h new file mode 100644 index 000000000..4abed4e15 --- /dev/null +++ b/flight/PiOS/STM32F4xx/inc/pios_usart_config.h @@ -0,0 +1,56 @@ +/* + * pios_usart_config.h + * + * Created on: May 8, 2011 + * Author: Michael Smioth + */ + +#ifndef PIOS_USART_CONFIG_H_ +#define PIOS_USART_CONFIG_H_ + +/** + * Generic USART configuration structure for an STM32F2xx port. + */ +#define USART_CONFIG(_usart, _baudrate, _rx_gpio, _rx_pin, _tx_gpio, _tx_pin) \ +{ \ + .regs = _usart, \ + .remap = GPIO_AF_ ## _usart, \ + .init = { \ + .USART_BaudRate = _baudrate, \ + .USART_WordLength = USART_WordLength_8b, \ + .USART_Parity = USART_Parity_No, \ + .USART_StopBits = USART_StopBits_1, \ + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, \ + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, \ + }, \ + .irq = { \ + .init = { \ + .NVIC_IRQChannel = _usart ## _IRQn, \ + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, \ + .NVIC_IRQChannelSubPriority = 0, \ + .NVIC_IRQChannelCmd = ENABLE, \ + }, \ + }, \ + .rx = { \ + .gpio = _rx_gpio, \ + .init = { \ + .GPIO_Pin = _rx_pin, \ + .GPIO_Mode = GPIO_Mode_AF, \ + .GPIO_Speed = GPIO_Speed_50MHz, \ + .GPIO_OType = GPIO_OType_PP, \ + .GPIO_PuPd = GPIO_PuPd_UP, \ + }, \ + }, \ + .tx = { \ + .gpio = _tx_gpio, \ + .init = { \ + .GPIO_Pin = _tx_pin, \ + .GPIO_Mode = GPIO_Mode_AF, \ + .GPIO_Speed = GPIO_Speed_50MHz, \ + .GPIO_OType = GPIO_OType_PP, \ + .GPIO_PuPd = GPIO_PuPd_UP, \ + }, \ + }, \ +} + +#endif /* PIOS_USART_CONFIG_H_ */ diff --git a/flight/PiOS/STM32F4xx/inc/stm32f4xx_conf.h b/flight/PiOS/STM32F4xx/inc/stm32f4xx_conf.h new file mode 100644 index 000000000..673f5f3d0 --- /dev/null +++ b/flight/PiOS/STM32F4xx/inc/stm32f4xx_conf.h @@ -0,0 +1,88 @@ +/** + ****************************************************************************** + * @file Project/STM32F4xx_StdPeriph_Templates/stm32f4xx_conf.h + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief Library configuration file. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_CONF_H +#define __STM32F4xx_CONF_H + +/* Includes ------------------------------------------------------------------*/ +/* Uncomment the line below to enable peripheral header file inclusion */ +#include "stm32f4xx_adc.h" +#include "stm32f4xx_can.h" +#include "stm32f4xx_crc.h" +#include "stm32f4xx_cryp.h" +#include "stm32f4xx_dac.h" +#include "stm32f4xx_dbgmcu.h" +#include "stm32f4xx_dcmi.h" +#include "stm32f4xx_dma.h" +#include "stm32f4xx_exti.h" +#include "stm32f4xx_flash.h" +#include "stm32f4xx_fsmc.h" +#include "stm32f4xx_hash.h" +#include "stm32f4xx_gpio.h" +#include "stm32f4xx_i2c.h" +#include "stm32f4xx_iwdg.h" +#include "stm32f4xx_pwr.h" +#include "stm32f4xx_rcc.h" +#include "stm32f4xx_rng.h" +#include "stm32f4xx_rtc.h" +#include "stm32f4xx_sdio.h" +#include "stm32f4xx_spi.h" +#include "stm32f4xx_syscfg.h" +#include "stm32f4xx_tim.h" +#include "stm32f4xx_usart.h" +#include "stm32f4xx_wwdg.h" +#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* If an external clock source is used, then the value of the following define + should be set to the value of the external clock source, else, if no external + clock is used, keep this define commented */ +/*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */ + + +/* Uncomment the line below to expanse the "assert_param" macro in the + Standard Peripheral Library drivers code */ +/* #define USE_FULL_ASSERT 1 */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT + +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + +#endif /* __STM32F4xx_CONF_H */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/library.mk b/flight/PiOS/STM32F4xx/library.mk new file mode 100644 index 000000000..c86ea86ce --- /dev/null +++ b/flight/PiOS/STM32F4xx/library.mk @@ -0,0 +1,74 @@ +# +# Rules to (help) build the F4xx device support. +# + +# +# Directory containing this makefile +# +PIOS_DEVLIB := $(dir $(lastword $(MAKEFILE_LIST))) + +# +# Hardcoded linker script names for now +# +LINKER_SCRIPTS_APP = $(PIOS_DEVLIB)/link_STM32F4xx_OP_memory.ld \ + $(PIOS_DEVLIB)/link_STM32F4xx_sections.ld + +LINKER_SCRIPTS_BL = $(PIOS_DEVLIB)/link_STM32F4xx_BL_memory.ld \ + $(PIOS_DEVLIB)/link_STM32F4xx_sections.ld + +# +# Compiler options implied by the F4xx +# +CDEFS += -DSTM32F4XX +CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ) +CDEFS += -DUSE_STDPERIPH_DRIVER +ARCHFLAGS += -mcpu=cortex-m4 -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard + +# +# PIOS device library source and includes +# +SRC += $(wildcard $(PIOS_DEVLIB)*.c) +EXTRAINCDIRS += $(PIOS_DEVLIB)/inc + +# +# CMSIS for the F4 +# +include $(PIOSCOMMONLIB)/CMSIS2/library.mk +CMSIS2_DEVICEDIR := $(PIOS_DEVLIB)/Libraries/CMSIS2/Device/ST/STM32F4xx +SRC += $(wildcard $(CMSIS2_DEVICEDIR)/Source/*.c) +EXTRAINCDIRS += $(CMSIS2_DEVICEDIR)/Include + +# +# ST Peripheral library +# +PERIPHLIB = $(PIOS_DEVLIB)/Libraries/STM32F4xx_StdPeriph_Driver +SRC += $(wildcard $(PERIPHLIB)/src/*.c) +EXTRAINCDIRS += $(PERIPHLIB)/inc + +# +# ST USB OTG library +# +USBOTGLIB = $(PIOS_DEVLIB)/Libraries/STM32_USB_OTG_Driver +USBOTGLIB_SRC = usb_core.c usb_dcd.c usb_dcd_int.c +SRC += $(addprefix $(USBOTGLIB)/src/,$(USBOTGLIB_SRC)) +EXTRAINCDIRS += $(USBOTGLIB)/inc + +# +# ST USB Device library +# +USBDEVLIB = $(PIOS_DEVLIB)/Libraries/STM32_USB_Device_Library +SRC += $(wildcard $(USBDEVLIB)/Core/src/*.c) +EXTRAINCDIRS += $(USBDEVLIB)/Core/inc + +# +# FreeRTOS +# +# If the application has included the generic FreeRTOS support, then add in +# the device-specific pieces of the code. +# +ifneq ($(FREERTOS_DIR),) +FREERTOS_PORTDIR := $(PIOS_DEVLIB)/Libraries/FreeRTOS/Source +SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4/*.c) +EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4 +endif + diff --git a/flight/PiOS/STM32F4xx/link_STM32F4xx_BL_memory.ld b/flight/PiOS/STM32F4xx/link_STM32F4xx_BL_memory.ld new file mode 100644 index 000000000..3c0a67711 --- /dev/null +++ b/flight/PiOS/STM32F4xx/link_STM32F4xx_BL_memory.ld @@ -0,0 +1,7 @@ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x008000 - 0x000080 + BD_INFO (r) : ORIGIN = 0x08008000 - 0x80, LENGTH = 0x000080 + SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x020000 + CCSRAM (rw) : ORIGIN = 0x10000000, LENGTH = 0x010000 +} diff --git a/flight/PiOS/STM32F4xx/link_STM32F4xx_OP_memory.ld b/flight/PiOS/STM32F4xx/link_STM32F4xx_OP_memory.ld new file mode 100644 index 000000000..9f279355d --- /dev/null +++ b/flight/PiOS/STM32F4xx/link_STM32F4xx_OP_memory.ld @@ -0,0 +1,8 @@ +MEMORY +{ + BD_INFO (r) : ORIGIN = 0x08008000 - 0x80, LENGTH = 0x000080 + RSVD (rx) : ORIGIN = 0x08008000, LENGTH = 0x020000 - 0x008000 + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 0x0e0000 + SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x020000 + CCSRAM (rw) : ORIGIN = 0x10000000, LENGTH = 0x010000 +} diff --git a/flight/PiOS/STM32F4xx/link_STM32F4xx_sections.ld b/flight/PiOS/STM32F4xx/link_STM32F4xx_sections.ld new file mode 100644 index 000000000..bc75294d5 --- /dev/null +++ b/flight/PiOS/STM32F4xx/link_STM32F4xx_sections.ld @@ -0,0 +1,174 @@ + +/* Section Definitions */ +SECTIONS +{ + /* + * Vectors, code and constant data. + */ + .text : + { + PROVIDE (pios_isr_vector_table_base = .); + KEEP(*(.cpu_vectors)) /* CPU exception vectors */ + KEEP(*(.io_vectors)) /* I/O interrupt vectors */ + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + } > FLASH + + /* + * Init section for UAVObjects. + */ + .initcalluavobj.init : + { + . = ALIGN(4); + __uavobj_initcall_start = .; + KEEP(*(.initcalluavobj.init)) + . = ALIGN(4); + __uavobj_initcall_end = .; + } >FLASH + + /* + * Module init section section + */ + .initcallmodule.init : + { + . = ALIGN(4); + __module_initcall_start = .; + KEEP(*(.initcallmodule.init)) + . = ALIGN(4); + __module_initcall_end = .; + } >FLASH + + /* + * C++ exception handling. + */ + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > FLASH + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > FLASH + + /* + * Markers for the end of the 'text' section and the in-flash start of + * non-constant data + */ + . = ALIGN(4); + _etext = .; + _sidata = .; + + /* + * Board info structure, normally only generated by the bootloader but can + * be read by the application. + */ + PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO)); + .boardinfo : + { + . = ALIGN(4); + KEEP(*(.boardinfo)) + . = ALIGN(ORIGIN(BD_INFO)+LENGTH(BD_INFO)); + } > BD_INFO + + /* + * Place the IRQ/bootstrap stack at the bottom of SRAM so that an overflow + * results in a hard fault. + */ + .istack (NOLOAD) : + { + . = ALIGN(4); + _irq_stack_end = . ; + *(.irqstack) + _irq_stack_top = . ; + } > SRAM + + + /* + * Non-const initialised data. + */ + .data : AT (_sidata) + { + . = ALIGN(4); + _sdata = .; + *(.data .data.*) + . = ALIGN(4); + _edata = . ; + } > SRAM + + /* + * Uninitialised data (BSS + commons). + */ + .bss (NOLOAD) : + { + _sbss = . ; + *(.bss .bss.*) + *(COMMON) + _ebss = . ; + PROVIDE ( _end = _ebss ) ; + } > SRAM + + /* + * The heap consumes the remainder of the SRAM. + */ + .heap (NOLOAD) : + { + . = ALIGN(4); + _sheap = . ; + + /* + * This allows us to declare an object or objects up to the minimum acceptable + * heap size and receive a linker error if the space available for the heap is + * not sufficient. + */ + *(.heap) + + /* extend the heap up to the top of SRAM */ + . = ORIGIN(SRAM) + LENGTH(SRAM) - ABSOLUTE(_sheap); + _eheap = .; + } > SRAM + + /* + * 'Fast' memory goes in the CCM SRAM + */ + .fast (NOLOAD) : + { + _sfast = . ; + *(.fast) + _efast = . ; + } > CCSRAM + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} diff --git a/flight/PiOS/STM32F4xx/pios_adc.c b/flight/PiOS/STM32F4xx/pios_adc.c new file mode 100644 index 000000000..250dea7b0 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_adc.c @@ -0,0 +1,387 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_ADC ADC Functions + * @brief STM32F4xx ADC PIOS interface + * @{ + * + * @file pios_adc.c + * @author Michael Smith Copyright (C) 2011. + * @brief Analog to Digital converstion routines + * @see The GNU Public License (GPL) Version 3 + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* + * @note This is a stripped-down ADC driver intended primarily for sampling + * voltage and current values. Samples are averaged over the period between + * fetches so that relatively accurate measurements can be obtained without + * forcing higher-level logic to poll aggressively. + * + * @todo This module needs more work to be more generally useful. It should + * almost certainly grow callback support so that e.g. voltage and current readings + * can be shipped out for coulomb counting purposes. The F1xx interface presumes + * use with analog sensors, but that implementation largely dominates the ADC + * resources. Rather than commit to a new API without a defined use case, we + * should stick to our lightweight subset until we have a better idea of what's needed. + */ + +#include "pios.h" +#include + +extern struct pios_adc_cfg pios_adc_cfg; + +#if defined(PIOS_INCLUDE_ADC) +static void init_pins(void); +static void init_dma(void); +static void init_timer(void); +static void init_adc(void); +#endif + +struct dma_config { + GPIO_TypeDef *port; + uint32_t pin; + uint32_t channel; +}; + +struct adc_accumulator { + uint32_t accumulator; + uint32_t count; +}; + +#if defined(PIOS_INCLUDE_ADC) +static struct dma_config config[] = PIOS_DMA_PIN_CONFIG; +#define PIOS_ADC_NUM_PINS (sizeof(config) / sizeof(config[0])) + +static struct adc_accumulator accumulator[PIOS_ADC_NUM_PINS]; + +static uint16_t adc_raw_buffer[2][PIOS_ADC_MAX_SAMPLES][PIOS_ADC_NUM_PINS]; +#endif + +#define PIOS_ADC_TIMER TIM3 /* might want this to come from the config */ +#define PIOS_LOWRATE_ADC ADC1 + +#if defined(PIOS_INCLUDE_ADC) +static void +init_pins(void) +{ + /* Setup analog pins */ + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_StructInit(&GPIO_InitStructure); + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN; + + for (int32_t i = 0; i < PIOS_ADC_NUM_PINS; i++) { + GPIO_InitStructure.GPIO_Pin = config[i].pin; + GPIO_Init(config[i].port, &GPIO_InitStructure); + } +} + +static void +init_dma(void) +{ + /* Disable interrupts */ + DMA_ITConfig(pios_adc_cfg.dma.rx.channel, pios_adc_cfg.dma.irq.flags, DISABLE); + + /* Configure DMA channel */ + DMA_DeInit(pios_adc_cfg.dma.rx.channel); + DMA_InitTypeDef DMAInit = pios_adc_cfg.dma.rx.init; + DMAInit.DMA_Memory0BaseAddr = (uint32_t)&adc_raw_buffer[0]; + DMAInit.DMA_BufferSize = sizeof(adc_raw_buffer[0]) / sizeof(uint16_t); + DMAInit.DMA_DIR = DMA_DIR_PeripheralToMemory; + DMAInit.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + DMAInit.DMA_MemoryInc = DMA_MemoryInc_Enable; + DMAInit.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; + DMAInit.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; + DMAInit.DMA_Mode = DMA_Mode_Circular; + DMAInit.DMA_Priority = DMA_Priority_Low; + DMAInit.DMA_FIFOMode = DMA_FIFOMode_Disable; + DMAInit.DMA_FIFOThreshold = DMA_FIFOThreshold_HalfFull; + DMAInit.DMA_MemoryBurst = DMA_MemoryBurst_Single; + DMAInit.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; + + DMA_Init(pios_adc_cfg.dma.rx.channel, &DMAInit); /* channel is actually stream ... */ + + /* configure for double-buffered mode and interrupt on every buffer flip */ + DMA_DoubleBufferModeConfig(pios_adc_cfg.dma.rx.channel, (uint32_t)&adc_raw_buffer[1], DMA_Memory_0); + DMA_DoubleBufferModeCmd(pios_adc_cfg.dma.rx.channel, ENABLE); + DMA_ITConfig(pios_adc_cfg.dma.rx.channel, DMA_IT_TC, ENABLE); + + /* enable DMA */ + DMA_Cmd(pios_adc_cfg.dma.rx.channel, ENABLE); + + /* Configure DMA interrupt */ + NVIC_InitTypeDef NVICInit = pios_adc_cfg.dma.irq.init; + NVICInit.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW; + NVICInit.NVIC_IRQChannelSubPriority = 0; + NVICInit.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVICInit); +} + +static void +init_timer(void) +{ + RCC_ClocksTypeDef clocks; + TIM_TimeBaseInitTypeDef TIMInit; + + /* get clock info */ + RCC_GetClocksFreq(&clocks); + + /* reset/disable the timer */ + TIM_DeInit(PIOS_ADC_TIMER); + + /* configure for 1kHz auto-reload cycle */ + TIM_TimeBaseStructInit(&TIMInit); + TIMInit.TIM_Prescaler = clocks.PCLK1_Frequency / 1000000; /* 1MHz base clock*/ + TIMInit.TIM_CounterMode = TIM_CounterMode_Down; + TIMInit.TIM_Period = 1000; /* 1kHz conversion rate */ + TIMInit.TIM_ClockDivision = TIM_CKD_DIV1; /* no additional divisor */ + TIM_TimeBaseInit(PIOS_ADC_TIMER, &TIMInit); + + PIOS_COM_SendFormattedString(PIOS_COM_DEBUG, "TIM_Prescaler %d\r\n",TIMInit.TIM_Prescaler); + + /* configure trigger output on reload */ + TIM_SelectOutputTrigger(PIOS_ADC_TIMER, TIM_TRGOSource_Update); + TIM_Cmd(PIOS_ADC_TIMER, ENABLE); +} + +static void +init_adc(void) +{ + ADC_DeInit(); + + /* turn on VREFInt in case we need it */ + ADC_TempSensorVrefintCmd(ENABLE); + + /* Do common ADC init */ + ADC_CommonInitTypeDef ADC_CommonInitStructure; + ADC_CommonStructInit(&ADC_CommonInitStructure); + ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent; + ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div2; + ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled; + ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles; + ADC_CommonInit(&ADC_CommonInitStructure); + + ADC_InitTypeDef ADC_InitStructure; + ADC_StructInit(&ADC_InitStructure); + ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b; + ADC_InitStructure.ADC_ScanConvMode = ENABLE; + ADC_InitStructure.ADC_ContinuousConvMode = DISABLE; + ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T3_TRGO; + ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_Rising; + ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; + ADC_InitStructure.ADC_NbrOfConversion = ((PIOS_ADC_NUM_PINS)/* >> 1*/); + ADC_Init(PIOS_LOWRATE_ADC, &ADC_InitStructure); + + /* Enable PIOS_LOWRATE_ADC->DMA request */ + ADC_DMACmd(PIOS_LOWRATE_ADC, ENABLE); + + /* Configure input scan */ + for (int32_t i = 0; i < PIOS_ADC_NUM_PINS; i++) { + ADC_RegularChannelConfig(PIOS_LOWRATE_ADC, + config[i].channel, + i+1, + ADC_SampleTime_56Cycles); /* XXX this is totally arbitrary... */ + } + + ADC_DMARequestAfterLastTransferCmd(PIOS_LOWRATE_ADC, ENABLE); + + /* Finally start initial conversion */ + ADC_Cmd(PIOS_LOWRATE_ADC, ENABLE); +} +#endif + +/** + * @brief Init the ADC. + */ +void PIOS_ADC_Init() +{ +#if defined(PIOS_INCLUDE_ADC) + init_pins(); + init_dma(); + init_timer(); + init_adc(); +#endif +} + +/** + * @brief Configure the ADC to run at a fixed oversampling + * @param[in] oversampling the amount of oversampling to run at + */ +void PIOS_ADC_Config(uint32_t oversampling) +{ + /* we ignore this */ +} + +/** + * Returns value of an ADC Pin + * @param[in] pin number + * @return ADC pin value averaged over the set of samples since the last reading. + * @return -1 if pin doesn't exist + */ +int32_t PIOS_ADC_PinGet(uint32_t pin) +{ +#if defined(PIOS_INCLUDE_ADC) + int32_t result; + + /* Check if pin exists */ + if (pin >= PIOS_ADC_NUM_PINS) { + return -1; + } + + /* return accumulated result and clear accumulator */ + result = accumulator[pin].accumulator / (accumulator[pin].count ?: 1); + accumulator[pin].accumulator = 0; + accumulator[pin].count = 0; + + return result; +#endif + return -1; +} + +/** + * @brief Set a callback function that is executed whenever + * the ADC double buffer swaps + * @note Not currently supported. + */ +void PIOS_ADC_SetCallback(ADCCallback new_function) +{ + // XXX might be nice to do something here +} + +#if defined(PIOS_INCLUDE_FREERTOS) +/** + * @brief Register a queue to add data to when downsampled + * @note Not currently supported. + */ +void PIOS_ADC_SetQueue(xQueueHandle data_queue) +{ + // XXX it might make sense? to do this +} +#endif + +/** + * @brief Return the address of the downsampled data buffer + * @note Not currently supported. + */ +float * PIOS_ADC_GetBuffer(void) +{ + return NULL; +} + +/** + * @brief Return the address of the raw data data buffer + * @note Not currently supported. + */ +int16_t * PIOS_ADC_GetRawBuffer(void) +{ + return NULL; +} + +/** + * @brief Return the amount of over sampling + * @note Not currently supported (always returns 1) + */ +uint8_t PIOS_ADC_GetOverSampling(void) +{ + return 1; +} + +/** + * @brief Set the fir coefficients. Takes as many samples as the + * current filter order plus one (normalization) + * + * @param new_filter Array of adc_oversampling floats plus one for the + * filter coefficients + * @note Not currently supported. + */ +void PIOS_ADC_SetFIRCoefficients(float * new_filter) +{ + // not implemented +} + +/** + * @brief accumulate the data for each of the channels. + */ +void accumulate(uint16_t *buffer, uint32_t count) +{ +#if defined(PIOS_INCLUDE_ADC) + uint16_t *sp = buffer; + + /* + * Accumulate sampled values. + */ + while (count--) { + for (int i = 0; i < PIOS_ADC_NUM_PINS; i++) { + accumulator[i].accumulator += *sp++; + accumulator[i].count++; + /* + * If the accumulator reaches half-full, rescale in order to + * make more space. + */ + if (accumulator[i].accumulator >= (1 << 31)) { + accumulator[i].accumulator /= 2; + accumulator[i].count /= 2; + } + } + } + +#if defined(PIOS_INCLUDE_FREERTOS) + // XXX should do something with this +#if 0 + if (pios_adc_devs[0].data_queue) { + static portBASE_TYPE xHigherPriorityTaskWoken; + xQueueSendFromISR(pios_adc_devs[0].data_queue, pios_adc_devs[0].downsampled_buffer, &xHigherPriorityTaskWoken); + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); + } +#endif +#endif +#endif + // XXX callback? +} + +/** + * @brief Interrupt on buffer flip. + * + * The hardware is done with the 'other' buffer, so we can pass it to the accumulator. + */ +void PIOS_ADC_DMA_Handler(void) +{ +#if defined(PIOS_INCLUDE_ADC) + /* terminal count, buffer has flipped */ + if (DMA_GetITStatus(pios_adc_cfg.dma.rx.channel, pios_adc_cfg.full_flag)) { + DMA_ClearITPendingBit(pios_adc_cfg.dma.rx.channel, pios_adc_cfg.full_flag); + + /* accumulate results from the buffer that was just completed */ + accumulate(&adc_raw_buffer[DMA_GetCurrentMemoryTarget(pios_adc_cfg.dma.rx.channel) ? 0 : 1][0][0], + PIOS_ADC_MAX_SAMPLES); + +// static uint8_t outputcounter = 0; +// if (outputcounter == 0) +// { +// PIOS_COM_SendFormattedString(PIOS_COM_DEBUG, "adc vals %d %d %d %d %d %d\r\n", adc_raw_buffer[0][0][0], adc_raw_buffer[0][0][1], adc_raw_buffer[0][0][2], adc_raw_buffer[0][0][3], adc_raw_buffer[0][0][4], adc_raw_buffer[0][0][5]); +// } +// outputcounter++; + } +#endif +} + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_bl_helper.c b/flight/PiOS/STM32F4xx/pios_bl_helper.c new file mode 100644 index 000000000..05de4a305 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_bl_helper.c @@ -0,0 +1,195 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_BOOTLOADER Functions + * @brief HAL code to interface to the OpenPilot AHRS module + * @{ + * + * @file pios_bl_helper.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Bootloader Helper Functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" +#if defined(PIOS_INCLUDE_BL_HELPER) +#include +#include "stm32f4xx_flash.h" +#include + +uint8_t *PIOS_BL_HELPER_FLASH_If_Read(uint32_t SectorAddress) +{ + return (uint8_t *) (SectorAddress); +} + +#if defined(PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT) +uint8_t PIOS_BL_HELPER_FLASH_Ini() +{ + FLASH_Unlock(); + FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); + return 1; +} + +struct device_flash_sector { + uint32_t start; + uint32_t size; + uint16_t st_sector; +}; + +static struct device_flash_sector flash_sectors[] = { + [0] = { + .start = 0x08000000, + .size = 16 * 1024, + .st_sector = FLASH_Sector_0, + }, + [1] = { + .start = 0x08004000, + .size = 16 * 1024, + .st_sector = FLASH_Sector_1, + }, + [2] = { + .start = 0x08008000, + .size = 16 * 1024, + .st_sector = FLASH_Sector_2, + }, + [3] = { + .start = 0x0800C000, + .size = 16 * 1024, + .st_sector = FLASH_Sector_3, + }, + [4] = { + .start = 0x08010000, + .size = 64 * 1024, + .st_sector = FLASH_Sector_4, + }, + [5] = { + .start = 0x08020000, + .size = 128 * 1024, + .st_sector = FLASH_Sector_5, + }, + [6] = { + .start = 0x08040000, + .size = 128 * 1024, + .st_sector = FLASH_Sector_6, + }, + [7] = { + .start = 0x08060000, + .size = 128 * 1024, + .st_sector = FLASH_Sector_7, + }, + [8] = { + .start = 0x08080000, + .size = 128 * 1024, + .st_sector = FLASH_Sector_8, + }, + [9] = { + .start = 0x080A0000, + .size = 128 * 1024, + .st_sector = FLASH_Sector_9, + }, + [10] = { + .start = 0x080C0000, + .size = 128 * 1024, + .st_sector = FLASH_Sector_10, + }, + [11] = { + .start = 0x080E0000, + .size = 128 * 1024, + .st_sector = FLASH_Sector_11, + }, +}; + +static bool PIOS_BL_HELPER_FLASH_GetSectorInfo(uint32_t address, uint8_t * sector_number, uint32_t *sector_start, uint32_t *sector_size) +{ + for (uint8_t i = 0; i < NELEMENTS(flash_sectors); i++) { + struct device_flash_sector * sector = &flash_sectors[i]; + if ((address >= sector->start) && + (address < (sector->start + sector->size))) { + /* address lies within this sector */ + *sector_number = sector->st_sector; + *sector_start = sector->start; + *sector_size = sector->size; + return (true); + } + } + + return (false); +} + +uint8_t PIOS_BL_HELPER_FLASH_Start() +{ + const struct pios_board_info * bdinfo = &pios_board_info_blob; + uint32_t pageAddress = bdinfo->fw_base; + bool fail = false; + while ((pageAddress < (bdinfo->fw_base + bdinfo->fw_size + bdinfo->desc_size)) + && (fail == false)) { + uint8_t sector_number; + uint32_t sector_start; + uint32_t sector_size; + if (!PIOS_BL_HELPER_FLASH_GetSectorInfo(pageAddress, + §or_number, + §or_start, + §or_size)) { + /* We're asking for an invalid flash address */ + PIOS_Assert(0); + } + for (int retry = 0; retry < MAX_DEL_RETRYS; ++retry) { + if (FLASH_EraseSector(sector_number, VoltageRange_3) == FLASH_COMPLETE) { + fail = false; + break; + } else { + fail = true; + } + + } + /* Move to the next sector */ + pageAddress += sector_size; + } + + return (fail == true) ? 0 : 1; +} +#endif + +uint32_t PIOS_BL_HELPER_CRC_Memory_Calc() +{ + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + PIOS_BL_HELPER_CRC_Ini(); + CRC_ResetDR(); + CRC_CalcBlockCRC((uint32_t *) bdinfo->fw_base, (bdinfo->fw_size) >> 2); + return CRC_GetCRC(); +} + +void PIOS_BL_HELPER_FLASH_Read_Description(uint8_t * array, uint8_t size) +{ + const struct pios_board_info * bdinfo = &pios_board_info_blob; + uint8_t x = 0; + if (size > bdinfo->desc_size) size = bdinfo->desc_size; + for (uint32_t i = bdinfo->fw_base + bdinfo->fw_size; i < bdinfo->fw_base + bdinfo->fw_size + size; ++i) { + array[x] = *PIOS_BL_HELPER_FLASH_If_Read(i); + ++x; + } +} + +void PIOS_BL_HELPER_CRC_Ini() +{ +} +#endif diff --git a/flight/PiOS/STM32F4xx/pios_debug.c b/flight/PiOS/STM32F4xx/pios_debug.c new file mode 100644 index 000000000..339b9d427 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_debug.c @@ -0,0 +1,169 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @defgroup PIOS_DEBUG Debugging Functions + * @brief Debugging functionality + * @{ + * + * @file pios_debug.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Debugging Functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +// Global variables +const char *PIOS_DEBUG_AssertMsg = "ASSERT FAILED"; + +#ifdef PIOS_ENABLE_DEBUG_PINS +static const struct pios_tim_channel * debug_channels; +static uint8_t debug_num_channels; +#endif /* PIOS_ENABLE_DEBUG_PINS */ + +/** +* Initialise Debug-features +*/ +void PIOS_DEBUG_Init(const struct pios_tim_channel * channels, uint8_t num_channels) +{ +#ifdef PIOS_ENABLE_DEBUG_PINS + PIOS_Assert(channels); + PIOS_Assert(num_channels); + + /* Store away the GPIOs we've been given */ + debug_channels = channels; + debug_num_channels = num_channels; + + /* Configure the GPIOs we've been given */ + for (uint8_t i = 0; i < num_channels; i++) { + const struct pios_tim_channel * chan = &channels[i]; + + // Initialise pins as standard output pins + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_StructInit(&GPIO_InitStructure); + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Pin = chan->init->GPIO_Pin; + + /* Initialize the GPIO */ + GPIO_Init(chan->init->port, &GPIO_InitStructure); + + /* Set the pin low */ + GPIO_WriteBit(chan->init->port, chan->init->GPIO_Pin, Bit_RESET); + } +#endif // PIOS_ENABLE_DEBUG_PINS +} + +/** +* Set debug-pin high +* \param pin 0 for S1 output +*/ +void PIOS_DEBUG_PinHigh(uint8_t pin) +{ +#ifdef PIOS_ENABLE_DEBUG_PINS + if (!debug_channels || pin >= debug_num_channels) { + return; + } + + const struct pios_tim_channel * chan = &debug_channels[pin]; + + GPIO_WriteBit(chan->init->port, chan->init->GPIO_Pin, Bit_Set); + +#endif // PIOS_ENABLE_DEBUG_PINS +} + +/** +* Set debug-pin low +* \param pin 0 for S1 output +*/ +void PIOS_DEBUG_PinLow(uint8_t pin) +{ +#ifdef PIOS_ENABLE_DEBUG_PINS + if (!debug_channels || pin >= debug_num_channels) { + return; + } + + const struct pios_tim_channel * chan = &debug_channels[pin]; + + GPIO_WriteBit(chan->init->port, chan->init->GPIO_Pin, Bit_RESET); + +#endif // PIOS_ENABLE_DEBUG_PINS +} + + +void PIOS_DEBUG_PinValue8Bit(uint8_t value) +{ +#ifdef PIOS_ENABLE_DEBUG_PINS + if (!debug_channels) { + return; + } + + uint32_t bsrr_l = ( ((~value)&0x0F)<<(16+6) ) | ((value & 0x0F)<<6); + uint32_t bsrr_h = ( ((~value)&0xF0)<<(16+6-4) ) | ((value & 0xF0)<<(6-4)); + + PIOS_IRQ_Disable(); + + /* + * This is sketchy since it assumes a particular ordering + * and bitwise layout of the channels provided to the debug code. + */ + debug_channels[0].init.port->BSRR = bsrr_l; + debug_channels[4].init.port->BSRR = bsrr_h; + + PIOS_IRQ_Enable(); +#endif // PIOS_ENABLE_DEBUG_PINS +} + +void PIOS_DEBUG_PinValue4BitL(uint8_t value) +{ +#ifdef PIOS_ENABLE_DEBUG_PINS + if (!debug_channels) { + return; + } + + /* + * This is sketchy since it assumes a particular ordering + * and bitwise layout of the channels provided to the debug code. + */ + uint32_t bsrr_l = ((~(value & 0x0F)<<(16+6))) | ((value & 0x0F)<<6); + debug_channels[0].init.port->BSRR = bsrr_l; +#endif // PIOS_ENABLE_DEBUG_PINS +} + + +/** + * Report a serious error and halt + */ +void PIOS_DEBUG_Panic(const char *msg) +{ +#ifdef PIOS_COM_DEBUG + register int *lr asm("lr"); // Link-register holds the PC of the caller + PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, "\r%s @0x%x\r", msg, lr); +#endif + + // Stay put + while (1) ; +} + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_delay.c b/flight/PiOS/STM32F4xx/pios_delay.c new file mode 100644 index 000000000..947998c3f --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_delay.c @@ -0,0 +1,175 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_DELAY Delay Functions + * @brief PiOS Delay functionality + * @{ + * + * @file pios_delay.c + * @author Michael Smith Copyright (C) 2012 + * @brief Delay Functions + * - Provides a micro-second granular delay using the CPU + * cycle counter. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include + +#if defined(PIOS_INCLUDE_DELAY) + +/* these should be defined by CMSIS, but they aren't */ +#define DWT_CTRL (*(volatile uint32_t *)0xe0001000) +#define CYCCNTENA (1<<0) +#define DWT_CYCCNT (*(volatile uint32_t *)0xe0001004) + + +/* cycles per microsecond */ +static uint32_t us_ticks; + +/** + * Initialises the Timer used by PIOS_DELAY functions. + * + * \return always zero (success) + */ + +int32_t PIOS_DELAY_Init(void) +{ + RCC_ClocksTypeDef clocks; + + /* compute the number of system clocks per microsecond */ + RCC_GetClocksFreq(&clocks); + us_ticks = clocks.SYSCLK_Frequency / 1000000; + PIOS_DEBUG_Assert(us_ticks > 1); + + /* turn on access to the DWT registers */ + CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; + + /* enable the CPU cycle counter */ + DWT_CTRL |= CYCCNTENA; + + return 0; +} + +/** + * Waits for a specific number of uS + * + * Example:
+ * \code + * // Wait for 500 uS + * PIOS_DELAY_Wait_uS(500); + * \endcode + * \param[in] uS delay + * \return < 0 on errors + */ +int32_t PIOS_DELAY_WaituS(uint32_t uS) +{ + uint32_t elapsed = 0; + uint32_t last_count = DWT_CYCCNT; + + for (;;) { + uint32_t current_count = DWT_CYCCNT; + uint32_t elapsed_uS; + + /* measure the time elapsed since the last time we checked */ + elapsed += current_count - last_count; + last_count = current_count; + + /* convert to microseconds */ + elapsed_uS = elapsed / us_ticks; + if (elapsed_uS >= uS) + break; + + /* reduce the delay by the elapsed time */ + uS -= elapsed_uS; + + /* keep fractional microseconds for the next iteration */ + elapsed %= us_ticks; + } + + /* No error */ + return 0; +} + +/** + * Waits for a specific number of mS + * + * Example:
+ * \code + * // Wait for 500 mS + * PIOS_DELAY_Wait_mS(500); + * \endcode + * \param[in] mS delay (1..65535 milliseconds) + * \return < 0 on errors + */ +int32_t PIOS_DELAY_WaitmS(uint32_t mS) +{ + while (mS--) { + PIOS_DELAY_WaituS(1000); + } + + /* No error */ + return 0; +} + +/** + * @brief Query the Delay timer for the current uS + * @return A microsecond value + */ +uint32_t PIOS_DELAY_GetuS() +{ + return DWT_CYCCNT / us_ticks; +} + +/** + * @brief Calculate time in microseconds since a previous time + * @param[in] t previous time + * @return time in us since previous time t. + */ +uint32_t PIOS_DELAY_GetuSSince(uint32_t t) +{ + return (PIOS_DELAY_GetuS() - t); +} + +/** + * @brief Get the raw delay timer, useful for timing + * @return Unitless value (uint32 wrap around) + */ +uint32_t PIOS_DELAY_GetRaw() +{ + return DWT_CYCCNT; +} + +/** + * @brief Compare to raw times to and convert to us + * @return A microsecond value + */ +uint32_t PIOS_DELAY_DiffuS(uint32_t raw) +{ + uint32_t diff = DWT_CYCCNT - raw; + return diff / us_ticks; +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_dsm.c b/flight/PiOS/STM32F4xx/pios_dsm.c new file mode 100644 index 000000000..7c5348560 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_dsm.c @@ -0,0 +1,409 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_DSM Spektrum/JR DSMx satellite receiver functions + * @brief Code to bind and read Spektrum/JR DSMx satellite receiver serial stream + * @{ + * + * @file pios_dsm.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Code bind and read Spektrum/JR DSMx satellite receiver serial stream + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" +#include "pios_dsm_priv.h" + +#if defined(PIOS_INCLUDE_DSM) + +#if !defined(PIOS_INCLUDE_RTC) +#error PIOS_INCLUDE_RTC must be used to use DSM +#endif + +/* Forward Declarations */ +static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel); +static uint16_t PIOS_DSM_RxInCallback(uint32_t context, + uint8_t *buf, + uint16_t buf_len, + uint16_t *headroom, + bool *need_yield); +static void PIOS_DSM_Supervisor(uint32_t dsm_id); + +/* Local Variables */ +const struct pios_rcvr_driver pios_dsm_rcvr_driver = { + .read = PIOS_DSM_Get, +}; + +enum pios_dsm_dev_magic { + PIOS_DSM_DEV_MAGIC = 0x44534d78, +}; + +struct pios_dsm_state { + uint16_t channel_data[PIOS_DSM_NUM_INPUTS]; + uint8_t received_data[DSM_FRAME_LENGTH]; + uint8_t receive_timer; + uint8_t failsafe_timer; + uint8_t frame_found; + uint8_t byte_count; +#ifdef DSM_LOST_FRAME_COUNTER + uint8_t frames_lost_last; + uint16_t frames_lost; +#endif +}; + +struct pios_dsm_dev { + enum pios_dsm_dev_magic magic; + const struct pios_dsm_cfg *cfg; + enum pios_dsm_proto proto; + struct pios_dsm_state state; +}; + +/* Allocate DSM device descriptor */ +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_dsm_dev *PIOS_DSM_Alloc(void) +{ + struct pios_dsm_dev *dsm_dev; + + dsm_dev = (struct pios_dsm_dev *)pvPortMalloc(sizeof(*dsm_dev)); + if (!dsm_dev) + return NULL; + + dsm_dev->magic = PIOS_DSM_DEV_MAGIC; + return dsm_dev; +} +#else +static struct pios_dsm_dev pios_dsm_devs[PIOS_DSM_MAX_DEVS]; +static uint8_t pios_dsm_num_devs; +static struct pios_dsm_dev *PIOS_DSM_Alloc(void) +{ + struct pios_dsm_dev *dsm_dev; + + if (pios_dsm_num_devs >= PIOS_DSM_MAX_DEVS) + return NULL; + + dsm_dev = &pios_dsm_devs[pios_dsm_num_devs++]; + dsm_dev->magic = PIOS_DSM_DEV_MAGIC; + + return dsm_dev; +} +#endif + +/* Validate DSM device descriptor */ +static bool PIOS_DSM_Validate(struct pios_dsm_dev *dsm_dev) +{ + return (dsm_dev->magic == PIOS_DSM_DEV_MAGIC); +} + +/* Try to bind DSMx satellite using specified number of pulses */ +static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t bind) +{ + const struct pios_dsm_cfg *cfg = dsm_dev->cfg; + + GPIO_InitTypeDef GPIO_InitStructure = cfg->bind.init; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; + + /* just to limit bind pulses */ + if (bind > 10) + bind = 10; + + GPIO_Init(cfg->bind.gpio, &cfg->bind.init); + + /* RX line, set high */ + GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); + + /* on CC works up to 140ms, guess bind window is around 20-140ms after power up */ + PIOS_DELAY_WaitmS(60); + + for (int i = 0; i < bind ; i++) { + /* RX line, drive low for 120us */ + GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); + PIOS_DELAY_WaituS(120); + /* RX line, drive high for 120us */ + GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); + PIOS_DELAY_WaituS(120); + } + /* RX line, set input and wait for data */ + GPIO_Init(cfg->bind.gpio, &GPIO_InitStructure); +} + +/* Reset channels in case of lost signal or explicit failsafe receiver flag */ +static void PIOS_DSM_ResetChannels(struct pios_dsm_dev *dsm_dev) +{ + struct pios_dsm_state *state = &(dsm_dev->state); + for (int i = 0; i < PIOS_DSM_NUM_INPUTS; i++) { + state->channel_data[i] = PIOS_RCVR_TIMEOUT; + } +} + +/* Reset DSM receiver state */ +static void PIOS_DSM_ResetState(struct pios_dsm_dev *dsm_dev) +{ + struct pios_dsm_state *state = &(dsm_dev->state); + state->receive_timer = 0; + state->failsafe_timer = 0; + state->frame_found = 0; +#ifdef DSM_LOST_FRAME_COUNTER + state->frames_lost_last = 0; + state->frames_lost = 0; +#endif + PIOS_DSM_ResetChannels(dsm_dev); +} + +/** + * Check and unroll complete frame data. + * \output 0 frame data accepted + * \output -1 frame error found + */ +static int PIOS_DSM_UnrollChannels(struct pios_dsm_dev *dsm_dev) +{ + struct pios_dsm_state *state = &(dsm_dev->state); + uint8_t resolution; + +#ifdef DSM_LOST_FRAME_COUNTER + /* increment the lost frame counter */ + uint8_t frames_lost = state->received_data[0]; + state->frames_lost += (frames_lost - state->frames_lost_last); + state->frames_lost_last = frames_lost; +#endif + + /* check the frame type assuming master satellite stream */ + uint8_t type = state->received_data[1]; + switch (type) { + case 0x01: + case 0x02: + case 0x12: + /* DSM2, DSMJ stream */ + if (dsm_dev->proto == PIOS_DSM_PROTO_DSM2) { + /* DSM2/DSMJ resolution is known from the header */ + resolution = (type & DSM_DSM2_RES_MASK) ? 11 : 10; + } else { + /* DSMX resolution should explicitly be selected */ + goto stream_error; + } + break; + case 0xA2: + case 0xB2: + /* DSMX stream */ + if (dsm_dev->proto == PIOS_DSM_PROTO_DSMX10BIT) { + resolution = 10; + } else if (dsm_dev->proto == PIOS_DSM_PROTO_DSMX11BIT) { + resolution = 11; + } else { + /* DSMX resolution should explicitly be selected */ + goto stream_error; + } + break; + default: + /* unknown yet data stream */ + goto stream_error; + } + + /* unroll channels */ + uint8_t *s = &(state->received_data[2]); + uint16_t mask = (resolution == 10) ? 0x03ff : 0x07ff; + + for (int i = 0; i < DSM_CHANNELS_PER_FRAME; i++) { + uint16_t word = ((uint16_t)s[0] << 8) | s[1]; + s += 2; + + /* skip empty channel slot */ + if (word == 0xffff) + continue; + + /* minimal data validation */ + if ((i > 0) && (word & DSM_2ND_FRAME_MASK)) { + /* invalid frame data, ignore rest of the frame */ + goto stream_error; + } + + /* extract and save the channel value */ + uint8_t channel_num = (word >> resolution) & 0x0f; + if (channel_num < PIOS_DSM_NUM_INPUTS) + state->channel_data[channel_num] = (word & mask); + } + +#ifdef DSM_LOST_FRAME_COUNTER + /* put lost frames counter into the last channel for debugging */ + state->channel_data[PIOS_DSM_NUM_INPUTS-1] = state->frames_lost; +#endif + + /* all channels processed */ + return 0; + +stream_error: + /* either DSM2 selected with DSMX stream found, or vice-versa */ + return -1; +} + +/* Update decoder state processing input byte from the DSMx stream */ +static void PIOS_DSM_UpdateState(struct pios_dsm_dev *dsm_dev, uint8_t byte) +{ + struct pios_dsm_state *state = &(dsm_dev->state); + if (state->frame_found) { + /* receiving the data frame */ + if (state->byte_count < DSM_FRAME_LENGTH) { + /* store next byte */ + state->received_data[state->byte_count++] = byte; + if (state->byte_count == DSM_FRAME_LENGTH) { + /* full frame received - process and wait for new one */ + if (!PIOS_DSM_UnrollChannels(dsm_dev)) + /* data looking good */ + state->failsafe_timer = 0; + + /* prepare for the next frame */ + state->frame_found = 0; + } + } + } +} + +/* Initialise DSM receiver interface */ +int32_t PIOS_DSM_Init(uint32_t *dsm_id, + const struct pios_dsm_cfg *cfg, + const struct pios_com_driver *driver, + uint32_t lower_id, + enum pios_dsm_proto proto, + uint8_t bind) +{ + PIOS_DEBUG_Assert(dsm_id); + PIOS_DEBUG_Assert(cfg); + PIOS_DEBUG_Assert(driver); + + struct pios_dsm_dev *dsm_dev; + + dsm_dev = (struct pios_dsm_dev *)PIOS_DSM_Alloc(); + if (!dsm_dev) + return -1; + + /* Bind the configuration to the device instance */ + dsm_dev->cfg = cfg; + dsm_dev->proto = proto; + + /* Bind the receiver if requested */ + if (bind) + PIOS_DSM_Bind(dsm_dev, bind); + + PIOS_DSM_ResetState(dsm_dev); + + *dsm_id = (uint32_t)dsm_dev; + + /* Set comm driver callback */ + (driver->bind_rx_cb)(lower_id, PIOS_DSM_RxInCallback, *dsm_id); + + if (!PIOS_RTC_RegisterTickCallback(PIOS_DSM_Supervisor, *dsm_id)) { + PIOS_DEBUG_Assert(0); + } + + return 0; +} + +/* Comm byte received callback */ +static uint16_t PIOS_DSM_RxInCallback(uint32_t context, + uint8_t *buf, + uint16_t buf_len, + uint16_t *headroom, + bool *need_yield) +{ + struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)context; + + bool valid = PIOS_DSM_Validate(dsm_dev); + PIOS_Assert(valid); + + /* process byte(s) and clear receive timer */ + for (uint8_t i = 0; i < buf_len; i++) { + PIOS_DSM_UpdateState(dsm_dev, buf[i]); + dsm_dev->state.receive_timer = 0; + } + + /* Always signal that we can accept another byte */ + if (headroom) + *headroom = DSM_FRAME_LENGTH; + + /* We never need a yield */ + *need_yield = false; + + /* Always indicate that all bytes were consumed */ + return buf_len; +} + +/** + * Get the value of an input channel + * \param[in] channel Number of the channel desired (zero based) + * \output PIOS_RCVR_INVALID channel not available + * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver + * \output >0 channel value + */ +static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel) +{ + struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)rcvr_id; + + if (!PIOS_DSM_Validate(dsm_dev)) + return PIOS_RCVR_INVALID; + + /* return error if channel is not available */ + if (channel >= PIOS_DSM_NUM_INPUTS) + return PIOS_RCVR_INVALID; + + /* may also be PIOS_RCVR_TIMEOUT set by other function */ + return dsm_dev->state.channel_data[channel]; +} + +/** + * Input data supervisor is called periodically and provides + * two functions: frame syncing and failsafe triggering. + * + * DSM frames come at 11ms or 22ms rate at 115200bps. + * RTC timer is running at 625Hz (1.6ms). So with divider 5 it gives + * 8ms pause between frames which is good for both DSM frame rates. + * + * Data receive function must clear the receive_timer to confirm new + * data reception. If no new data received in 100ms, we must call the + * failsafe function which clears all channels. + */ +static void PIOS_DSM_Supervisor(uint32_t dsm_id) +{ + struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)dsm_id; + + bool valid = PIOS_DSM_Validate(dsm_dev); + PIOS_Assert(valid); + + struct pios_dsm_state *state = &(dsm_dev->state); + + /* waiting for new frame if no bytes were received in 8ms */ + if (++state->receive_timer > 4) { + state->frame_found = 1; + state->byte_count = 0; + state->receive_timer = 0; + } + + /* activate failsafe if no frames have arrived in 102.4ms */ + if (++state->failsafe_timer > 64) { + PIOS_DSM_ResetChannels(dsm_dev); + state->failsafe_timer = 0; + } +} + +#endif /* PIOS_INCLUDE_DSM */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_exti.c b/flight/PiOS/STM32F4xx/pios_exti.c new file mode 100644 index 000000000..9f9567d51 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_exti.c @@ -0,0 +1,232 @@ +/** + ****************************************************************************** + * + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_EXTI External Interrupt Handlers + * @brief External interrupt handler functions + * @{ + * + * @file pios_exti.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief External Interrupt Handlers + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_EXTI) + +/* Map EXTI line to full config */ +#define EXTI_MAX_LINES 16 +#define PIOS_EXTI_INVALID 0xFF +static uint8_t pios_exti_line_to_cfg_map[EXTI_MAX_LINES] = { + [0 ... EXTI_MAX_LINES-1] = PIOS_EXTI_INVALID, +}; + +/* Table of exti configs registered at compile time */ +extern struct pios_exti_cfg __start__exti __attribute__((weak)); +extern struct pios_exti_cfg __stop__exti __attribute__((weak)); + +static uint8_t PIOS_EXTI_line_to_index (uint32_t line) +{ + switch (line) { + case EXTI_Line0: return 0; + case EXTI_Line1: return 1; + case EXTI_Line2: return 2; + case EXTI_Line3: return 3; + case EXTI_Line4: return 4; + case EXTI_Line5: return 5; + case EXTI_Line6: return 6; + case EXTI_Line7: return 7; + case EXTI_Line8: return 8; + case EXTI_Line9: return 9; + case EXTI_Line10: return 10; + case EXTI_Line11: return 11; + case EXTI_Line12: return 12; + case EXTI_Line13: return 13; + case EXTI_Line14: return 14; + case EXTI_Line15: return 15; + } + + PIOS_Assert(0); + return 0xFF; +} + +uint8_t PIOS_EXTI_gpio_port_to_exti_source_port(GPIO_TypeDef * gpio_port) +{ + switch((uint32_t)gpio_port) { + case (uint32_t)GPIOA: return (EXTI_PortSourceGPIOA); + case (uint32_t)GPIOB: return (EXTI_PortSourceGPIOB); + case (uint32_t)GPIOC: return (EXTI_PortSourceGPIOC); + case (uint32_t)GPIOD: return (EXTI_PortSourceGPIOD); + case (uint32_t)GPIOE: return (EXTI_PortSourceGPIOE); + case (uint32_t)GPIOF: return (EXTI_PortSourceGPIOF); + case (uint32_t)GPIOG: return (EXTI_PortSourceGPIOG); + } + + PIOS_Assert(0); + return 0xFF; +} + +uint8_t PIOS_EXTI_gpio_pin_to_exti_source_pin(uint32_t gpio_pin) +{ + switch((uint32_t)gpio_pin) { + case GPIO_Pin_0: return (GPIO_PinSource0); + case GPIO_Pin_1: return (GPIO_PinSource1); + case GPIO_Pin_2: return (GPIO_PinSource2); + case GPIO_Pin_3: return (GPIO_PinSource3); + case GPIO_Pin_4: return (GPIO_PinSource4); + case GPIO_Pin_5: return (GPIO_PinSource5); + case GPIO_Pin_6: return (GPIO_PinSource6); + case GPIO_Pin_7: return (GPIO_PinSource7); + case GPIO_Pin_8: return (GPIO_PinSource8); + case GPIO_Pin_9: return (GPIO_PinSource9); + case GPIO_Pin_10: return (GPIO_PinSource10); + case GPIO_Pin_11: return (GPIO_PinSource11); + case GPIO_Pin_12: return (GPIO_PinSource12); + case GPIO_Pin_13: return (GPIO_PinSource13); + case GPIO_Pin_14: return (GPIO_PinSource14); + case GPIO_Pin_15: return (GPIO_PinSource15); + } + + PIOS_Assert(0); + return 0xFF; +} + +int32_t PIOS_EXTI_Init(const struct pios_exti_cfg * cfg) +{ + PIOS_Assert(cfg); + PIOS_Assert(&__start__exti); + PIOS_Assert(cfg >= &__start__exti); + PIOS_Assert(cfg < &__stop__exti); + + uint8_t cfg_index = cfg - &__start__exti; + + /* Connect this config to the requested vector */ + uint8_t line_index = PIOS_EXTI_line_to_index(cfg->line); + + if (pios_exti_line_to_cfg_map[line_index] != PIOS_EXTI_INVALID) { + /* Someone else already has this mapped */ + goto out_fail; + } + + /* Bind the config to the exti line */ + pios_exti_line_to_cfg_map[line_index] = cfg_index; + + /* Initialize the GPIO pin */ + GPIO_Init(cfg->pin.gpio, &cfg->pin.init); + + /* Set up the EXTI interrupt source */ + uint8_t exti_source_port = PIOS_EXTI_gpio_port_to_exti_source_port(cfg->pin.gpio); + uint8_t exti_source_pin = PIOS_EXTI_gpio_pin_to_exti_source_pin(cfg->pin.init.GPIO_Pin); + SYSCFG_EXTILineConfig(exti_source_port, exti_source_pin); + EXTI_Init(&cfg->exti.init); + + /* Enable the interrupt channel */ + NVIC_Init(&cfg->irq.init); + + return 0; + +out_fail: + return -1; +} + +static void PIOS_EXTI_generic_irq_handler(uint8_t line_index) +{ + uint8_t cfg_index = pios_exti_line_to_cfg_map[line_index]; + + PIOS_Assert(&__start__exti); + + if (cfg_index > NELEMENTS(pios_exti_line_to_cfg_map) || + cfg_index == PIOS_EXTI_INVALID) { + /* Unconfigured interrupt just fired! */ + return; + } + + struct pios_exti_cfg * cfg = &__start__exti + cfg_index; + cfg->vector(); +} + +/* Bind Interrupt Handlers */ + +#define PIOS_EXTI_HANDLE_LINE(line) \ + if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \ + EXTI_ClearITPendingBit(EXTI_Line##line); \ + PIOS_EXTI_generic_irq_handler(line); \ + } + +static void PIOS_EXTI_0_irq_handler (void) +{ + PIOS_EXTI_HANDLE_LINE(0); +} +void EXTI0_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_0_irq_handler"))); + +static void PIOS_EXTI_1_irq_handler (void) +{ + PIOS_EXTI_HANDLE_LINE(1); +} +void EXTI1_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_1_irq_handler"))); + +static void PIOS_EXTI_2_irq_handler (void) +{ + PIOS_EXTI_HANDLE_LINE(2); +} +void EXTI2_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_2_irq_handler"))); + +static void PIOS_EXTI_3_irq_handler (void) +{ + PIOS_EXTI_HANDLE_LINE(3); +} +void EXTI3_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_3_irq_handler"))); + +static void PIOS_EXTI_4_irq_handler (void) +{ + PIOS_EXTI_HANDLE_LINE(4); +} +void EXTI4_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_4_irq_handler"))); + +static void PIOS_EXTI_9_5_irq_handler (void) +{ + PIOS_EXTI_HANDLE_LINE(5); + PIOS_EXTI_HANDLE_LINE(6); + PIOS_EXTI_HANDLE_LINE(7); + PIOS_EXTI_HANDLE_LINE(8); + PIOS_EXTI_HANDLE_LINE(9); +} +void EXTI9_5_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_9_5_irq_handler"))); + +static void PIOS_EXTI_15_10_irq_handler (void) +{ + PIOS_EXTI_HANDLE_LINE(10); + PIOS_EXTI_HANDLE_LINE(11); + PIOS_EXTI_HANDLE_LINE(12); + PIOS_EXTI_HANDLE_LINE(13); + PIOS_EXTI_HANDLE_LINE(14); + PIOS_EXTI_HANDLE_LINE(15); +} +void EXTI15_10_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_15_10_irq_handler"))); + +#endif /* PIOS_INCLUDE_EXTI */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_gpio.c b/flight/PiOS/STM32F4xx/pios_gpio.c new file mode 100644 index 000000000..88f342a74 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_gpio.c @@ -0,0 +1,100 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @defgroup PIOS_GPIO GPIO Functions + * @brief GPIO hardware code for STM32F4xx + * @{ + * + * @file pios_gpio.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief GPIO functions, init, toggle, on & off. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_GPIO) + +/* Private Function Prototypes */ + +/* Local Variables */ +static GPIO_TypeDef *GPIO_PORT[PIOS_GPIO_NUM] = PIOS_GPIO_PORTS; +static const uint32_t GPIO_PIN[PIOS_GPIO_NUM] = PIOS_GPIO_PINS; + +/** +* Initialises all the GPIO's +*/ +void PIOS_GPIO_Init(void) +{ + /* Do nothing */ +} + +/** +* Enable a GPIO Pin +* \param[in] Pin Pin Number +*/ +void PIOS_GPIO_Enable(uint8_t Pin) +{ + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + GPIO_InitStructure.GPIO_Pin = GPIO_PIN[Pin]; + GPIO_Init(GPIO_PORT[Pin], &GPIO_InitStructure); + + /* GPIO's Off */ + PIOS_GPIO_Off(Pin); +} + +/** +* Turn on Pin +* \param[in] Pin Pin Number +*/ +void PIOS_GPIO_On(uint8_t Pin) +{ + GPIO_ResetBits(GPIO_PORT[Pin], GPIO_PIN[Pin]); +} + +/** +* Turn off Pin +* \param[in] Pin Pin Number +*/ +void PIOS_GPIO_Off(uint8_t Pin) +{ + GPIO_SetBits(GPIO_PORT[Pin], GPIO_PIN[Pin]); +} + +/** +* Toggle Pin on/off +* \param[in] Pin Pin Number +*/ +void PIOS_GPIO_Toggle(uint8_t Pin) +{ + GPIO_ToggleBits(GPIO_PORT[Pin], GPIO_PIN[Pin]); +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_i2c.c b/flight/PiOS/STM32F4xx/pios_i2c.c new file mode 100644 index 000000000..562774bcd --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_i2c.c @@ -0,0 +1,1238 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_I2C I2C Functions + * @brief STM32F4xx Hardware dependent I2C functionality + * @{ + * + * @file pios_i2c.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief I2C Enable/Disable routines + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* + * @note This is very closely related to the F1xx code and should really + * be merged. + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_I2C) + +#if defined(PIOS_INCLUDE_FREERTOS) +#define USE_FREERTOS +#endif + +#include + +//#define I2C_HALT_ON_ERRORS + +enum i2c_adapter_event { + I2C_EVENT_BUS_ERROR, + I2C_EVENT_START, + I2C_EVENT_STARTED_MORE_TXN_READ, + I2C_EVENT_STARTED_MORE_TXN_WRITE, + I2C_EVENT_STARTED_LAST_TXN_READ, + I2C_EVENT_STARTED_LAST_TXN_WRITE, + I2C_EVENT_ADDR_SENT_LEN_EQ_0, + I2C_EVENT_ADDR_SENT_LEN_EQ_1, + I2C_EVENT_ADDR_SENT_LEN_EQ_2, + I2C_EVENT_ADDR_SENT_LEN_GT_2, + I2C_EVENT_TRANSFER_DONE_LEN_EQ_0, + I2C_EVENT_TRANSFER_DONE_LEN_EQ_1, + I2C_EVENT_TRANSFER_DONE_LEN_EQ_2, + I2C_EVENT_TRANSFER_DONE_LEN_GT_2, + I2C_EVENT_NACK, + I2C_EVENT_STOPPED, + I2C_EVENT_AUTO, /* FIXME: remove this */ + + I2C_EVENT_NUM_EVENTS /* Must be last */ +}; + +#if defined(PIOS_I2C_DIAGNOSTICS) +static struct pios_i2c_fault_history i2c_adapter_fault_history; + +volatile uint32_t i2c_evirq_history[I2C_LOG_DEPTH]; +volatile uint8_t i2c_evirq_history_pointer = 0; + +volatile uint32_t i2c_erirq_history[I2C_LOG_DEPTH]; +volatile uint8_t i2c_erirq_history_pointer = 0; + +volatile enum i2c_adapter_state i2c_state_history[I2C_LOG_DEPTH]; +volatile uint8_t i2c_state_history_pointer = 0; + +volatile enum i2c_adapter_event i2c_state_event_history[I2C_LOG_DEPTH]; +volatile uint8_t i2c_state_event_history_pointer; + +static uint8_t i2c_fsm_fault_count = 0; +static uint8_t i2c_bad_event_counter = 0; +static uint8_t i2c_error_interrupt_counter = 0; +static uint8_t i2c_nack_counter = 0; +static uint8_t i2c_timeout_counter = 0; +#endif + +static void go_fsm_fault(struct pios_i2c_adapter *i2c_adapter); +static void go_bus_error(struct pios_i2c_adapter *i2c_adapter); +static void go_stopping(struct pios_i2c_adapter *i2c_adapter); +static void go_stopped(struct pios_i2c_adapter *i2c_adapter); +static void go_starting(struct pios_i2c_adapter *i2c_adapter); +static void go_r_any_txn_addr(struct pios_i2c_adapter *i2c_adapter); +static void go_r_more_txn_pre_one(struct pios_i2c_adapter *i2c_adapter); +static void go_r_any_txn_pre_first(struct pios_i2c_adapter *i2c_adapter); +static void go_r_any_txn_pre_middle(struct pios_i2c_adapter *i2c_adapter); +static void go_r_more_txn_pre_last(struct pios_i2c_adapter *i2c_adapter); +static void go_r_any_txn_post_last(struct pios_i2c_adapter *i2c_adapter); + +static void go_r_any_txn_addr(struct pios_i2c_adapter *i2c_adapter); +static void go_r_last_txn_pre_one(struct pios_i2c_adapter *i2c_adapter); +static void go_r_any_txn_pre_first(struct pios_i2c_adapter *i2c_adapter); +static void go_r_any_txn_pre_middle(struct pios_i2c_adapter *i2c_adapter); +static void go_r_last_txn_pre_last(struct pios_i2c_adapter *i2c_adapter); +static void go_r_any_txn_post_last(struct pios_i2c_adapter *i2c_adapter); + +static void go_w_any_txn_addr(struct pios_i2c_adapter *i2c_adapter); +static void go_w_any_txn_middle(struct pios_i2c_adapter *i2c_adapter); +static void go_w_more_txn_last(struct pios_i2c_adapter *i2c_adapter); + +static void go_w_any_txn_addr(struct pios_i2c_adapter *i2c_adapter); +static void go_w_any_txn_middle(struct pios_i2c_adapter *i2c_adapter); +static void go_w_last_txn_last(struct pios_i2c_adapter *i2c_adapter); + +static void go_nack(struct pios_i2c_adapter *i2c_adapter); + +struct i2c_adapter_transition { + void (*entry_fn) (struct pios_i2c_adapter * i2c_adapter); + enum i2c_adapter_state next_state[I2C_EVENT_NUM_EVENTS]; +}; + +static void i2c_adapter_process_auto(struct pios_i2c_adapter *i2c_adapter); +static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum i2c_adapter_event event); +static void i2c_adapter_fsm_init(struct pios_i2c_adapter *i2c_adapter); +static bool i2c_adapter_wait_for_stopped(struct pios_i2c_adapter *i2c_adapter); +static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter); + +static void i2c_adapter_log_fault(enum pios_i2c_error_type type); +static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter); + +const static struct i2c_adapter_transition i2c_adapter_transitions[I2C_STATE_NUM_STATES] = { + [I2C_STATE_FSM_FAULT] = { + .entry_fn = go_fsm_fault, + .next_state = { + [I2C_EVENT_AUTO] = I2C_STATE_STOPPING, + }, + }, + [I2C_STATE_BUS_ERROR] = { + .entry_fn = go_bus_error, + .next_state = { + [I2C_EVENT_AUTO] = I2C_STATE_STOPPING, + }, + }, + + [I2C_STATE_STOPPED] = { + .entry_fn = go_stopped, + .next_state = { + [I2C_EVENT_START] = I2C_STATE_STARTING, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_STOPPING] = { + .entry_fn = go_stopping, + .next_state = { + [I2C_EVENT_STOPPED] = I2C_STATE_STOPPED, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_STARTING] = { + .entry_fn = go_starting, + .next_state = { + [I2C_EVENT_STARTED_MORE_TXN_READ] = I2C_STATE_R_MORE_TXN_ADDR, + [I2C_EVENT_STARTED_MORE_TXN_WRITE] = I2C_STATE_W_MORE_TXN_ADDR, + [I2C_EVENT_STARTED_LAST_TXN_READ] = I2C_STATE_R_LAST_TXN_ADDR, + [I2C_EVENT_STARTED_LAST_TXN_WRITE] = I2C_STATE_W_LAST_TXN_ADDR, + [I2C_EVENT_NACK] = I2C_STATE_NACK, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + /* + * Read with restart + */ + + [I2C_STATE_R_MORE_TXN_ADDR] = { + .entry_fn = go_r_any_txn_addr, + .next_state = { + [I2C_EVENT_ADDR_SENT_LEN_EQ_1] = I2C_STATE_R_MORE_TXN_PRE_ONE, + [I2C_EVENT_ADDR_SENT_LEN_EQ_2] = I2C_STATE_R_MORE_TXN_PRE_FIRST, + [I2C_EVENT_ADDR_SENT_LEN_GT_2] = I2C_STATE_R_MORE_TXN_PRE_FIRST, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_R_MORE_TXN_PRE_ONE] = { + .entry_fn = go_r_more_txn_pre_one, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_1] = I2C_STATE_R_MORE_TXN_POST_LAST, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_R_MORE_TXN_PRE_FIRST] = { + .entry_fn = go_r_any_txn_pre_first, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_2] = I2C_STATE_R_MORE_TXN_PRE_LAST, + [I2C_EVENT_TRANSFER_DONE_LEN_GT_2] = I2C_STATE_R_MORE_TXN_PRE_MIDDLE, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_R_MORE_TXN_PRE_MIDDLE] = { + .entry_fn = go_r_any_txn_pre_middle, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_2] = I2C_STATE_R_MORE_TXN_PRE_LAST, + [I2C_EVENT_TRANSFER_DONE_LEN_GT_2] = I2C_STATE_R_MORE_TXN_PRE_MIDDLE, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_R_MORE_TXN_PRE_LAST] = { + .entry_fn = go_r_more_txn_pre_last, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_1] = I2C_STATE_R_MORE_TXN_POST_LAST, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_R_MORE_TXN_POST_LAST] = { + .entry_fn = go_r_any_txn_post_last, + .next_state = { + [I2C_EVENT_AUTO] = I2C_STATE_STARTING, + }, + }, + + /* + * Read + */ + + [I2C_STATE_R_LAST_TXN_ADDR] = { + .entry_fn = go_r_any_txn_addr, + .next_state = { + [I2C_EVENT_ADDR_SENT_LEN_EQ_1] = I2C_STATE_R_LAST_TXN_PRE_ONE, + [I2C_EVENT_ADDR_SENT_LEN_EQ_2] = I2C_STATE_R_LAST_TXN_PRE_FIRST, + [I2C_EVENT_ADDR_SENT_LEN_GT_2] = I2C_STATE_R_LAST_TXN_PRE_FIRST, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_R_LAST_TXN_PRE_ONE] = { + .entry_fn = go_r_last_txn_pre_one, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_1] = I2C_STATE_R_LAST_TXN_POST_LAST, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_R_LAST_TXN_PRE_FIRST] = { + .entry_fn = go_r_any_txn_pre_first, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_2] = I2C_STATE_R_LAST_TXN_PRE_LAST, + [I2C_EVENT_TRANSFER_DONE_LEN_GT_2] = I2C_STATE_R_LAST_TXN_PRE_MIDDLE, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_R_LAST_TXN_PRE_MIDDLE] = { + .entry_fn = go_r_any_txn_pre_middle, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_2] = I2C_STATE_R_LAST_TXN_PRE_LAST, + [I2C_EVENT_TRANSFER_DONE_LEN_GT_2] = I2C_STATE_R_LAST_TXN_PRE_MIDDLE, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_R_LAST_TXN_PRE_LAST] = { + .entry_fn = go_r_last_txn_pre_last, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_1] = I2C_STATE_R_LAST_TXN_POST_LAST, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_R_LAST_TXN_POST_LAST] = { + .entry_fn = go_r_any_txn_post_last, + .next_state = { + [I2C_EVENT_AUTO] = I2C_STATE_STOPPING, + }, + }, + + /* + * Write with restart + */ + + [I2C_STATE_W_MORE_TXN_ADDR] = { + .entry_fn = go_w_any_txn_addr, + .next_state = { + [I2C_EVENT_ADDR_SENT_LEN_EQ_1] = I2C_STATE_W_MORE_TXN_LAST, + [I2C_EVENT_ADDR_SENT_LEN_EQ_2] = I2C_STATE_W_MORE_TXN_MIDDLE, + [I2C_EVENT_ADDR_SENT_LEN_GT_2] = I2C_STATE_W_MORE_TXN_MIDDLE, + [I2C_EVENT_NACK] = I2C_STATE_NACK, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_W_MORE_TXN_MIDDLE] = { + .entry_fn = go_w_any_txn_middle, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_1] = I2C_STATE_W_MORE_TXN_LAST, + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_2] = I2C_STATE_W_MORE_TXN_MIDDLE, + [I2C_EVENT_TRANSFER_DONE_LEN_GT_2] = I2C_STATE_W_MORE_TXN_MIDDLE, + [I2C_EVENT_NACK] = I2C_STATE_NACK, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_W_MORE_TXN_LAST] = { + .entry_fn = go_w_more_txn_last, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_0] = I2C_STATE_STARTING, + [I2C_EVENT_NACK] = I2C_STATE_NACK, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + /* + * Write + */ + + [I2C_STATE_W_LAST_TXN_ADDR] = { + .entry_fn = go_w_any_txn_addr, + .next_state = { + [I2C_EVENT_ADDR_SENT_LEN_EQ_1] = I2C_STATE_W_LAST_TXN_LAST, + [I2C_EVENT_ADDR_SENT_LEN_EQ_2] = I2C_STATE_W_LAST_TXN_MIDDLE, + [I2C_EVENT_ADDR_SENT_LEN_GT_2] = I2C_STATE_W_LAST_TXN_MIDDLE, + [I2C_EVENT_NACK] = I2C_STATE_NACK, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_W_LAST_TXN_MIDDLE] = { + .entry_fn = go_w_any_txn_middle, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_1] = I2C_STATE_W_LAST_TXN_LAST, + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_2] = I2C_STATE_W_LAST_TXN_MIDDLE, + [I2C_EVENT_TRANSFER_DONE_LEN_GT_2] = I2C_STATE_W_LAST_TXN_MIDDLE, + [I2C_EVENT_NACK] = I2C_STATE_NACK, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + + [I2C_STATE_W_LAST_TXN_LAST] = { + .entry_fn = go_w_last_txn_last, + .next_state = { + [I2C_EVENT_TRANSFER_DONE_LEN_EQ_0] = I2C_STATE_STOPPING, + [I2C_EVENT_NACK] = I2C_STATE_NACK, + [I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR, + }, + }, + [I2C_STATE_NACK] = { + .entry_fn = go_nack, + .next_state = { + [I2C_EVENT_AUTO] = I2C_STATE_STOPPING, + }, + }, +}; + +static void go_fsm_fault(struct pios_i2c_adapter *i2c_adapter) +{ +#if defined(I2C_HALT_ON_ERRORS) + PIOS_DEBUG_Assert(0); +#endif + /* Note that this transfer has hit a bus error */ + i2c_adapter->bus_error = true; + + i2c_adapter_reset_bus(i2c_adapter); + +} + +static void go_bus_error(struct pios_i2c_adapter *i2c_adapter) +{ + /* Note that this transfer has hit a bus error */ + i2c_adapter->bus_error = true; + + i2c_adapter_reset_bus(i2c_adapter); +} + +static void go_stopping(struct pios_i2c_adapter *i2c_adapter) +{ +#ifdef USE_FREERTOS + signed portBASE_TYPE pxHigherPriorityTaskWoken = pdFALSE; +#endif + + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE); + +#ifdef USE_FREERTOS + if (xSemaphoreGiveFromISR(i2c_adapter->sem_ready, &pxHigherPriorityTaskWoken) != pdTRUE) { +#if defined(I2C_HALT_ON_ERRORS) + PIOS_DEBUG_Assert(0); +#endif + } + portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); /* FIXME: is this the right place for this? */ +#endif /* USE_FREERTOS */ + + if(i2c_adapter->callback) + i2c_adapter_callback_handler(i2c_adapter); +} + +static void go_stopped(struct pios_i2c_adapter *i2c_adapter) +{ + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE); + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, ENABLE); +} + +static void go_starting(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_DEBUG_Assert(i2c_adapter->active_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn >= i2c_adapter->first_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn); + + i2c_adapter->active_byte = &(i2c_adapter->active_txn->buf[0]); + i2c_adapter->last_byte = &(i2c_adapter->active_txn->buf[i2c_adapter->active_txn->len - 1]); + + I2C_GenerateSTART(i2c_adapter->cfg->regs, ENABLE); + if (i2c_adapter->active_txn->rw == PIOS_I2C_TXN_READ) { + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, ENABLE); + } else { + // For write operations, do not enable the IT_BUF events. + // The current driver does not act when the TX data register is not full, only when the complete byte is sent. + // With the IT_BUF enabled, we constantly get IRQs, See OP-326 + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_ERR, ENABLE); + } +} + +/* Common to 'more' and 'last' transaction */ +static void go_r_any_txn_addr(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_DEBUG_Assert(i2c_adapter->active_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn >= i2c_adapter->first_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn); + + PIOS_DEBUG_Assert(i2c_adapter->active_txn->rw == PIOS_I2C_TXN_READ); + + I2C_Send7bitAddress(i2c_adapter->cfg->regs, (i2c_adapter->active_txn->addr) << 1, I2C_Direction_Receiver); +} + +static void go_r_more_txn_pre_one(struct pios_i2c_adapter *i2c_adapter) +{ + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE); + I2C_GenerateSTART(i2c_adapter->cfg->regs, ENABLE); +} + +static void go_r_last_txn_pre_one(struct pios_i2c_adapter *i2c_adapter) +{ + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE); + I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE); +} + +/* Common to 'more' and 'last' transaction */ +static void go_r_any_txn_pre_first(struct pios_i2c_adapter *i2c_adapter) +{ + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, ENABLE); +} + +/* Common to 'more' and 'last' transaction */ +static void go_r_any_txn_pre_middle(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_DEBUG_Assert(i2c_adapter->active_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte); + + *(i2c_adapter->active_byte) = I2C_ReceiveData(i2c_adapter->cfg->regs); + + /* Move to the next byte */ + i2c_adapter->active_byte++; + PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte); +} + +static void go_r_more_txn_pre_last(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_DEBUG_Assert(i2c_adapter->active_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte); + + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE); + PIOS_IRQ_Disable(); + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE); + I2C_GenerateSTART(i2c_adapter->cfg->regs, ENABLE); + *(i2c_adapter->active_byte) = I2C_ReceiveData(i2c_adapter->cfg->regs); + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, ENABLE); + PIOS_IRQ_Enable(); + + /* Move to the next byte */ + i2c_adapter->active_byte++; + PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte); +} + +static void go_r_last_txn_pre_last(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_DEBUG_Assert(i2c_adapter->active_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte); + + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE); + PIOS_IRQ_Disable(); + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE); + I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE); + *(i2c_adapter->active_byte) = I2C_ReceiveData(i2c_adapter->cfg->regs); + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, ENABLE); + PIOS_IRQ_Enable(); + + /* Move to the next byte */ + i2c_adapter->active_byte++; + PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte); +} + +/* Common to 'more' and 'last' transaction */ +static void go_r_any_txn_post_last(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_DEBUG_Assert(i2c_adapter->active_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_byte == i2c_adapter->last_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn >= i2c_adapter->first_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn); + + *(i2c_adapter->active_byte) = I2C_ReceiveData(i2c_adapter->cfg->regs); + + /* Move to the next byte */ + i2c_adapter->active_byte++; + + /* Move to the next transaction */ + i2c_adapter->active_txn++; +} + +/* Common to 'more' and 'last' transaction */ +static void go_w_any_txn_addr(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_DEBUG_Assert(i2c_adapter->active_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn >= i2c_adapter->first_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn); + + PIOS_DEBUG_Assert(i2c_adapter->active_txn->rw == PIOS_I2C_TXN_WRITE); + + I2C_Send7bitAddress(i2c_adapter->cfg->regs, (i2c_adapter->active_txn->addr) << 1, I2C_Direction_Transmitter); +} + +static void go_w_any_txn_middle(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_DEBUG_Assert(i2c_adapter->active_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_byte < i2c_adapter->last_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn >= i2c_adapter->first_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn); + + I2C_SendData(i2c_adapter->cfg->regs, *(i2c_adapter->active_byte)); + + /* Move to the next byte */ + i2c_adapter->active_byte++; + PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte); +} + +static void go_w_more_txn_last(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_DEBUG_Assert(i2c_adapter->active_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_byte == i2c_adapter->last_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn >= i2c_adapter->first_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn); + + I2C_SendData(i2c_adapter->cfg->regs, *(i2c_adapter->active_byte)); + + /* Move to the next byte */ + i2c_adapter->active_byte++; + + /* Move to the next transaction */ + i2c_adapter->active_txn++; + PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn); +} + +static void go_w_last_txn_last(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_DEBUG_Assert(i2c_adapter->active_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_byte == i2c_adapter->last_byte); + PIOS_DEBUG_Assert(i2c_adapter->active_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn >= i2c_adapter->first_txn); + PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn); + + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_BUF, DISABLE); + I2C_SendData(i2c_adapter->cfg->regs, *(i2c_adapter->active_byte)); + +// SHOULD MOVE THIS INTO A STOPPING STATE AND SET IT ONLY AFTER THE BYTE WAS SENT + I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE); + + /* Move to the next byte */ + i2c_adapter->active_byte++; +} + +static void go_nack(struct pios_i2c_adapter *i2c_adapter) +{ + i2c_adapter->nack = true; + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE); + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE); + I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE); +} + +static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum i2c_adapter_event event) +{ + PIOS_IRQ_Disable(); + +#if defined(PIOS_I2C_DIAGNOSTICS) + i2c_state_event_history[i2c_state_event_history_pointer] = event; + i2c_state_event_history_pointer = (i2c_state_event_history_pointer + 1) % I2C_LOG_DEPTH; + + i2c_state_history[i2c_state_history_pointer] = i2c_adapter->curr_state; + i2c_state_history_pointer = (i2c_state_history_pointer + 1) % I2C_LOG_DEPTH; + + if(i2c_adapter_transitions[i2c_adapter->curr_state].next_state[event] == I2C_STATE_FSM_FAULT) + i2c_adapter_log_fault(PIOS_I2C_ERROR_FSM); +#endif + /* + * Move to the next state + * + * This is done prior to calling the new state's entry function to + * guarantee that the entry function never depends on the previous + * state. This way, it cannot ever know what the previous state was. + */ + enum i2c_adapter_state prev_state = i2c_adapter->curr_state; + if (prev_state) ; + + i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[event]; + + /* Call the entry function (if any) for the next state. */ + if (i2c_adapter_transitions[i2c_adapter->curr_state].entry_fn) { + i2c_adapter_transitions[i2c_adapter->curr_state].entry_fn(i2c_adapter); + } + + /* Process any AUTO transitions in the FSM */ + i2c_adapter_process_auto(i2c_adapter); + + PIOS_IRQ_Enable(); +} + +static void i2c_adapter_process_auto(struct pios_i2c_adapter *i2c_adapter) +{ + PIOS_IRQ_Disable(); + + enum i2c_adapter_state prev_state = i2c_adapter->curr_state; + if (prev_state) ; + + while (i2c_adapter_transitions[i2c_adapter->curr_state].next_state[I2C_EVENT_AUTO]) { + i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[I2C_EVENT_AUTO]; + + /* Call the entry function (if any) for the next state. */ + if (i2c_adapter_transitions[i2c_adapter->curr_state].entry_fn) { + i2c_adapter_transitions[i2c_adapter->curr_state].entry_fn(i2c_adapter); + } + } + + PIOS_IRQ_Enable(); +} + +static void i2c_adapter_fsm_init(struct pios_i2c_adapter *i2c_adapter) +{ + i2c_adapter_reset_bus(i2c_adapter); + i2c_adapter->curr_state = I2C_STATE_STOPPED; +} + +static bool i2c_adapter_wait_for_stopped(struct pios_i2c_adapter *i2c_adapter) +{ + uint32_t guard; + + /* + * Wait for the bus to return to the stopped state. + * This was pulled out of the FSM due to occasional + * failures at this transition which previously resulted + * in spinning on this bit in the ISR forever. + */ + for (guard = 1e6; /* FIXME: should use the configured bus timeout */ + guard && (i2c_adapter->cfg->regs->CR1 & I2C_CR1_STOP); guard--) + continue; + if (!guard) { + /* We timed out waiting for the stop condition */ + return false; + } + + return true; +} + +static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter) +{ + /* Reset the I2C block */ + I2C_DeInit(i2c_adapter->cfg->regs); + + /* Make sure the bus is free by clocking it until any slaves release the bus. */ + GPIO_InitTypeDef scl_gpio_init; + scl_gpio_init = i2c_adapter->cfg->scl.init; + scl_gpio_init.GPIO_Mode = GPIO_Mode_OUT; + GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); + GPIO_Init(i2c_adapter->cfg->scl.gpio, &scl_gpio_init); + + GPIO_InitTypeDef sda_gpio_init; + sda_gpio_init = i2c_adapter->cfg->sda.init; + sda_gpio_init.GPIO_Mode = GPIO_Mode_OUT; + GPIO_SetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin); + GPIO_Init(i2c_adapter->cfg->sda.gpio, &sda_gpio_init); + + /* Check SDA line to determine if slave is asserting bus and clock out if so, this may */ + /* have to be repeated (due to futher bus errors) but better than clocking 0xFF into an */ + /* ESC */ + //bool sda_hung = GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET; + while(GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET) { + + /* Set clock high and wait for any clock stretching to finish. */ + GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); + while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET) ; + PIOS_DELAY_WaituS(2); + + /* Set clock low */ + GPIO_ResetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); + PIOS_DELAY_WaituS(2); + + /* Clock high again */ + GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); + PIOS_DELAY_WaituS(2); + } + + /* Generate a start then stop condition */ + GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); + PIOS_DELAY_WaituS(2); + GPIO_ResetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin); + PIOS_DELAY_WaituS(2); + GPIO_ResetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin); + PIOS_DELAY_WaituS(2); + + /* Set data and clock high and wait for any clock stretching to finish. */ + GPIO_SetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin); + GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); + while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET) ; + /* Wait for data to be high */ + while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) != Bit_SET) ; + + + /* Bus signals are guaranteed to be high (ie. free) after this point */ + /* Initialize the GPIO pins to the peripheral function */ + if (i2c_adapter->cfg->remap) { + GPIO_PinAFConfig(i2c_adapter->cfg->scl.gpio, + __builtin_ctz(i2c_adapter->cfg->scl.init.GPIO_Pin), + i2c_adapter->cfg->remap); + GPIO_PinAFConfig(i2c_adapter->cfg->sda.gpio, + __builtin_ctz(i2c_adapter->cfg->sda.init.GPIO_Pin), + i2c_adapter->cfg->remap); + } + GPIO_Init(i2c_adapter->cfg->scl.gpio, (GPIO_InitTypeDef*)&(i2c_adapter->cfg->scl.init)); // Struct is const, function signature not + GPIO_Init(i2c_adapter->cfg->sda.gpio, (GPIO_InitTypeDef*)&(i2c_adapter->cfg->sda.init)); + + /* Reset the I2C block */ + I2C_DeInit(i2c_adapter->cfg->regs); + + /* Initialize the I2C block */ + I2C_Init(i2c_adapter->cfg->regs, (I2C_InitTypeDef*)&(i2c_adapter->cfg->init)); + + if (i2c_adapter->cfg->regs->SR2 & I2C_FLAG_BUSY) { + /* Reset the I2C block */ + I2C_SoftwareResetCmd(i2c_adapter->cfg->regs, ENABLE); + I2C_SoftwareResetCmd(i2c_adapter->cfg->regs, DISABLE); + } +} + +#include + +/* Return true if the FSM is in a terminal state */ +static bool i2c_adapter_fsm_terminated(struct pios_i2c_adapter *i2c_adapter) +{ + switch (i2c_adapter->curr_state) { + case I2C_STATE_STOPPING: + case I2C_STATE_STOPPED: + return (true); + default: + return (false); + } +} + +uint32_t i2c_cb_count = 0; +static bool i2c_adapter_callback_handler(struct pios_i2c_adapter * i2c_adapter) +{ + bool semaphore_success = true; + /* Wait for the transfer to complete */ +#ifdef USE_FREERTOS + portTickType timeout; + timeout = i2c_adapter->cfg->transfer_timeout_ms / portTICK_RATE_MS; + semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE); + xSemaphoreGive(i2c_adapter->sem_ready); +#endif /* USE_FREERTOS */ + + /* Spin waiting for the transfer to finish */ + while (!i2c_adapter_fsm_terminated(i2c_adapter)) ; + + if (i2c_adapter_wait_for_stopped(i2c_adapter)) { + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_STOPPED); + } else { + i2c_adapter_fsm_init(i2c_adapter); + } + + // Execute user supplied function + i2c_adapter->callback(); + + i2c_cb_count++; + +#ifdef USE_FREERTOS + /* Unlock the bus */ + xSemaphoreGive(i2c_adapter->sem_busy); + if(!semaphore_success) + i2c_timeout_counter++; +#else + PIOS_IRQ_Disable(); + i2c_adapter->busy = 0; + PIOS_IRQ_Enable(); +#endif /* USE_FREERTOS */ + + + return (!i2c_adapter->bus_error) && semaphore_success; +} + +/** + * Logs the last N state transitions and N IRQ events due to + * an error condition + * \param[in] i2c the adapter number to log an event for + */ +void i2c_adapter_log_fault(enum pios_i2c_error_type type) +{ +#if defined(PIOS_I2C_DIAGNOSTICS) + i2c_adapter_fault_history.type = type; + for(uint8_t i = 0; i < I2C_LOG_DEPTH; i++) { + i2c_adapter_fault_history.evirq[i] = + i2c_evirq_history[(I2C_LOG_DEPTH + i2c_evirq_history_pointer - 1 - i) % I2C_LOG_DEPTH]; + i2c_adapter_fault_history.erirq[i] = + i2c_erirq_history[(I2C_LOG_DEPTH + i2c_erirq_history_pointer - 1 - i) % I2C_LOG_DEPTH]; + i2c_adapter_fault_history.event[i] = + i2c_state_event_history[(I2C_LOG_DEPTH + i2c_state_event_history_pointer - 1 - i) % I2C_LOG_DEPTH]; + i2c_adapter_fault_history.state[i] = + i2c_state_history[(I2C_LOG_DEPTH + i2c_state_history_pointer - 1 - i) % I2C_LOG_DEPTH]; + } + switch(type) { + case PIOS_I2C_ERROR_EVENT: + i2c_bad_event_counter++; + break; + case PIOS_I2C_ERROR_FSM: + i2c_fsm_fault_count++; + break; + case PIOS_I2C_ERROR_INTERRUPT: + i2c_error_interrupt_counter++; + break; + } +#endif +} + + +/** + * Logs the last N state transitions and N IRQ events due to + * an error condition + * \param[out] data address where to copy the pios_i2c_fault_history structure to + * \param[out] counts three uint16 that receive the bad event, fsm, and error irq + * counts + */ +void PIOS_I2C_GetDiagnostics(struct pios_i2c_fault_history * data, uint8_t * counts) +{ +#if defined(PIOS_I2C_DIAGNOSTICS) + memcpy(data, &i2c_adapter_fault_history, sizeof(i2c_adapter_fault_history)); + counts[0] = i2c_bad_event_counter; + counts[1] = i2c_fsm_fault_count; + counts[2] = i2c_error_interrupt_counter; + counts[3] = i2c_nack_counter; + counts[4] = i2c_timeout_counter; +#else + struct pios_i2c_fault_history i2c_adapter_fault_history; + i2c_adapter_fault_history.type = PIOS_I2C_ERROR_EVENT; + + memcpy(data, &i2c_adapter_fault_history, sizeof(i2c_adapter_fault_history)); + counts[0] = counts[1] = counts[2] = 0; +#endif +} + +static bool PIOS_I2C_validate(struct pios_i2c_adapter * i2c_adapter) +{ + return (i2c_adapter->magic == PIOS_I2C_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) && 0 +static struct pios_i2c_dev * PIOS_I2C_alloc(void) +{ + struct pios_i2c_dev * i2c_adapter; + + i2c_adapter = (struct pios_i2c_adapter *)malloc(sizeof(*i2c_adapter)); + if (!i2c_adapter) return(NULL); + + i2c_adapter->magic = PIOS_I2C_DEV_MAGIC; + return(i2c_adapter); +} +#else +static struct pios_i2c_adapter pios_i2c_adapters[PIOS_I2C_MAX_DEVS]; +static uint8_t pios_i2c_num_adapters; +static struct pios_i2c_adapter * PIOS_I2C_alloc(void) +{ + struct pios_i2c_adapter * i2c_adapter; + + if (pios_i2c_num_adapters >= PIOS_I2C_MAX_DEVS) { + return (NULL); + } + + i2c_adapter = &pios_i2c_adapters[pios_i2c_num_adapters++]; + i2c_adapter->magic = PIOS_I2C_DEV_MAGIC; + + return (i2c_adapter); +} +#endif + + +/** +* Initializes IIC driver +* \param[in] mode currently only mode 0 supported +* \return < 0 if initialisation failed +*/ +int32_t PIOS_I2C_Init(uint32_t * i2c_id, const struct pios_i2c_adapter_cfg * cfg) +{ + PIOS_DEBUG_Assert(i2c_id); + PIOS_DEBUG_Assert(cfg); + + struct pios_i2c_adapter * i2c_adapter; + + i2c_adapter = (struct pios_i2c_adapter *) PIOS_I2C_alloc(); + if (!i2c_adapter) goto out_fail; + + /* Bind the configuration to the device instance */ + i2c_adapter->cfg = cfg; + +#ifdef USE_FREERTOS + /* + * Must be done prior to calling i2c_adapter_fsm_init() + * since the sem_ready mutex is used in the initial state. + */ + vSemaphoreCreateBinary(i2c_adapter->sem_ready); + i2c_adapter->sem_busy = xSemaphoreCreateMutex(); +#else + i2c_adapter->busy = 0; +#endif // USE_FREERTOS + + /* Initialize the state machine */ + i2c_adapter_fsm_init(i2c_adapter); + + *i2c_id = (uint32_t)i2c_adapter; + + /* Configure and enable I2C interrupts */ + NVIC_Init((NVIC_InitTypeDef*)&(i2c_adapter->cfg->event.init)); + NVIC_Init((NVIC_InitTypeDef*)&(i2c_adapter->cfg->error.init)); + + /* No error */ + return 0; + +out_fail: + return(-1); +} + +int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns) +{ + struct pios_i2c_adapter * i2c_adapter = (struct pios_i2c_adapter *)i2c_id; + + bool valid = PIOS_I2C_validate(i2c_adapter); + PIOS_Assert(valid) + + PIOS_DEBUG_Assert(txn_list); + PIOS_DEBUG_Assert(num_txns); + + bool semaphore_success = true; + +#ifdef USE_FREERTOS + /* Lock the bus */ + portTickType timeout; + timeout = i2c_adapter->cfg->transfer_timeout_ms / portTICK_RATE_MS; + semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_busy, timeout) == pdTRUE); +#else + PIOS_IRQ_Disable(); + if(i2c_adapter->busy) { + PIOS_IRQ_Enable(); + return -2; + } + i2c_adapter->busy = 1; + PIOS_IRQ_Enable(); +#endif /* USE_FREERTOS */ + + PIOS_DEBUG_Assert(i2c_adapter->curr_state == I2C_STATE_STOPPED); + + i2c_adapter->first_txn = &txn_list[0]; + i2c_adapter->last_txn = &txn_list[num_txns - 1]; + i2c_adapter->active_txn = i2c_adapter->first_txn; + +#ifdef USE_FREERTOS + /* Make sure the done/ready semaphore is consumed before we start */ + semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE); +#endif + + i2c_adapter->callback = NULL; + i2c_adapter->bus_error = false; + i2c_adapter->nack = false; + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START); + + /* Wait for the transfer to complete */ +#ifdef USE_FREERTOS + semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE); + xSemaphoreGive(i2c_adapter->sem_ready); +#endif /* USE_FREERTOS */ + + /* Spin waiting for the transfer to finish */ + while (!i2c_adapter_fsm_terminated(i2c_adapter)) ; + + if (i2c_adapter_wait_for_stopped(i2c_adapter)) { + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_STOPPED); + } else { + i2c_adapter_fsm_init(i2c_adapter); + } + +#ifdef USE_FREERTOS + /* Unlock the bus */ + xSemaphoreGive(i2c_adapter->sem_busy); + if(!semaphore_success) + i2c_timeout_counter++; +#else + PIOS_IRQ_Disable(); + i2c_adapter->busy = 0; + PIOS_IRQ_Enable(); +#endif /* USE_FREERTOS */ + + return !semaphore_success ? -2 : + i2c_adapter->bus_error ? -1 : + i2c_adapter->nack ? -3 : + 0; +} + +int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, void *callback) +{ + struct pios_i2c_adapter * i2c_adapter = (struct pios_i2c_adapter *)i2c_id; + + bool valid = PIOS_I2C_validate(i2c_adapter); + PIOS_Assert(valid) + PIOS_Assert(callback); + + PIOS_DEBUG_Assert(txn_list); + PIOS_DEBUG_Assert(num_txns); + + bool semaphore_success = true; + +#ifdef USE_FREERTOS + /* Lock the bus */ + portTickType timeout; + timeout = i2c_adapter->cfg->transfer_timeout_ms / portTICK_RATE_MS; + semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_busy, timeout) == pdTRUE); +#else + if(i2c_adapter->busy) { + PIOS_IRQ_Enable(); + return -2; + } +#endif /* USE_FREERTOS */ + + PIOS_DEBUG_Assert(i2c_adapter->curr_state == I2C_STATE_STOPPED); + + i2c_adapter->first_txn = &txn_list[0]; + i2c_adapter->last_txn = &txn_list[num_txns - 1]; + i2c_adapter->active_txn = i2c_adapter->first_txn; + +#ifdef USE_FREERTOS + /* Make sure the done/ready semaphore is consumed before we start */ + semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE); +#endif + + i2c_adapter->callback = callback; + i2c_adapter->bus_error = false; + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START); + + return !semaphore_success ? -2 : 0; +} + +void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id) +{ + struct pios_i2c_adapter * i2c_adapter = (struct pios_i2c_adapter *)i2c_id; + + bool valid = PIOS_I2C_validate(i2c_adapter); + PIOS_Assert(valid) + + uint32_t event = I2C_GetLastEvent(i2c_adapter->cfg->regs); + +#if defined(PIOS_I2C_DIAGNOSTICS) + /* Store event for diagnostics */ + i2c_evirq_history[i2c_evirq_history_pointer] = event; + i2c_evirq_history_pointer = (i2c_evirq_history_pointer + 1) % I2C_LOG_DEPTH; +#endif + +#define EVENT_MASK 0x000700FF + event &= EVENT_MASK; + + // This is very poor and inconsistent practice with the FSM since no other + // throw event depends on the current state. However when accelerated (-Os) + // we definitely catch this event twice and there is no clean way to do deal + // with that in the FMS short of a special state for it + if(i2c_adapter->curr_state == I2C_STATE_STARTING && event == 0x70084) + return; + + switch (event) { /* Mask out all the bits we don't care about */ + case (I2C_EVENT_MASTER_MODE_SELECT | 0x40): + /* Unexplained event: EV5 + RxNE : Extraneous Rx. Probably a late NACK from previous read. */ + /* Clean up the extra Rx until the root cause is identified and just keep going */ + (void)I2C_ReceiveData(i2c_adapter->cfg->regs); + /* Fall through */ + case I2C_EVENT_MASTER_MODE_SELECT: /* EV5 */ + switch (i2c_adapter->active_txn->rw) { + case PIOS_I2C_TXN_READ: + if (i2c_adapter->active_txn == i2c_adapter->last_txn) { + /* Final transaction */ + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_STARTED_LAST_TXN_READ); + } else if (i2c_adapter->active_txn < i2c_adapter->last_txn) { + /* More transactions follow */ + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_STARTED_MORE_TXN_READ); + } else { + PIOS_DEBUG_Assert(0); + } + break; + case PIOS_I2C_TXN_WRITE: + if (i2c_adapter->active_txn == i2c_adapter->last_txn) { + /* Final transaction */ + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_STARTED_LAST_TXN_WRITE); + } else if (i2c_adapter->active_txn < i2c_adapter->last_txn) { + /* More transactions follow */ + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_STARTED_MORE_TXN_WRITE); + } else { + PIOS_DEBUG_Assert(0); + } + break; + default: + PIOS_DEBUG_Assert(0); + break; + } + break; + case I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED: /* EV6 */ + case I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED: /* EV6 */ + switch (i2c_adapter->last_byte - i2c_adapter->active_byte + 1) { + case 0: + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_ADDR_SENT_LEN_EQ_0); + break; + case 1: + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_ADDR_SENT_LEN_EQ_1); + break; + case 2: + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_ADDR_SENT_LEN_EQ_2); + break; + default: + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_ADDR_SENT_LEN_GT_2); + break; + } + break; + case 0x80: /* TxE only. TRA + MSL + BUSY have been cleared before we got here. */ + /* Ignore */ + { + static volatile bool halt = false; + while (halt) ; + } + break; + case 0: /* This triggers an FSM fault sometimes, but not having it stops things working */ + case 0x40: /* RxNE only. MSL + BUSY have already been cleared by HW. */ + case 0x44: /* RxNE + BTF. MSL + BUSY have already been cleared by HW. */ + case I2C_EVENT_MASTER_BYTE_RECEIVED: /* EV7 */ + case (I2C_EVENT_MASTER_BYTE_RECEIVED | 0x4): /* EV7 + BTF */ + case I2C_EVENT_MASTER_BYTE_TRANSMITTED: /* EV8_2 */ + case 0x84: /* TxE + BTF. EV8_2 but TRA + MSL + BUSY have already been cleared by HW. */ + switch (i2c_adapter->last_byte - i2c_adapter->active_byte + 1) { + case 0: + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_TRANSFER_DONE_LEN_EQ_0); + break; + case 1: + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_TRANSFER_DONE_LEN_EQ_1); + break; + case 2: + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_TRANSFER_DONE_LEN_EQ_2); + break; + default: + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_TRANSFER_DONE_LEN_GT_2); + break; + } + break; + case I2C_EVENT_MASTER_BYTE_TRANSMITTING: /* EV8 */ + /* Ignore this event and wait for TRANSMITTED in case we can't keep up */ + goto skip_event; + break; + case 0x30084: /* Occurs between byte tranmistted and master mode selected */ + case 0x30000: /* Need to throw away this spurious event */ + case 0x30403 & EVENT_MASK: /* Detected this after got a NACK, probably stop bit */ + goto skip_event; + break; + default: + i2c_adapter_log_fault(PIOS_I2C_ERROR_EVENT); +#if defined(I2C_HALT_ON_ERRORS) + PIOS_DEBUG_Assert(0); +#endif + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_BUS_ERROR); + break; + } + +skip_event: + ; +} + + +void PIOS_I2C_ER_IRQ_Handler(uint32_t i2c_id) +{ + struct pios_i2c_adapter * i2c_adapter = (struct pios_i2c_adapter *)i2c_id; + + bool valid = PIOS_I2C_validate(i2c_adapter); + PIOS_Assert(valid) + +#if defined(PIOS_I2C_DIAGNOSTICS) + uint32_t event = I2C_GetLastEvent(i2c_adapter->cfg->regs); + + i2c_erirq_history[i2c_erirq_history_pointer] = event; + i2c_erirq_history_pointer = (i2c_erirq_history_pointer + 1) % 5; + +#endif + + if(event & I2C_FLAG_AF) { + i2c_nack_counter++; + + I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_AF); + + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_NACK); + } else { /* Mostly bus errors here */ + i2c_adapter_log_fault(PIOS_I2C_ERROR_INTERRUPT); + + /* Fail hard on any errors for now */ + i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_BUS_ERROR); + } +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_iap.c b/flight/PiOS/STM32F4xx/pios_iap.c new file mode 100644 index 000000000..0e5659866 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_iap.c @@ -0,0 +1,142 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_IAP IAP Functions + * @brief STM32F4xx Hardware dependent I2C functionality + * @{ + * + * @file pios_iap.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief In application programming functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/**************************************************************************************** + * Header files + ****************************************************************************************/ +#include + +/**************************************************************************************** + * Private Definitions/Macros + ****************************************************************************************/ + +/* these definitions reside here for protection and privacy. */ +#define IAP_MAGIC_WORD_1 0x1122 +#define IAP_MAGIC_WORD_2 0xAA55 + +#define UPPERWORD16(lw) (uint16_t)((uint32_t)(lw)>>16) +#define LOWERWORD16(lw) (uint16_t)((uint32_t)(lw)&0x0000ffff) +#define UPPERBYTE(w) (uint8_t)((w)>>8) +#define LOWERBYTE(w) (uint8_t)((w)&0x00ff) + +/**************************************************************************************** + * Private Functions + ****************************************************************************************/ + +/**************************************************************************************** + * Private (static) Data + ****************************************************************************************/ + +/**************************************************************************************** + * Public/Global Data + ****************************************************************************************/ + +/*! + * \brief PIOS_IAP_Init - performs required initializations for iap module. + * \param none. + * \return none. + * \retval none. + * + * Created: Sep 8, 2010 10:10:48 PM by joe + */ +void PIOS_IAP_Init( void ) +{ + /* Enable CRC clock */ + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_CRC, ENABLE); + + /* Enable PWR and BKP clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_AHB1Periph_BKPSRAM, ENABLE); + + /* Enable write access to Backup domain */ + PWR_BackupAccessCmd(ENABLE); + + /* Clear Tamper pin Event(TE) pending flag */ + RTC_ClearFlag(RTC_FLAG_TAMP1F); +} + +/*! + * \brief Determines if an In-Application-Programming request has been made. + * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) + * \return TRUE - if correct sequence found, along with 'comm' updated. + * FALSE - Note that 'comm' will have an invalid comm identifier. + * \retval + * + */ +uint32_t PIOS_IAP_CheckRequest( void ) +{ + uint32_t retval = false; + uint16_t reg1; + uint16_t reg2; + + reg1 = RTC_ReadBackupRegister( MAGIC_REG_1 ); + reg2 = RTC_ReadBackupRegister( MAGIC_REG_2 ); + + if( reg1 == IAP_MAGIC_WORD_1 && reg2 == IAP_MAGIC_WORD_2 ) { + // We have a match. + retval = true; + } else { + retval = false; + } + return retval; +} + + + +/*! + * \brief Sets the 1st word of the request sequence. + * \param n/a + * \return n/a + * \retval + */ +void PIOS_IAP_SetRequest1(void) +{ + RTC_WriteBackupRegister( MAGIC_REG_1, IAP_MAGIC_WORD_1); +} + +void PIOS_IAP_SetRequest2(void) +{ + RTC_WriteBackupRegister( MAGIC_REG_2, IAP_MAGIC_WORD_2); +} + +void PIOS_IAP_ClearRequest(void) +{ + RTC_WriteBackupRegister( MAGIC_REG_1, 0); + RTC_WriteBackupRegister( MAGIC_REG_2, 0); +} + +uint16_t PIOS_IAP_ReadBootCount(void) +{ + return RTC_ReadBackupRegister ( IAP_BOOTCOUNT ); +} + +void PIOS_IAP_WriteBootCount (uint16_t boot_count) +{ + RTC_WriteBackupRegister ( IAP_BOOTCOUNT, boot_count ); +} diff --git a/flight/PiOS/STM32F4xx/pios_irq.c b/flight/PiOS/STM32F4xx/pios_irq.c new file mode 100644 index 000000000..b556931bc --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_irq.c @@ -0,0 +1,101 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_IRQ IRQ Setup Functions + * @brief STM32 Hardware code to enable and disable interrupts + * @{ + * + * @file pios_irq.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012 + * @brief IRQ Enable/Disable routines + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* + * @todo This should be shared with the F1xx code. + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_IRQ) + +/* Private Function Prototypes */ + +/* Local Variables */ +/* The nesting counter ensures, that interrupts won't be enabled so long nested functions disable them */ +static uint32_t nested_ctr; + +/* Stored priority level before IRQ has been disabled (important for co-existence with vPortEnterCritical) */ +static uint32_t prev_primask; + +/** +* Disables all interrupts (nested) +* \return < 0 On errors +*/ +int32_t PIOS_IRQ_Disable(void) +{ + /* Get current priority if nested level == 0 */ + if (!nested_ctr) { + __asm volatile (" mrs %0, primask\n":"=r" (prev_primask) + ); + } + + /* Disable interrupts */ + __asm volatile (" mov r0, #1 \n" " msr primask, r0\n":::"r0"); + + ++nested_ctr; + + /* No error */ + return 0; +} + +/** +* Enables all interrupts (nested) +* \return < 0 on errors +* \return -1 on nesting errors (PIOS_IRQ_Disable() hasn't been called before) +*/ +int32_t PIOS_IRQ_Enable(void) +{ + /* Check for nesting error */ + if (nested_ctr == 0) { + /* Nesting error */ + return -1; + } + + /* Decrease nesting level */ + --nested_ctr; + + /* Set back previous priority once nested level reached 0 again */ + if (nested_ctr == 0) { + __asm volatile (" msr primask, %0\n"::"r" (prev_primask) + ); + } + + /* No error */ + return 0; +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_led.c b/flight/PiOS/STM32F4xx/pios_led.c new file mode 100644 index 000000000..c73d37198 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_led.c @@ -0,0 +1,128 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_LED LED Functions + * @brief STM32 Hardware LED handling code + * @{ + * + * @file pios_led.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief LED functions, init, toggle, on & off. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_LED) + +#include + +const static struct pios_led_cfg * led_cfg; + +/** + * Initialises all the LED's + */ +int32_t PIOS_LED_Init(const struct pios_led_cfg * cfg) +{ + PIOS_Assert(cfg); + + /* Store away the config in a global used by API functions */ + led_cfg = cfg; + + for (uint8_t i = 0; i < cfg->num_leds; i++) { + const struct pios_led * led = &(cfg->leds[i]); + + if (led->remap) { + GPIO_PinAFConfig(led->pin.gpio, led->pin.init.GPIO_Pin, led->remap); + } + + GPIO_Init(led->pin.gpio, &led->pin.init); + + PIOS_LED_Off(i); + } + + return 0; +} + +/** + * Turn on LED + * \param[in] LED LED id + */ +void PIOS_LED_On(uint32_t led_id) +{ + PIOS_Assert(led_cfg); + + if (led_id >= led_cfg->num_leds) { + /* LED index out of range */ + return; + } + + const struct pios_led * led = &(led_cfg->leds[led_id]); + + GPIO_ResetBits(led->pin.gpio, led->pin.init.GPIO_Pin); +} + +/** + * Turn off LED + * \param[in] LED LED id + */ +void PIOS_LED_Off(uint32_t led_id) +{ + PIOS_Assert(led_cfg); + + if (led_id >= led_cfg->num_leds) { + /* LED index out of range */ + return; + } + + const struct pios_led * led = &(led_cfg->leds[led_id]); + + GPIO_SetBits(led->pin.gpio, led->pin.init.GPIO_Pin); +} + +/** + * Toggle LED on/off + * \param[in] LED LED id + */ +void PIOS_LED_Toggle(uint32_t led_id) +{ + PIOS_Assert(led_cfg); + + if (led_id >= led_cfg->num_leds) { + /* LED index out of range */ + return; + } + + const struct pios_led * led = &(led_cfg->leds[led_id]); + + if (GPIO_ReadOutputDataBit(led->pin.gpio, led->pin.init.GPIO_Pin) == Bit_SET) { + PIOS_LED_On(led_id); + } else { + PIOS_LED_Off(led_id); + } +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_ppm.c b/flight/PiOS/STM32F4xx/pios_ppm.c new file mode 100644 index 000000000..e17b342b7 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_ppm.c @@ -0,0 +1,357 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_PPM PPM Input Functions + * @brief Code to measure PPM input and seperate into channels + * @{ + * + * @file pios_ppm.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief PPM Input functions (STM32 dependent) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" +#include "pios_ppm_priv.h" + +#if defined(PIOS_INCLUDE_PPM) + +/* Provide a RCVR driver */ +static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel); + +const struct pios_rcvr_driver pios_ppm_rcvr_driver = { + .read = PIOS_PPM_Get, +}; + +#define PIOS_PPM_IN_MIN_NUM_CHANNELS 4 +#define PIOS_PPM_IN_MAX_NUM_CHANNELS PIOS_PPM_NUM_INPUTS +#define PIOS_PPM_STABLE_CHANNEL_COUNT 25 // frames +#define PIOS_PPM_IN_MIN_SYNC_PULSE_US 3800 // microseconds +#define PIOS_PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds +#define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds + +/* Local Variables */ +static TIM_ICInitTypeDef TIM_ICInitStructure; + +static void PIOS_PPM_Supervisor(uint32_t ppm_id); + +enum pios_ppm_dev_magic { + PIOS_PPM_DEV_MAGIC = 0xee014d8b, +}; + +struct pios_ppm_dev { + enum pios_ppm_dev_magic magic; + const struct pios_ppm_cfg * cfg; + + uint8_t PulseIndex; + uint32_t PreviousTime; + uint32_t CurrentTime; + uint32_t DeltaTime; + uint32_t CaptureValue[PIOS_PPM_IN_MAX_NUM_CHANNELS]; + uint32_t CaptureValueNewFrame[PIOS_PPM_IN_MAX_NUM_CHANNELS]; + uint32_t LargeCounter; + int8_t NumChannels; + int8_t NumChannelsPrevFrame; + uint8_t NumChannelCounter; + + uint8_t supv_timer; + bool Tracking; + bool Fresh; +}; + +static bool PIOS_PPM_validate(struct pios_ppm_dev * ppm_dev) +{ + return (ppm_dev->magic == PIOS_PPM_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_ppm_dev * PIOS_PPM_alloc(void) +{ + struct pios_ppm_dev * ppm_dev; + + ppm_dev = (struct pios_ppm_dev *)pvPortMalloc(sizeof(*ppm_dev)); + if (!ppm_dev) return(NULL); + + ppm_dev->magic = PIOS_PPM_DEV_MAGIC; + return(ppm_dev); +} +#else +static struct pios_ppm_dev pios_ppm_devs[PIOS_PPM_MAX_DEVS]; +static uint8_t pios_ppm_num_devs; +static struct pios_ppm_dev * PIOS_PPM_alloc(void) +{ + struct pios_ppm_dev * ppm_dev; + + if (pios_ppm_num_devs >= PIOS_PPM_MAX_DEVS) { + return (NULL); + } + + ppm_dev = &pios_ppm_devs[pios_ppm_num_devs++]; + ppm_dev->magic = PIOS_PPM_DEV_MAGIC; + + return (ppm_dev); +} +#endif + +static void PIOS_PPM_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +static void PIOS_PPM_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +const static struct pios_tim_callbacks tim_callbacks = { + .overflow = PIOS_PPM_tim_overflow_cb, + .edge = PIOS_PPM_tim_edge_cb, +}; + +extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) +{ + PIOS_DEBUG_Assert(ppm_id); + PIOS_DEBUG_Assert(cfg); + + struct pios_ppm_dev * ppm_dev; + + ppm_dev = (struct pios_ppm_dev *) PIOS_PPM_alloc(); + if (!ppm_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + ppm_dev->cfg = cfg; + + /* Set up the state variables */ + ppm_dev->PulseIndex = 0; + ppm_dev->PreviousTime = 0; + ppm_dev->CurrentTime = 0; + ppm_dev->DeltaTime = 0; + ppm_dev->LargeCounter = 0; + ppm_dev->NumChannels = -1; + ppm_dev->NumChannelsPrevFrame = -1; + ppm_dev->NumChannelCounter = 0; + ppm_dev->Tracking = false; + ppm_dev->Fresh = false; + + for (uint8_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { + /* Flush counter variables */ + ppm_dev->CaptureValue[i] = 0; + ppm_dev->CaptureValueNewFrame[i] = 0; + + } + + uint32_t tim_id; + if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, &tim_callbacks, (uint32_t)ppm_dev)) { + return -1; + } + + /* Configure the channels to be in capture/compare mode */ + for (uint8_t i = 0; i < cfg->num_channels; i++) { + const struct pios_tim_channel * chan = &cfg->channels[i]; + + /* Configure timer for input capture */ + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); + + /* Enable the Capture Compare Interrupt Request */ + switch (chan->timer_chan) { + case TIM_Channel_1: + TIM_ITConfig(chan->timer, TIM_IT_CC1 | TIM_IT_Update, ENABLE); + break; + case TIM_Channel_2: + TIM_ITConfig(chan->timer, TIM_IT_CC2 | TIM_IT_Update, ENABLE); + break; + case TIM_Channel_3: + TIM_ITConfig(chan->timer, TIM_IT_CC3 | TIM_IT_Update, ENABLE); + break; + case TIM_Channel_4: + TIM_ITConfig(chan->timer, TIM_IT_CC4 | TIM_IT_Update, ENABLE); + break; + } + } + + /* Setup local variable which stays in this scope */ + /* Doing this here and using a local variable saves doing it in the ISR */ + TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStructure.TIM_ICFilter = 0x0; + + if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) { + PIOS_DEBUG_Assert(0); + } + + *ppm_id = (uint32_t)ppm_dev; + + return(0); + +out_fail: + return(-1); +} + +/** +* Get the value of an input channel +* \param[in] Channel Number of the channel desired +* \output -1 Channel not available +* \output >0 Channel value +*/ +static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel) +{ + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)rcvr_id; + + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return PIOS_RCVR_INVALID; + } + + if (channel >= PIOS_PPM_IN_MAX_NUM_CHANNELS) { + /* Channel out of range */ + return PIOS_RCVR_INVALID; + } + return ppm_dev->CaptureValue[channel]; +} + +static void PIOS_PPM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) +{ + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)context; + + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return; + } + + ppm_dev->LargeCounter += count; + + return; +} + + +static void PIOS_PPM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +{ + /* Recover our device context */ + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)context; + + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return; + } + + if (chan_idx >= ppm_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + + /* Shift the last measurement out */ + ppm_dev->PreviousTime = ppm_dev->CurrentTime; + + /* Grab the new count */ + ppm_dev->CurrentTime = count; + + /* Convert to 32-bit timer result */ + ppm_dev->CurrentTime += ppm_dev->LargeCounter; + + /* Capture computation */ + ppm_dev->DeltaTime = ppm_dev->CurrentTime - ppm_dev->PreviousTime; + + ppm_dev->PreviousTime = ppm_dev->CurrentTime; + + /* Sync pulse detection */ + if (ppm_dev->DeltaTime > PIOS_PPM_IN_MIN_SYNC_PULSE_US) { + if (ppm_dev->PulseIndex == ppm_dev->NumChannelsPrevFrame + && ppm_dev->PulseIndex >= PIOS_PPM_IN_MIN_NUM_CHANNELS + && ppm_dev->PulseIndex <= PIOS_PPM_IN_MAX_NUM_CHANNELS) + { + /* If we see n simultaneous frames of the same + number of channels we save it as our frame size */ + if (ppm_dev->NumChannelCounter < PIOS_PPM_STABLE_CHANNEL_COUNT) + ppm_dev->NumChannelCounter++; + else + ppm_dev->NumChannels = ppm_dev->PulseIndex; + } else { + ppm_dev->NumChannelCounter = 0; + } + + /* Check if the last frame was well formed */ + if (ppm_dev->PulseIndex == ppm_dev->NumChannels && ppm_dev->Tracking) { + /* The last frame was well formed */ + for (uint32_t i = 0; i < ppm_dev->NumChannels; i++) { + ppm_dev->CaptureValue[i] = ppm_dev->CaptureValueNewFrame[i]; + } + for (uint32_t i = ppm_dev->NumChannels; + i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { + ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + } + } + + ppm_dev->Fresh = true; + ppm_dev->Tracking = true; + ppm_dev->NumChannelsPrevFrame = ppm_dev->PulseIndex; + ppm_dev->PulseIndex = 0; + + /* We rely on the supervisor to set CaptureValue to invalid + if no valid frame is found otherwise we ride over it */ + + } else if (ppm_dev->Tracking) { + /* Valid pulse duration 0.75 to 2.5 ms*/ + if (ppm_dev->DeltaTime > PIOS_PPM_IN_MIN_CHANNEL_PULSE_US + && ppm_dev->DeltaTime < PIOS_PPM_IN_MAX_CHANNEL_PULSE_US + && ppm_dev->PulseIndex < PIOS_PPM_IN_MAX_NUM_CHANNELS) { + + ppm_dev->CaptureValueNewFrame[ppm_dev->PulseIndex] = ppm_dev->DeltaTime; + ppm_dev->PulseIndex++; + } else { + /* Not a valid pulse duration */ + ppm_dev->Tracking = false; + for (uint32_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS ; i++) { + ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT; + } + } + } +} + +static void PIOS_PPM_Supervisor(uint32_t ppm_id) { + /* Recover our device context */ + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)ppm_id; + + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return; + } + + /* + * RTC runs at 625Hz so divide down the base rate so + * that this loop runs at 25Hz. + */ + if(++(ppm_dev->supv_timer) < 25) { + return; + } + ppm_dev->supv_timer = 0; + + if (!ppm_dev->Fresh) { + ppm_dev->Tracking = false; + + for (int32_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS ; i++) { + ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT; + } + } + + ppm_dev->Fresh = false; +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_pwm.c b/flight/PiOS/STM32F4xx/pios_pwm.c new file mode 100644 index 000000000..5bbec32aa --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_pwm.c @@ -0,0 +1,282 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_PWM PWM Input Functions + * @brief Code to measure with PWM input + * @{ + * + * @file pios_pwm.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief PWM Input functions (STM32 dependent) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" +#include "pios_pwm_priv.h" + +#if defined(PIOS_INCLUDE_PWM) + +/* Provide a RCVR driver */ +static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel); + +const struct pios_rcvr_driver pios_pwm_rcvr_driver = { + .read = PIOS_PWM_Get, +}; + +/* Local Variables */ +/* 100 ms timeout without updates on channels */ +const static uint32_t PWM_SUPERVISOR_TIMEOUT = 100000; + +enum pios_pwm_dev_magic { + PIOS_PWM_DEV_MAGIC = 0xab30293c, +}; + +struct pios_pwm_dev { + enum pios_pwm_dev_magic magic; + const struct pios_pwm_cfg * cfg; + + uint8_t CaptureState[PIOS_PWM_NUM_INPUTS]; + uint16_t RiseValue[PIOS_PWM_NUM_INPUTS]; + uint16_t FallValue[PIOS_PWM_NUM_INPUTS]; + uint32_t CaptureValue[PIOS_PWM_NUM_INPUTS]; + uint32_t CapCounter[PIOS_PWM_NUM_INPUTS]; + uint32_t us_since_update[PIOS_PWM_NUM_INPUTS]; +}; + +static bool PIOS_PWM_validate(struct pios_pwm_dev * pwm_dev) +{ + return (pwm_dev->magic == PIOS_PWM_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_pwm_dev * PIOS_PWM_alloc(void) +{ + struct pios_pwm_dev * pwm_dev; + + pwm_dev = (struct pios_pwm_dev *)pvPortMalloc(sizeof(*pwm_dev)); + if (!pwm_dev) return(NULL); + + pwm_dev->magic = PIOS_PWM_DEV_MAGIC; + return(pwm_dev); +} +#else +static struct pios_pwm_dev pios_pwm_devs[PIOS_PWM_MAX_DEVS]; +static uint8_t pios_pwm_num_devs; +static struct pios_pwm_dev * PIOS_PWM_alloc(void) +{ + struct pios_pwm_dev * pwm_dev; + + if (pios_pwm_num_devs >= PIOS_PWM_MAX_DEVS) { + return (NULL); + } + + pwm_dev = &pios_pwm_devs[pios_pwm_num_devs++]; + pwm_dev->magic = PIOS_PWM_DEV_MAGIC; + + return (pwm_dev); +} +#endif + +static void PIOS_PWM_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +static void PIOS_PWM_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +const static struct pios_tim_callbacks tim_callbacks = { + .overflow = PIOS_PWM_tim_overflow_cb, + .edge = PIOS_PWM_tim_edge_cb, +}; + +/** +* Initialises all the pins +*/ +int32_t PIOS_PWM_Init(uint32_t * pwm_id, const struct pios_pwm_cfg * cfg) +{ + PIOS_DEBUG_Assert(pwm_id); + PIOS_DEBUG_Assert(cfg); + + struct pios_pwm_dev * pwm_dev; + + pwm_dev = (struct pios_pwm_dev *) PIOS_PWM_alloc(); + if (!pwm_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + pwm_dev->cfg = cfg; + + for (uint8_t i = 0; i < PIOS_PWM_NUM_INPUTS; i++) { + /* Flush counter variables */ + pwm_dev->CaptureState[i] = 0; + pwm_dev->RiseValue[i] = 0; + pwm_dev->FallValue[i] = 0; + pwm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + } + + uint32_t tim_id; + if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, &tim_callbacks, (uint32_t)pwm_dev)) { + return -1; + } + + /* Configure the channels to be in capture/compare mode */ + for (uint8_t i = 0; i < cfg->num_channels; i++) { + const struct pios_tim_channel * chan = &cfg->channels[i]; + + /* Configure timer for input capture */ + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); + + /* Enable the Capture Compare Interrupt Request */ + switch (chan->timer_chan) { + case TIM_Channel_1: + TIM_ITConfig(chan->timer, TIM_IT_CC1, ENABLE); + break; + case TIM_Channel_2: + TIM_ITConfig(chan->timer, TIM_IT_CC2, ENABLE); + break; + case TIM_Channel_3: + TIM_ITConfig(chan->timer, TIM_IT_CC3, ENABLE); + break; + case TIM_Channel_4: + TIM_ITConfig(chan->timer, TIM_IT_CC4, ENABLE); + break; + } + + // Need the update event for that timer to detect timeouts + TIM_ITConfig(chan->timer, TIM_IT_Update, ENABLE); + + } + + *pwm_id = (uint32_t) pwm_dev; + + return (0); + +out_fail: + return (-1); +} + +/** +* Get the value of an input channel +* \param[in] Channel Number of the channel desired +* \output -1 Channel not available +* \output >0 Channel value +*/ +static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel) +{ + struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)rcvr_id; + + if (!PIOS_PWM_validate(pwm_dev)) { + /* Invalid device specified */ + return PIOS_RCVR_INVALID; + } + + if (channel >= PIOS_PWM_NUM_INPUTS) { + /* Channel out of range */ + return PIOS_RCVR_INVALID; + } + return pwm_dev->CaptureValue[channel]; +} + +static void PIOS_PWM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) +{ + struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)context; + + if (!PIOS_PWM_validate(pwm_dev)) { + /* Invalid device specified */ + return; + } + + if (channel >= pwm_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + + pwm_dev->us_since_update[channel] += count; + if(pwm_dev->us_since_update[channel] >= PWM_SUPERVISOR_TIMEOUT) { + pwm_dev->CaptureState[channel] = 0; + pwm_dev->RiseValue[channel] = 0; + pwm_dev->FallValue[channel] = 0; + pwm_dev->CaptureValue[channel] = PIOS_RCVR_TIMEOUT; + pwm_dev->us_since_update[channel] = 0; + } + + return; +} + +static void PIOS_PWM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +{ + /* Recover our device context */ + struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)context; + + if (!PIOS_PWM_validate(pwm_dev)) { + /* Invalid device specified */ + return; + } + + if (chan_idx >= pwm_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + + const struct pios_tim_channel * chan = &pwm_dev->cfg->channels[chan_idx]; + + if (pwm_dev->CaptureState[chan_idx] == 0) { + pwm_dev->RiseValue[chan_idx] = count; + pwm_dev->us_since_update[chan_idx] = 0; + } else { + pwm_dev->FallValue[chan_idx] = count; + } + + // flip state machine and capture value here + /* Simple rise or fall state machine */ + TIM_ICInitTypeDef TIM_ICInitStructure = pwm_dev->cfg->tim_ic_init; + if (pwm_dev->CaptureState[chan_idx] == 0) { + /* Switch states */ + pwm_dev->CaptureState[chan_idx] = 1; + + /* Switch polarity of input capture */ + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); + } else { + /* Capture computation */ + if (pwm_dev->FallValue[chan_idx] > pwm_dev->RiseValue[chan_idx]) { + pwm_dev->CaptureValue[chan_idx] = (pwm_dev->FallValue[chan_idx] - pwm_dev->RiseValue[chan_idx]); + } else { + pwm_dev->CaptureValue[chan_idx] = ((chan->timer->ARR - pwm_dev->RiseValue[chan_idx]) + pwm_dev->FallValue[chan_idx]); + } + + /* Switch states */ + pwm_dev->CaptureState[chan_idx] = 0; + + /* Increase supervisor counter */ + pwm_dev->CapCounter[chan_idx]++; + + /* Switch polarity of input capture */ + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); + } + +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_rtc.c b/flight/PiOS/STM32F4xx/pios_rtc.c new file mode 100644 index 000000000..cc2de2ce2 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_rtc.c @@ -0,0 +1,138 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_PWM PWM Input Functions + * @brief Code to measure with PWM input + * @{ + * + * @file pios_pwm.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief PWM Input functions (STM32 dependent) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_RTC) +#include + +#ifndef PIOS_RTC_PRESCALER +#define PIOS_RTC_PRESCALER 100 +#endif + +struct rtc_callback_entry { + void (*fn)(uint32_t); + uint32_t data; +}; + +#define PIOS_RTC_MAX_CALLBACKS 3 +struct rtc_callback_entry rtc_callback_list[PIOS_RTC_MAX_CALLBACKS]; +static uint8_t rtc_callback_next = 0; + +void PIOS_RTC_Init(const struct pios_rtc_cfg * cfg) +{ + RCC_BackupResetCmd(ENABLE); + RCC_BackupResetCmd(DISABLE); + RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE); + PWR_BackupAccessCmd(ENABLE); + // Divide external 8 MHz clock to 1 MHz + RCC_RTCCLKConfig(cfg->clksrc); + RCC_RTCCLKCmd(ENABLE); + + RTC_WakeUpCmd(DISABLE); + // Divide 1 Mhz clock by 16 -> 62.5 khz + RTC_WakeUpClockConfig(RTC_WakeUpClock_RTCCLK_Div16); + // Divide 62.5 khz by 200 to get 625 Hz + RTC_SetWakeUpCounter(cfg->prescaler); //cfg->prescaler); + RTC_WakeUpCmd(ENABLE); + + /* Configure and enable the RTC Second interrupt */ + EXTI_InitTypeDef ExtiInit = { + .EXTI_Line = EXTI_Line22, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }; + EXTI_Init(&ExtiInit); + NVIC_Init(&cfg->irq.init); + RTC_ITConfig(RTC_IT_WUT, ENABLE); + + RTC_ClearFlag(RTC_FLAG_WUTF); +} + +uint32_t PIOS_RTC_Counter() +{ + return RTC_GetWakeUpCounter(); +} + +/* FIXME: This shouldn't use hard-coded clock rates, dividers or prescalers. + * Should get these from the cfg struct passed to init. + */ +float PIOS_RTC_Rate() +{ + return (float) (8e6 / 128) / (1 + PIOS_RTC_PRESCALER); +} + +float PIOS_RTC_MsPerTick() +{ + return 1000.0f / PIOS_RTC_Rate(); +} + +/* TODO: This needs a mutex around rtc_callbacks[] */ +bool PIOS_RTC_RegisterTickCallback(void (*fn)(uint32_t id), uint32_t data) +{ + struct rtc_callback_entry * cb; + if (rtc_callback_next >= PIOS_RTC_MAX_CALLBACKS) { + return false; + } + + cb = &rtc_callback_list[rtc_callback_next++]; + + cb->fn = fn; + cb->data = data; + return true; +} + +void PIOS_RTC_irq_handler (void) +{ + if (RTC_GetITStatus(RTC_IT_WUT)) + { + /* Call all registered callbacks */ + for (uint8_t i = 0; i < rtc_callback_next; i++) { + struct rtc_callback_entry * cb = &rtc_callback_list[i]; + if (cb->fn) { + (cb->fn)(cb->data); + } + } + + /* Clear the RTC Second interrupt */ + RTC_ClearITPendingBit(RTC_IT_WUT); + } + + if (EXTI_GetITStatus(EXTI_Line22) != RESET) + EXTI_ClearITPendingBit(EXTI_Line22); +} +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_servo.c b/flight/PiOS/STM32F4xx/pios_servo.c new file mode 100644 index 000000000..cfcf5c1e5 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_servo.c @@ -0,0 +1,155 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_SERVO RC Servo Functions + * @brief Code to do set RC servo output + * @{ + * + * @file pios_servo.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief RC Servo routines (STM32 dependent) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" +#include "pios_servo_priv.h" +#include "pios_tim_priv.h" + +/* Private Function Prototypes */ + +static const struct pios_servo_cfg * servo_cfg; + +/** +* Initialise Servos +*/ +int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg) +{ + uint32_t tim_id; + if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, NULL, 0)) { + return -1; + } + + /* Store away the requested configuration */ + servo_cfg = cfg; + + /* Configure the channels to be in output compare mode */ + for (uint8_t i = 0; i < cfg->num_channels; i++) { + const struct pios_tim_channel * chan = &cfg->channels[i]; + + /* Set up for output compare function */ + switch(chan->timer_chan) { + case TIM_Channel_1: + TIM_OC1Init(chan->timer, &cfg->tim_oc_init); + TIM_OC1PreloadConfig(chan->timer, TIM_OCPreload_Enable); + break; + case TIM_Channel_2: + TIM_OC2Init(chan->timer, &cfg->tim_oc_init); + TIM_OC2PreloadConfig(chan->timer, TIM_OCPreload_Enable); + break; + case TIM_Channel_3: + TIM_OC3Init(chan->timer, &cfg->tim_oc_init); + TIM_OC3PreloadConfig(chan->timer, TIM_OCPreload_Enable); + break; + case TIM_Channel_4: + TIM_OC4Init(chan->timer, &cfg->tim_oc_init); + TIM_OC4PreloadConfig(chan->timer, TIM_OCPreload_Enable); + break; + } + + TIM_ARRPreloadConfig(chan->timer, ENABLE); + TIM_CtrlPWMOutputs(chan->timer, ENABLE); + TIM_Cmd(chan->timer, ENABLE); + } + + return 0; +} + +/** +* Set the servo update rate (Max 500Hz) +* \param[in] array of rates in Hz +* \param[in] maximum number of banks +*/ +void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks) +{ + if (!servo_cfg) { + return; + } + + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = servo_cfg->tim_base_init; + TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; + TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; + // + + uint8_t set = 0; + + for(uint8_t i = 0; (i < servo_cfg->num_channels) && (set < banks); i++) { + bool new = true; + const struct pios_tim_channel * chan = &servo_cfg->channels[i]; + + /* See if any previous channels use that same timer */ + for(uint8_t j = 0; (j < i) && new; j++) + new &= chan->timer != servo_cfg->channels[j].timer; + + if(new) { + // Choose the correct prescaler value for the APB the timer is attached + if (chan->timer==TIM1 || chan->timer==TIM8 || chan->timer==TIM9 || chan->timer==TIM10 || chan->timer==TIM11 ){ + TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1; + } + else { + TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1; + } + + TIM_TimeBaseStructure.TIM_Period = ((1000000 / speeds[set]) - 1); + TIM_TimeBaseInit(chan->timer, &TIM_TimeBaseStructure); + set++; + } + } +} + +/** +* Set servo position +* \param[in] Servo Servo number (0-7) +* \param[in] Position Servo position in microseconds +*/ +void PIOS_Servo_Set(uint8_t servo, uint16_t position) +{ + /* Make sure servo exists */ + if (!servo_cfg || servo >= servo_cfg->num_channels) { + return; + } + + /* Update the position */ + const struct pios_tim_channel * chan = &servo_cfg->channels[servo]; + switch(chan->timer_chan) { + case TIM_Channel_1: + TIM_SetCompare1(chan->timer, position); + break; + case TIM_Channel_2: + TIM_SetCompare2(chan->timer, position); + break; + case TIM_Channel_3: + TIM_SetCompare3(chan->timer, position); + break; + case TIM_Channel_4: + TIM_SetCompare4(chan->timer, position); + break; + } +} diff --git a/flight/PiOS/STM32F4xx/pios_spi.c b/flight/PiOS/STM32F4xx/pios_spi.c new file mode 100644 index 000000000..87a8e0e9e --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_spi.c @@ -0,0 +1,667 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_SPI SPI Functions + * @brief PIOS interface to read and write from SPI ports + * @{ + * + * @file pios_spi.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Hardware Abstraction Layer for SPI ports of STM32 + * @see The GNU Public License (GPL) Version 3 + * @notes + * + * Note that additional chip select lines can be easily added by using + * the remaining free GPIOs of the core module. Shared SPI ports should be + * arbitrated with (FreeRTOS based) Mutexes to avoid collisions! + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/* + * @todo Clocking is wrong (interface is badly defined, should be speed not prescaler magic numbers) + * @todo DMA doesn't work. Fix it. + */ +#include + +#if defined(PIOS_INCLUDE_SPI) + +#include + +#define SPI_MAX_BLOCK_PIO 128 + +static bool PIOS_SPI_validate(struct pios_spi_dev * com_dev) +{ + /* Should check device magic here */ + return(true); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_spi_dev * PIOS_SPI_alloc(void) +{ + return (malloc(sizeof(struct pios_spi_dev))); +} +#else +static struct pios_spi_dev pios_spi_devs[PIOS_SPI_MAX_DEVS]; +static uint8_t pios_spi_num_devs; +static struct pios_spi_dev * PIOS_SPI_alloc(void) +{ + if (pios_spi_num_devs >= PIOS_SPI_MAX_DEVS) { + return (NULL); + } + + return (&pios_spi_devs[pios_spi_num_devs++]); +} +#endif + +/** +* Initialises SPI pins +* \param[in] mode currently only mode 0 supported +* \return < 0 if initialisation failed +*/ +int32_t PIOS_SPI_Init(uint32_t * spi_id, const struct pios_spi_cfg * cfg) +{ + uint32_t init_ssel = 0; + + PIOS_Assert(spi_id); + PIOS_Assert(cfg); + + struct pios_spi_dev * spi_dev; + + spi_dev = (struct pios_spi_dev *) PIOS_SPI_alloc(); + if (!spi_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + spi_dev->cfg = cfg; + +#if defined(PIOS_INCLUDE_FREERTOS) + vSemaphoreCreateBinary(spi_dev->busy); + xSemaphoreGive(spi_dev->busy); +#endif + + /* Disable callback function */ + spi_dev->callback = NULL; + + /* Set rx/tx dummy bytes to a known value */ + spi_dev->rx_dummy_byte = 0xFF; + spi_dev->tx_dummy_byte = 0xFF; + + switch (spi_dev->cfg->init.SPI_NSS) { + case SPI_NSS_Soft: + if (spi_dev->cfg->init.SPI_Mode == SPI_Mode_Master) { + /* We're a master in soft NSS mode, make sure we see NSS high at all times. */ + SPI_NSSInternalSoftwareConfig(spi_dev->cfg->regs, SPI_NSSInternalSoft_Set); + /* Init as many slave selects as the config advertises. */ + init_ssel = spi_dev->cfg->slave_count; + } else { + /* We're a slave in soft NSS mode, make sure we see NSS low at all times. */ + SPI_NSSInternalSoftwareConfig(spi_dev->cfg->regs, SPI_NSSInternalSoft_Reset); + } + break; + + case SPI_NSS_Hard: + /* only legal for single-slave config */ + PIOS_Assert(spi_dev->cfg->slave_count == 1); + init_ssel = 1; + SPI_SSOutputCmd(spi_dev->cfg->regs, (spi_dev->cfg->init.SPI_Mode == SPI_Mode_Master) ? ENABLE : DISABLE); + /* FIXME: Should this also call SPI_SSOutputCmd()? */ + break; + + default: + PIOS_Assert(0); + } + + /* Initialize the GPIO pins */ + /* note __builtin_ctz() due to the difference between GPIO_PinX and GPIO_PinSourceX */ + if (spi_dev->cfg->remap) { + GPIO_PinAFConfig(spi_dev->cfg->sclk.gpio, + __builtin_ctz(spi_dev->cfg->sclk.init.GPIO_Pin), + spi_dev->cfg->remap); + GPIO_PinAFConfig(spi_dev->cfg->mosi.gpio, + __builtin_ctz(spi_dev->cfg->mosi.init.GPIO_Pin), + spi_dev->cfg->remap); + GPIO_PinAFConfig(spi_dev->cfg->miso.gpio, + __builtin_ctz(spi_dev->cfg->miso.init.GPIO_Pin), + spi_dev->cfg->remap); + for (uint32_t i = 0; i < init_ssel; i++) { + GPIO_PinAFConfig(spi_dev->cfg->ssel[i].gpio, + __builtin_ctz(spi_dev->cfg->ssel[i].init.GPIO_Pin), + spi_dev->cfg->remap); + } + } + GPIO_Init(spi_dev->cfg->sclk.gpio, (GPIO_InitTypeDef*)&(spi_dev->cfg->sclk.init)); + GPIO_Init(spi_dev->cfg->mosi.gpio, (GPIO_InitTypeDef*)&(spi_dev->cfg->mosi.init)); + GPIO_Init(spi_dev->cfg->miso.gpio, (GPIO_InitTypeDef*)&(spi_dev->cfg->miso.init)); + + if(spi_dev->cfg->init.SPI_NSS != SPI_NSS_Hard) { + for (uint32_t i = 0; i < init_ssel; i++) { + /* Since we're driving the SSEL pin in software, ensure that the slave is deselected */ + /* XXX multi-slave support - maybe have another SPI_NSS_ mode? */ + GPIO_SetBits(spi_dev->cfg->ssel[i].gpio, spi_dev->cfg->ssel[i].init.GPIO_Pin); + GPIO_Init(spi_dev->cfg->ssel[i].gpio, (GPIO_InitTypeDef*)&(spi_dev->cfg->ssel[i].init)); + } + } + + /* Configure DMA for SPI Rx */ + DMA_DeInit(spi_dev->cfg->dma.rx.channel); + DMA_Cmd(spi_dev->cfg->dma.rx.channel, DISABLE); + DMA_Init(spi_dev->cfg->dma.rx.channel, (DMA_InitTypeDef*)&(spi_dev->cfg->dma.rx.init)); + + /* Configure DMA for SPI Tx */ + DMA_DeInit(spi_dev->cfg->dma.tx.channel); + DMA_Cmd(spi_dev->cfg->dma.tx.channel, DISABLE); + DMA_Init(spi_dev->cfg->dma.tx.channel, (DMA_InitTypeDef*)&(spi_dev->cfg->dma.tx.init)); + + /* Initialize the SPI block */ + SPI_DeInit(spi_dev->cfg->regs); + SPI_Init(spi_dev->cfg->regs, (SPI_InitTypeDef*)&(spi_dev->cfg->init)); + + /* Configure CRC calculation */ + if (spi_dev->cfg->use_crc) { + SPI_CalculateCRC(spi_dev->cfg->regs, ENABLE); + } else { + SPI_CalculateCRC(spi_dev->cfg->regs, DISABLE); + } + + /* Enable SPI */ + SPI_Cmd(spi_dev->cfg->regs, ENABLE); + + /* Enable SPI interrupts to DMA */ + SPI_I2S_DMACmd(spi_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); + + /* Must store this before enabling interrupt */ + *spi_id = (uint32_t)spi_dev; + + /* Configure DMA interrupt */ + NVIC_Init((NVIC_InitTypeDef*)&(spi_dev->cfg->dma.irq.init)); + + return(0); + +out_fail: + return(-1); +} + +/** + * (Re-)initialises SPI peripheral clock rate + * + * \param[in] spi SPI number (0 or 1) + * \param[in] spi_prescaler configures the SPI speed: + *
    + *
  • PIOS_SPI_PRESCALER_2: sets clock rate 27.7~ nS @ 72 MHz (36 MBit/s) (only supported for spi==0, spi1 uses 4 instead) + *
  • PIOS_SPI_PRESCALER_4: sets clock rate 55.5~ nS @ 72 MHz (18 MBit/s) + *
  • PIOS_SPI_PRESCALER_8: sets clock rate 111.1~ nS @ 72 MHz (9 MBit/s) + *
  • PIOS_SPI_PRESCALER_16: sets clock rate 222.2~ nS @ 72 MHz (4.5 MBit/s) + *
  • PIOS_SPI_PRESCALER_32: sets clock rate 444.4~ nS @ 72 MHz (2.25 MBit/s) + *
  • PIOS_SPI_PRESCALER_64: sets clock rate 888.8~ nS @ 72 MHz (1.125 MBit/s) + *
  • PIOS_SPI_PRESCALER_128: sets clock rate 1.7~ nS @ 72 MHz (0.562 MBit/s) + *
  • PIOS_SPI_PRESCALER_256: sets clock rate 3.5~ nS @ 72 MHz (0.281 MBit/s) + *
+ * \return 0 if no error + * \return -1 if disabled SPI port selected + * \return -3 if invalid spi_prescaler selected + */ +int32_t PIOS_SPI_SetClockSpeed(uint32_t spi_id, SPIPrescalerTypeDef spi_prescaler) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + SPI_InitTypeDef SPI_InitStructure; + + if (spi_prescaler >= 8) { + /* Invalid prescaler selected */ + return -3; + } + + /* Start with a copy of the default configuration for the peripheral */ + SPI_InitStructure = spi_dev->cfg->init; + + /* Adjust the prescaler for the peripheral's clock */ + SPI_InitStructure.SPI_BaudRatePrescaler = ((uint16_t) spi_prescaler & 7) << 3; + + /* Write back the new configuration */ + SPI_Init(spi_dev->cfg->regs, &SPI_InitStructure); + + PIOS_SPI_TransferByte(spi_id, 0xFF); + return 0; +} + +/** + * Claim the SPI bus semaphore. Calling the SPI functions does not require this + * \param[in] spi SPI number (0 or 1) + * \return 0 if no error + * \return -1 if timeout before claiming semaphore + */ +int32_t PIOS_SPI_ClaimBus(uint32_t spi_id) +{ +#if defined(PIOS_INCLUDE_FREERTOS) + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + if (xSemaphoreTake(spi_dev->busy, 0xffff) != pdTRUE) + return -1; +#endif + return 0; +} + +/** + * Claim the SPI bus semaphore from an ISR. Has no timeout. + * \param[in] spi SPI number (0 or 1) + * \return 0 if no error + * \return -1 if timeout before claiming semaphore + */ +int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id) +{ +#if defined(PIOS_INCLUDE_FREERTOS) + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + if (xQueueGenericReceive(( xQueueHandle ) spi_dev->busy, NULL, 0x0000 , pdFALSE ) != pdTRUE) + return -1; +#endif + return 0; +} + + +/** + * Release the SPI bus semaphore. Calling the SPI functions does not require this + * \param[in] spi SPI number (0 or 1) + * \return 0 if no error + */ +int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) +{ +#if defined(PIOS_INCLUDE_FREERTOS) + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + xSemaphoreGive(spi_dev->busy); +#endif + return 0; +} + +/** +* Controls the RC (Register Clock alias Chip Select) pin of a SPI port +* \param[in] spi SPI number (0 or 1) +* \param[in] pin_value 0 or 1 +* \return 0 if no error +*/ +int32_t PIOS_SPI_RC_PinSet(uint32_t spi_id, uint32_t slave_id, uint8_t pin_value) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + PIOS_Assert(slave_id <= spi_dev->cfg->slave_count) + + /* XXX multi-slave support? */ + if (pin_value) { + GPIO_SetBits(spi_dev->cfg->ssel[slave_id].gpio, spi_dev->cfg->ssel[slave_id].init.GPIO_Pin); + } else { + GPIO_ResetBits(spi_dev->cfg->ssel[slave_id].gpio, spi_dev->cfg->ssel[slave_id].init.GPIO_Pin); + } + + return 0; +} + +/** +* Transfers a byte to SPI output and reads back the return value from SPI input +* \param[in] spi SPI number (0 or 1) +* \param[in] b the byte which should be transfered +*/ +int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + +// uint8_t dummy; + uint8_t rx_byte; + + /* + * Procedure taken from STM32F10xxx Reference Manual section 23.3.5 + */ + + /* Make sure the RXNE flag is cleared by reading the DR register */ + /*dummy =*/(void)spi_dev->cfg->regs->DR; + + /* Start the transfer */ + spi_dev->cfg->regs->DR = b; + + /* Wait until there is a byte to read */ + while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_RXNE)) ; + + /* Read the rx'd byte */ + rx_byte = spi_dev->cfg->regs->DR; + + /* Wait until the TXE goes high */ + while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_TXE)) ; + + /* Wait for SPI transfer to have fully completed */ + while (spi_dev->cfg->regs->SR & SPI_I2S_FLAG_BSY) ; + + /* Return received byte */ + return rx_byte; +} + +/** +* Transfers a block of bytes via DMA. +* \param[in] spi SPI number (0 or 1) +* \param[in] send_buffer pointer to buffer which should be sent.
+* If NULL, 0xff (all-one) will be sent. +* \param[in] receive_buffer pointer to buffer which should get the received values.
+* If NULL, received bytes will be discarded. +* \param[in] len number of bytes which should be transfered +* \param[in] callback pointer to callback function which will be executed +* from DMA channel interrupt once the transfer is finished. +* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will +* block until the transfer is finished. +* \return >= 0 if no error during transfer +* \return -1 if disabled SPI port selected +* \return -3 if function has been called during an ongoing DMA transfer +*/ +static int32_t SPI_DMA_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + DMA_InitTypeDef dma_init; + + /* Exit if ongoing transfer */ + if (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)) { + return -3; + } + + /* Disable the DMA channels */ + DMA_Cmd(spi_dev->cfg->dma.rx.channel, DISABLE); + DMA_Cmd(spi_dev->cfg->dma.tx.channel, DISABLE); + + while(DMA_GetCmdStatus(spi_dev->cfg->dma.rx.channel) == ENABLE); + while(DMA_GetCmdStatus(spi_dev->cfg->dma.tx.channel) == ENABLE); + + /* Disable the SPI peripheral */ + /* Initialize the SPI block */ + SPI_DeInit(spi_dev->cfg->regs); + SPI_Init(spi_dev->cfg->regs, (SPI_InitTypeDef*)&(spi_dev->cfg->init)); + SPI_Cmd(spi_dev->cfg->regs, DISABLE); + /* Configure CRC calculation */ + if (spi_dev->cfg->use_crc) { + SPI_CalculateCRC(spi_dev->cfg->regs, ENABLE); + } else { + SPI_CalculateCRC(spi_dev->cfg->regs, DISABLE); + } + + /* Enable SPI interrupts to DMA */ + SPI_I2S_DMACmd(spi_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); + + /* Set callback function */ + spi_dev->callback = callback; + + /* + * Configure Rx channel + */ + + /* Start with the default configuration for this peripheral */ + dma_init = spi_dev->cfg->dma.rx.init; + DMA_DeInit(spi_dev->cfg->dma.rx.channel); + if (receive_buffer != NULL) { + /* Enable memory addr. increment - bytes written into receive buffer */ + dma_init.DMA_Memory0BaseAddr = (uint32_t) receive_buffer; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; + } else { + /* Disable memory addr. increment - bytes written into dummy buffer */ + spi_dev->rx_dummy_byte = 0xFF; + dma_init.DMA_Memory0BaseAddr = (uint32_t) &spi_dev->rx_dummy_byte; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable; + } + if (spi_dev->cfg->use_crc) { + /* Make sure the CRC error flag is cleared before we start */ + SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR); + } + + dma_init.DMA_BufferSize = len; + DMA_Init(spi_dev->cfg->dma.rx.channel, &(dma_init)); + + /* + * Configure Tx channel + */ + + /* Start with the default configuration for this peripheral */ + dma_init = spi_dev->cfg->dma.tx.init; + DMA_DeInit(spi_dev->cfg->dma.tx.channel); + if (send_buffer != NULL) { + /* Enable memory addr. increment - bytes written into receive buffer */ + dma_init.DMA_Memory0BaseAddr = (uint32_t) send_buffer; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; + } else { + /* Disable memory addr. increment - bytes written into dummy buffer */ + spi_dev->tx_dummy_byte = 0xFF; + dma_init.DMA_Memory0BaseAddr = (uint32_t) &spi_dev->tx_dummy_byte; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable; + } + + if (spi_dev->cfg->use_crc) { + /* The last byte of the payload will be replaced with the CRC8 */ + dma_init.DMA_BufferSize = len - 1; + } else { + dma_init.DMA_BufferSize = len; + } + + DMA_Init(spi_dev->cfg->dma.tx.channel, &(dma_init)); + + /* Enable DMA interrupt if callback function active */ + DMA_ITConfig(spi_dev->cfg->dma.rx.channel, DMA_IT_TC, (callback != NULL) ? ENABLE : DISABLE); + + /* Flush out the CRC registers */ + SPI_CalculateCRC(spi_dev->cfg->regs, DISABLE); + (void)SPI_GetCRC(spi_dev->cfg->regs, SPI_CRC_Rx); + SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR); + + /* Make sure to flush out the receive buffer */ + (void)SPI_I2S_ReceiveData(spi_dev->cfg->regs); + + if (spi_dev->cfg->use_crc) { + /* Need a 0->1 transition to reset the CRC logic */ + SPI_CalculateCRC(spi_dev->cfg->regs, ENABLE); + } + + /* Start DMA transfers */ + DMA_Cmd(spi_dev->cfg->dma.rx.channel, ENABLE); + DMA_Cmd(spi_dev->cfg->dma.tx.channel, ENABLE); + + /* Reenable the SPI device */ + SPI_Cmd(spi_dev->cfg->regs, ENABLE); + + if (callback) { + /* User has requested a callback, don't wait for the transfer to complete. */ + return 0; + } + + /* Wait until all bytes have been transmitted/received */ + while (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)); + + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (!(SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE))); + + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)); + + /* Check the CRC on the transfer if enabled. */ + if (spi_dev->cfg->use_crc) { + /* Check the SPI CRC error flag */ + if (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_FLAG_CRCERR)) { + return -4; + } + } + + /* No error */ + return 0; +} + +/** +* Transfers a block of bytes via PIO. +* +* \param[in] spi_id SPI device handle +* \param[in] send_buffer pointer to buffer which should be sent.
+* If NULL, 0xff (all-one) will be sent. +* \param[in] receive_buffer pointer to buffer which should get the received values.
+* If NULL, received bytes will be discarded. +* \param[in] len number of bytes which should be transfered +* \return >= 0 if no error during transfer +* \return -1 if disabled SPI port selected +* \return -3 if function has been called during an ongoing DMA transfer +*/ +static int32_t SPI_PIO_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + uint8_t b; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + /* Exit if ongoing transfer */ + if (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)) { + return -3; + } + + /* Make sure the RXNE flag is cleared by reading the DR register */ + b = spi_dev->cfg->regs->DR; + + while (len--) { + /* get the byte to send */ + b = send_buffer ? *(send_buffer++) : 0xff; + + /* Start the transfer */ + spi_dev->cfg->regs->DR = b; + + /* Wait until there is a byte to read */ + while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_RXNE)) ; + + /* Read the rx'd byte */ + b = spi_dev->cfg->regs->DR; + + /* save the received byte */ + if (receive_buffer) + *(receive_buffer++) = b; + + /* Wait until the TXE goes high */ + while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_TXE)) ; + } + + /* Wait for SPI transfer to have fully completed */ + while (spi_dev->cfg->regs->SR & SPI_I2S_FLAG_BSY) ; + + return 0; +} + + +/** +* Transfers a block of bytes via PIO or DMA. +* \param[in] spi_id SPI device handle +* \param[in] send_buffer pointer to buffer which should be sent.
+* If NULL, 0xff (all-one) will be sent. +* \param[in] receive_buffer pointer to buffer which should get the received values.
+* If NULL, received bytes will be discarded. +* \param[in] len number of bytes which should be transfered +* \param[in] callback pointer to callback function which will be executed +* from DMA channel interrupt once the transfer is finished. +* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will +* block until the transfer is finished. +* \return >= 0 if no error during transfer +* \return -1 if disabled SPI port selected +* \return -3 if function has been called during an ongoing DMA transfer +*/ +int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback) +{ + if (callback || len > SPI_MAX_BLOCK_PIO) { + return SPI_DMA_TransferBlock(spi_id, send_buffer, receive_buffer, len, callback); + } + return SPI_PIO_TransferBlock(spi_id, send_buffer, receive_buffer, len); +} + +/** +* Check if a transfer is in progress +* \param[in] spi SPI number (0 or 1) +* \return >= 0 if no transfer is in progress +* \return -1 if disabled SPI port selected +* \return -2 if unsupported SPI port selected +* \return -3 if function has been called during an ongoing DMA transfer +*/ +int32_t PIOS_SPI_Busy(uint32_t spi_id) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + /* DMA buffer has data or SPI transmit register not empty or SPI is busy*/ + if (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel) || + !SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE) || + SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)) + { + return -3; + } + + return(0); +} + +void PIOS_SPI_IRQ_Handler(uint32_t spi_id) +{ + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(spi_dev); + PIOS_Assert(valid) + + // FIXME XXX Only RX channel or better clear flags for both channels? + DMA_ClearFlag(spi_dev->cfg->dma.rx.channel, spi_dev->cfg->dma.irq.flags); + + if(spi_dev->cfg->init.SPI_Mode == SPI_Mode_Master) { + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (!(SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE))) ; + + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)) ; + } + + if (spi_dev->callback != NULL) { + bool crc_ok = true; + uint8_t crc_val; + + if (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_FLAG_CRCERR)) { + crc_ok = false; + SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR); + } + crc_val = SPI_GetCRC(spi_dev->cfg->regs, SPI_CRC_Rx); + spi_dev->callback(crc_ok, crc_val); + } +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_sys.c b/flight/PiOS/STM32F4xx/pios_sys.c new file mode 100644 index 000000000..8ee9a79ce --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_sys.c @@ -0,0 +1,320 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_SYS System Functions + * @brief PIOS System Initialization code + * @{ + * + * @file pios_sys.c + * @author Michael Smith Copyright (C) 2011 + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Sets up basic STM32 system hardware, functions are called from Main. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_SYS) + +#define MEM8(addr) (*((volatile uint8_t *)(addr))) + +/* Private Function Prototypes */ +static void NVIC_Configuration(void); + +/** +* Initialises all system peripherals +*/ +void PIOS_SYS_Init(void) +{ + /* Setup STM32 system (RCC, clock, PLL and Flash configuration) - CMSIS Function */ + SystemInit(); + SystemCoreClockUpdate(); /* update SystemCoreClock for use elsewhere */ + + /* + * @todo might make sense to fetch the bus clocks and save them somewhere to avoid + * having to use the clunky get-all-clocks API everytime we need one. + */ + + /* Initialise Basic NVIC */ + /* do this early to ensure that we take exceptions in the right place */ + NVIC_Configuration(); + + /* Init the delay system */ + PIOS_DELAY_Init(); + + /* + * Turn on all the peripheral clocks. + * Micromanaging clocks makes no sense given the power situation in the system, so + * light up everything we might reasonably use here and just leave it on. + */ + RCC_AHB1PeriphClockCmd( + RCC_AHB1Periph_GPIOA | + RCC_AHB1Periph_GPIOB | + RCC_AHB1Periph_GPIOC | + RCC_AHB1Periph_GPIOD | + RCC_AHB1Periph_GPIOE | + RCC_AHB1Periph_GPIOF | + RCC_AHB1Periph_GPIOG | + RCC_AHB1Periph_GPIOH | + RCC_AHB1Periph_GPIOI | + RCC_AHB1Periph_CRC | + RCC_AHB1Periph_FLITF | + RCC_AHB1Periph_SRAM1 | + RCC_AHB1Periph_SRAM2 | + RCC_AHB1Periph_BKPSRAM | + RCC_AHB1Periph_DMA1 | + RCC_AHB1Periph_DMA2 | + //RCC_AHB1Periph_ETH_MAC | No ethernet + //RCC_AHB1Periph_ETH_MAC_Tx | + //RCC_AHB1Periph_ETH_MAC_Rx | + //RCC_AHB1Periph_ETH_MAC_PTP | + //RCC_AHB1Periph_OTG_HS | No high-speed USB (requires external PHY) + //RCC_AHB1Periph_OTG_HS_ULPI | No ULPI PHY (see above) + 0, ENABLE); + RCC_AHB2PeriphClockCmd( + //RCC_AHB2Periph_DCMI | No camera @todo might make sense later for basic vision support? + //RCC_AHB2Periph_CRYP | No crypto + //RCC_AHB2Periph_HASH | No hash generator + //RCC_AHB2Periph_RNG | No random numbers @todo might be good to have later if entropy is desired + //RCC_AHB2Periph_OTG_FS | + 0, ENABLE); + RCC_AHB3PeriphClockCmd( + //RCC_AHB3Periph_FSMC | No external static memory + 0, ENABLE); + RCC_APB1PeriphClockCmd( + RCC_APB1Periph_TIM2 | + RCC_APB1Periph_TIM3 | + RCC_APB1Periph_TIM4 | + RCC_APB1Periph_TIM5 | + RCC_APB1Periph_TIM6 | + RCC_APB1Periph_TIM7 | + RCC_APB1Periph_TIM12 | + RCC_APB1Periph_TIM13 | + RCC_APB1Periph_TIM14 | + RCC_APB1Periph_WWDG | + RCC_APB1Periph_SPI2 | + RCC_APB1Periph_SPI3 | + RCC_APB1Periph_USART2 | + RCC_APB1Periph_USART3 | + RCC_APB1Periph_UART4 | + RCC_APB1Periph_UART5 | + RCC_APB1Periph_I2C1 | + RCC_APB1Periph_I2C2 | + RCC_APB1Periph_I2C3 | + RCC_APB1Periph_CAN1 | + RCC_APB1Periph_CAN2 | + RCC_APB1Periph_PWR | + RCC_APB1Periph_DAC | + 0, ENABLE); + + RCC_APB2PeriphClockCmd( + RCC_APB2Periph_TIM1 | + RCC_APB2Periph_TIM8 | + RCC_APB2Periph_USART1 | + RCC_APB2Periph_USART6 | + RCC_APB2Periph_ADC | + RCC_APB2Periph_ADC1 | + RCC_APB2Periph_ADC2 | + RCC_APB2Periph_ADC3 | + RCC_APB2Periph_SDIO | + RCC_APB2Periph_SPI1 | + RCC_APB2Periph_SYSCFG | + RCC_APB2Periph_TIM9 | + RCC_APB2Periph_TIM10 | + RCC_APB2Periph_TIM11 | + 0, ENABLE); + + /* + * Configure all pins as input / pullup to avoid issues with + * uncommitted pins, excepting special-function pins that we need to + * remain as-is. + */ + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_StructInit(&GPIO_InitStructure); + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // default is un-pulled input + + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All; +#if (PIOS_USB_ENABLED) + GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_11 | GPIO_Pin_12); // leave USB D+/D- alone +#endif + GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15); // leave JTAG pins alone + GPIO_Init(GPIOA, &GPIO_InitStructure); + + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All; + GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_3 | GPIO_Pin_4); // leave JTAG pins alone + GPIO_Init(GPIOB, &GPIO_InitStructure); + + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All; + GPIO_Init(GPIOC, &GPIO_InitStructure); + GPIO_Init(GPIOD, &GPIO_InitStructure); + GPIO_Init(GPIOE, &GPIO_InitStructure); + GPIO_Init(GPIOF, &GPIO_InitStructure); + GPIO_Init(GPIOG, &GPIO_InitStructure); + GPIO_Init(GPIOH, &GPIO_InitStructure); + GPIO_Init(GPIOI, &GPIO_InitStructure); +} + +/** +* Shutdown PIOS and reset the microcontroller:
+*
    +*
  • Disable all RTOS tasks +*
  • Disable all interrupts +*
  • Turn off all board LEDs +*
  • Reset STM32 +*
+* \return < 0 if reset failed +*/ +int32_t PIOS_SYS_Reset(void) +{ + /* Disable all RTOS tasks */ +#if defined(PIOS_INCLUDE_FREERTOS) + /* port specific FreeRTOS function to disable tasks (nested) */ + portENTER_CRITICAL(); +#endif + + // disable all interrupts + PIOS_IRQ_Disable(); + + // turn off all board LEDs +#if (PIOS_LED_NUM == 1) + PIOS_LED_Off(LED1); +#elif (PIOS_LED_NUM == 2) + PIOS_LED_Off(LED1); + PIOS_LED_Off(LED2); +#endif + + /* XXX F10x port resets most (but not all) peripherals ... do we care? */ + + /* Reset STM32 */ + NVIC_SystemReset(); + + while (1) ; + + /* We will never reach this point */ + return -1; +} + +/** +* Returns the CPU's flash size (in bytes) +*/ +uint32_t PIOS_SYS_getCPUFlashSize(void) +{ + return ((uint32_t) MEM_SIZE); // it might be possible to locate in the OTP area, but haven't looked and not documented +} + +/** + * Returns the serial number as a string + * param[out] str pointer to a string which can store at least 32 digits + zero terminator! + * (24 digits returned for STM32) + * return < 0 if feature not supported + */ +int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array) +{ + int i; + + /* Stored in the so called "electronic signature" */ + for (i = 0; i < 12; ++i) { + uint8_t b = MEM8(0x1ffff7e8 + i); + + array[i] = b; + } + + /* No error */ + return 0; +} + +/** +* Returns the serial number as a string +* param[out] str pointer to a string which can store at least 32 digits + zero terminator! +* (24 digits returned for STM32) +* return < 0 if feature not supported +*/ +int32_t PIOS_SYS_SerialNumberGet(char *str) +{ + int i; + + /* Stored in the so called "electronic signature" */ + for (i = 0; i < 24; ++i) { + uint8_t b = *(uint8_t *)(0x1fff7a10 + i/2); + if (!(i & 1)) + b >>= 4; + b &= 0x0f; + + str[i] = ((b > 9) ? ('A' - 10) : '0') + b; + } + str[i] = '\0'; + + /* No error */ + return 0; +} + +/** +* Configures Vector Table base location and SysTick +*/ +static void NVIC_Configuration(void) +{ + /* Set the Vector Table base address as specified in .ld file */ + extern void *pios_isr_vector_table_base; + NVIC_SetVectorTable((uint32_t)&pios_isr_vector_table_base, 0x0); + + /* 4 bits for Interrupt priorities so no sub priorities */ + NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4); + + /* Configure HCLK clock as SysTick clock source. */ + SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK); +} + +#ifdef USE_FULL_ASSERT +/** +* Reports the name of the source file and the source line number +* where the assert_param error has occurred. +* \param[in] file pointer to the source file name +* \param[in] line assert_param error line source number +* \retval None +*/ +void assert_failed(uint8_t * file, uint32_t line) +{ + /* When serial debugging is implemented, use something like this. */ + /* printf("Wrong parameters value: file %s on line %d\r\n", file, line); */ + + /* Setup the LEDs to Alternate */ +#if defined(PIOS_LED_ALARM) + PIOS_LED_On(PIOS_LED_ALARM); +#endif +#if defiend(PIOS_LED_HEARTBEAT) + PIOS_LED_Off(PIOS_LED_HEARTBEAT); +#endif + + /* Infinite loop */ + while (1) { + PIOS_LED_Toggle(LED1); + PIOS_LED_Toggle(LED2); + for (int i = 0; i < 1000000; i++) ; + } +} +#endif + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_tim.c b/flight/PiOS/STM32F4xx/pios_tim.c new file mode 100644 index 000000000..7e3c6c1f6 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_tim.c @@ -0,0 +1,492 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_TIM Timer Functions + * @brief PIOS Timer control code + * @{ + * + * @file pios_tim.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Sets up timers and ways to register callbacks on them + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#include "pios.h" + +#include "pios_tim.h" +#include "pios_tim_priv.h" + +enum pios_tim_dev_magic { + PIOS_TIM_DEV_MAGIC = 0x87654098, +}; + +struct pios_tim_dev { + enum pios_tim_dev_magic magic; + + const struct pios_tim_channel * channels; + uint8_t num_channels; + + const struct pios_tim_callbacks * callbacks; + uint32_t context; +}; + +#if 0 +static bool PIOS_TIM_validate(struct pios_tim_dev * tim_dev) +{ + return (tim_dev->magic == PIOS_TIM_DEV_MAGIC); +} +#endif + +#if defined(PIOS_INCLUDE_FREERTOS) && 0 +static struct pios_tim_dev * PIOS_TIM_alloc(void) +{ + struct pios_tim_dev * tim_dev; + + tim_dev = (struct pios_tim_dev *)malloc(sizeof(*tim_dev)); + if (!tim_dev) return(NULL); + + tim_dev->magic = PIOS_TIM_DEV_MAGIC; + return(tim_dev); +} +#else +static struct pios_tim_dev pios_tim_devs[PIOS_TIM_MAX_DEVS]; +static uint8_t pios_tim_num_devs; +static struct pios_tim_dev * PIOS_TIM_alloc(void) +{ + struct pios_tim_dev * tim_dev; + + if (pios_tim_num_devs >= PIOS_TIM_MAX_DEVS) { + return (NULL); + } + + tim_dev = &pios_tim_devs[pios_tim_num_devs++]; + tim_dev->magic = PIOS_TIM_DEV_MAGIC; + + return (tim_dev); +} +#endif + + + + +int32_t PIOS_TIM_InitClock(const struct pios_tim_clock_cfg * cfg) +{ + PIOS_DEBUG_Assert(cfg); + + /* Enable appropriate clock to timer module */ + switch((uint32_t) cfg->timer) { + case (uint32_t)TIM1: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); + break; + case (uint32_t)TIM2: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); + break; + case (uint32_t)TIM3: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); + break; + case (uint32_t)TIM4: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); + break; +#ifdef STM32F10X_HD + case (uint32_t)TIM5: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); + break; + case (uint32_t)TIM6: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); + break; + case (uint32_t)TIM7: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); + break; + case (uint32_t)TIM8: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); + break; + case (uint32_t)TIM9: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM9, ENABLE); + break; + case (uint32_t)TIM10: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM10, ENABLE); + break; + case (uint32_t)TIM11: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM11, ENABLE); + break; +#endif + } + + /* Configure the dividers for this timer */ + TIM_TimeBaseInit(cfg->timer, cfg->time_base_init); + + /* Configure internal timer clocks */ + TIM_InternalClockConfig(cfg->timer); + + /* Enable timers */ + TIM_Cmd(cfg->timer, ENABLE); + + /* Enable Interrupts */ + NVIC_Init(&cfg->irq.init); + + return 0; +} + +int32_t PIOS_TIM_InitChannels(uint32_t * tim_id, const struct pios_tim_channel * channels, uint8_t num_channels, const struct pios_tim_callbacks * callbacks, uint32_t context) +{ + PIOS_Assert(channels); + PIOS_Assert(num_channels); + + struct pios_tim_dev * tim_dev; + tim_dev = (struct pios_tim_dev *) PIOS_TIM_alloc(); + if (!tim_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + tim_dev->channels = channels; + tim_dev->num_channels = num_channels; + tim_dev->callbacks = callbacks; + tim_dev->context = context; + + /* Configure the pins */ + for (uint8_t i = 0; i < num_channels; i++) { + const struct pios_tim_channel * chan = &(channels[i]); + + /* Enable the peripheral clock for the GPIO */ +/* switch ((uint32_t)chan->pin.gpio) { + case (uint32_t) GPIOA: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); + break; + case (uint32_t) GPIOB: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + break; + case (uint32_t) GPIOC: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + break; + default: + PIOS_Assert(0); + break; + } +*/ // commented out for now as f4 starts all clocks + GPIO_Init(chan->pin.gpio, &chan->pin.init); + + PIOS_DEBUG_Assert(chan->remaP); + + // Second parameter should technically be PinSource but they are numerically the same + GPIO_PinAFConfig(chan->pin.gpio, chan->pin.pin_source,chan->remap); + } + + *tim_id = (uint32_t)tim_dev; + + return(0); + +out_fail: + return(-1); +} + +static void PIOS_TIM_generic_irq_handler(TIM_TypeDef * timer) +{ + /* Iterate over all registered clients of the TIM layer to find channels on this timer */ + for (uint8_t i = 0; i < pios_tim_num_devs; i++) { + const struct pios_tim_dev * tim_dev = &pios_tim_devs[i]; + + if (!tim_dev->channels || tim_dev->num_channels == 0) { + /* No channels to process on this client */ + continue; + } + + /* Check for an overflow event on this timer */ + bool overflow_event; + uint16_t overflow_count; + if (TIM_GetITStatus(timer, TIM_IT_Update) == SET) { + TIM_ClearITPendingBit(timer, TIM_IT_Update); + overflow_count = timer->ARR; + overflow_event = true; + } else { + overflow_count = 0; + overflow_event = false; + } + + for (uint8_t j = 0; j < tim_dev->num_channels; j++) { + const struct pios_tim_channel * chan = &tim_dev->channels[j]; + + if (chan->timer != timer) { + /* channel is not on this timer */ + continue; + } + + /* Figure out which interrupt bit we should be looking at */ + uint16_t timer_it; + switch (chan->timer_chan) { + case TIM_Channel_1: + timer_it = TIM_IT_CC1; + break; + case TIM_Channel_2: + timer_it = TIM_IT_CC2; + break; + case TIM_Channel_3: + timer_it = TIM_IT_CC3; + break; + case TIM_Channel_4: + timer_it = TIM_IT_CC4; + break; + default: + PIOS_Assert(0); + break; + } + + bool edge_event; + uint16_t edge_count; + if (TIM_GetITStatus(chan->timer, timer_it) == SET) { + TIM_ClearITPendingBit(chan->timer, timer_it); + + /* Read the current counter */ + switch(chan->timer_chan) { + case TIM_Channel_1: + edge_count = TIM_GetCapture1(chan->timer); + break; + case TIM_Channel_2: + edge_count = TIM_GetCapture2(chan->timer); + break; + case TIM_Channel_3: + edge_count = TIM_GetCapture3(chan->timer); + break; + case TIM_Channel_4: + edge_count = TIM_GetCapture4(chan->timer); + break; + default: + PIOS_Assert(0); + break; + } + edge_event = true; + } else { + edge_event = false; + edge_count = 0; + } + + if (!tim_dev->callbacks) { + /* No callbacks registered, we're done with this channel */ + continue; + } + + /* Generate the appropriate callbacks */ + if (overflow_event & edge_event) { + /* + * When both edge and overflow happen in the same interrupt, we + * need a heuristic to determine the order of the edge and overflow + * events so that the callbacks happen in the right order. If we + * get the order wrong, our pulse width calculations could be off by up + * to ARR ticks. That could be bad. + * + * Heuristic: If the edge_count is < 16 ticks above zero then we assume the + * edge happened just after the overflow. + */ + + if (edge_count < 16) { + /* Call the overflow callback first */ + if (tim_dev->callbacks->overflow) { + (*tim_dev->callbacks->overflow)((uint32_t)tim_dev, + tim_dev->context, + j, + overflow_count); + } + /* Call the edge callback second */ + if (tim_dev->callbacks->edge) { + (*tim_dev->callbacks->edge)((uint32_t)tim_dev, + tim_dev->context, + j, + edge_count); + } + } else { + /* Call the edge callback first */ + if (tim_dev->callbacks->edge) { + (*tim_dev->callbacks->edge)((uint32_t)tim_dev, + tim_dev->context, + j, + edge_count); + } + /* Call the overflow callback second */ + if (tim_dev->callbacks->overflow) { + (*tim_dev->callbacks->overflow)((uint32_t)tim_dev, + tim_dev->context, + j, + overflow_count); + } + } + } else if (overflow_event && tim_dev->callbacks->overflow) { + (*tim_dev->callbacks->overflow)((uint32_t)tim_dev, + tim_dev->context, + j, + overflow_count); + } else if (edge_event && tim_dev->callbacks->edge) { + (*tim_dev->callbacks->edge)((uint32_t)tim_dev, + tim_dev->context, + j, + edge_count); + } + } + } +} +#if 0 + uint16_t val = 0; + for(uint8_t i = 0; i < pios_pwm_cfg.num_channels; i++) { + struct pios_pwm_channel channel = pios_pwm_cfg.channels[i]; + if ((channel.timer == timer) && (TIM_GetITStatus(channel.timer, channel.ccr) == SET)) { + + TIM_ClearITPendingBit(channel.timer, channel.ccr); + + switch(channel.channel) { + case TIM_Channel_1: + val = TIM_GetCapture1(channel.timer); + break; + case TIM_Channel_2: + val = TIM_GetCapture2(channel.timer); + break; + case TIM_Channel_3: + val = TIM_GetCapture3(channel.timer); + break; + case TIM_Channel_4: + val = TIM_GetCapture4(channel.timer); + break; + } + + if (CaptureState[i] == 0) { + RiseValue[i] = val; + } else { + FallValue[i] = val; + } + + // flip state machine and capture value here + /* Simple rise or fall state machine */ + TIM_ICInitTypeDef TIM_ICInitStructure = pios_pwm_cfg.tim_ic_init; + if (CaptureState[i] == 0) { + /* Switch states */ + CaptureState[i] = 1; + + /* Switch polarity of input capture */ + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; + TIM_ICInitStructure.TIM_Channel = channel.channel; + TIM_ICInit(channel.timer, &TIM_ICInitStructure); + } else { + /* Capture computation */ + if (FallValue[i] > RiseValue[i]) { + CaptureValue[i] = (FallValue[i] - RiseValue[i]); + } else { + CaptureValue[i] = ((channel.timer->ARR - RiseValue[i]) + FallValue[i]); + } + + /* Switch states */ + CaptureState[i] = 0; + + /* Increase supervisor counter */ + CapCounter[i]++; + + /* Switch polarity of input capture */ + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStructure.TIM_Channel = channel.channel; + TIM_ICInit(channel.timer, &TIM_ICInitStructure); + } + } + } +#endif + +/* Bind Interrupt Handlers + * + * Map all valid TIM IRQs to the common interrupt handler + * and give it enough context to properly demux the various timers + */ +void TIM1_CC_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_1_CC_irq_handler"))); +static void PIOS_TIM_1_CC_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM1); +} + +// The rest of TIM1 interrupts are overlapped +void TIM1_BRK_TIM9_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_9_CC_irq_handler"))); +static void PIOS_TIM_9_CC_irq_handler (void) +{ + // TODO: Check for TIM1_BRK + PIOS_TIM_generic_irq_handler (TIM9); +} + +void TIM1_UP_TIM10_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_10_CC_irq_handler"))); +static void PIOS_TIM_10_CC_irq_handler (void) +{ + if (TIM_GetITStatus(TIM1, TIM_IT_Update)) { + PIOS_TIM_generic_irq_handler(TIM1); + } else if (TIM_GetITStatus(TIM10, TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4)) { + PIOS_TIM_generic_irq_handler (TIM10); + } +} + +void TIM1_TRG_COM_TIM11_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_11_CC_irq_handler"))); +static void PIOS_TIM_11_CC_irq_handler (void) +{ + // TODO: Check for TIM1_TRG + PIOS_TIM_generic_irq_handler (TIM11); +} + +void TIM2_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_2_irq_handler"))); +static void PIOS_TIM_2_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM2); +} + +void TIM3_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_3_irq_handler"))); +static void PIOS_TIM_3_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM3); +} + +void TIM4_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_4_irq_handler"))); +static void PIOS_TIM_4_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM4); +} + +void TIM5_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_5_irq_handler"))); +static void PIOS_TIM_5_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM5); +} + +void TIM6_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_6_irq_handler"))); +static void PIOS_TIM_6_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM6); +} + +void TIM7_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_7_irq_handler"))); +static void PIOS_TIM_7_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM7); +} + +void TIM8_UP_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_8_UP_irq_handler"))); +static void PIOS_TIM_8_UP_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM8); +} + +void TIM8_CC_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_8_CC_irq_handler"))); +static void PIOS_TIM_8_CC_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM8); +} + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_usart.c b/flight/PiOS/STM32F4xx/pios_usart.c new file mode 100644 index 000000000..2fe780e48 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_usart.c @@ -0,0 +1,358 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USART USART Functions + * @brief PIOS interface for USART port + * @{ + * + * @file pios_usart.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief USART commands. Inits USARTs, controls USARTs & Interupt handlers. (STM32 dependent) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* + * @todo This is virtually identical to the F1xx driver and should be merged. + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_USART) + +#include + +/* Provide a COM driver */ +static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud); +static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context); +static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context); +static void PIOS_USART_TxStart(uint32_t usart_id, uint16_t tx_bytes_avail); +static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail); + +const struct pios_com_driver pios_usart_com_driver = { + .set_baud = PIOS_USART_ChangeBaud, + .tx_start = PIOS_USART_TxStart, + .rx_start = PIOS_USART_RxStart, + .bind_tx_cb = PIOS_USART_RegisterTxCallback, + .bind_rx_cb = PIOS_USART_RegisterRxCallback, +}; + +enum pios_usart_dev_magic { + PIOS_USART_DEV_MAGIC = 0x4152834A, +}; + +struct pios_usart_dev { + enum pios_usart_dev_magic magic; + const struct pios_usart_cfg * cfg; + + pios_com_callback rx_in_cb; + uint32_t rx_in_context; + pios_com_callback tx_out_cb; + uint32_t tx_out_context; +}; + +static bool PIOS_USART_validate(struct pios_usart_dev * usart_dev) +{ + return (usart_dev->magic == PIOS_USART_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_usart_dev * PIOS_USART_alloc(void) +{ + struct pios_usart_dev * usart_dev; + + usart_dev = (struct pios_usart_dev *)pvPortMalloc(sizeof(*usart_dev)); + if (!usart_dev) return(NULL); + + usart_dev->rx_in_cb = 0; + usart_dev->rx_in_context = 0; + usart_dev->tx_out_cb = 0; + usart_dev->tx_out_context = 0; + usart_dev->magic = PIOS_USART_DEV_MAGIC; + return(usart_dev); +} +#else +static struct pios_usart_dev pios_usart_devs[PIOS_USART_MAX_DEVS]; +static uint8_t pios_usart_num_devs; +static struct pios_usart_dev * PIOS_USART_alloc(void) +{ + struct pios_usart_dev * usart_dev; + + if (pios_usart_num_devs >= PIOS_USART_MAX_DEVS) { + return (NULL); + } + + usart_dev = &pios_usart_devs[pios_usart_num_devs++]; + usart_dev->magic = PIOS_USART_DEV_MAGIC; + + return (usart_dev); +} +#endif + +/* Bind Interrupt Handlers + * + * Map all valid USART IRQs to the common interrupt handler + * and provide storage for a 32-bit device id IRQ to map + * each physical IRQ to a specific registered device instance. + */ +static void PIOS_USART_generic_irq_handler(uint32_t usart_id); + +static uint32_t PIOS_USART_1_id; +void USART1_IRQHandler(void) __attribute__ ((alias ("PIOS_USART_1_irq_handler"))); +static void PIOS_USART_1_irq_handler (void) +{ + PIOS_USART_generic_irq_handler (PIOS_USART_1_id); +} + +static uint32_t PIOS_USART_2_id; +void USART2_IRQHandler(void) __attribute__ ((alias ("PIOS_USART_2_irq_handler"))); +static void PIOS_USART_2_irq_handler (void) +{ + PIOS_USART_generic_irq_handler (PIOS_USART_2_id); +} + +static uint32_t PIOS_USART_3_id; +void USART3_IRQHandler(void) __attribute__ ((alias ("PIOS_USART_3_irq_handler"))); +static void PIOS_USART_3_irq_handler (void) +{ + PIOS_USART_generic_irq_handler (PIOS_USART_3_id); +} + +static uint32_t PIOS_USART_4_id; +void USART4_IRQHandler(void) __attribute__ ((alias ("PIOS_USART_4_irq_handler"))); +static void PIOS_USART_4_irq_handler (void) +{ + PIOS_USART_generic_irq_handler (PIOS_USART_4_id); +} + +static uint32_t PIOS_USART_5_id; +void USART5_IRQHandler(void) __attribute__ ((alias ("PIOS_USART_5_irq_handler"))); +static void PIOS_USART_5_irq_handler (void) +{ + PIOS_USART_generic_irq_handler (PIOS_USART_5_id); +} + +static uint32_t PIOS_USART_6_id; +void USART6_IRQHandler(void) __attribute__ ((alias ("PIOS_USART_6_irq_handler"))); +static void PIOS_USART_6_irq_handler (void) +{ + PIOS_USART_generic_irq_handler (PIOS_USART_6_id); +} + +/** +* Initialise a single USART device +*/ +int32_t PIOS_USART_Init(uint32_t * usart_id, const struct pios_usart_cfg * cfg) +{ + PIOS_DEBUG_Assert(usart_id); + PIOS_DEBUG_Assert(cfg); + + struct pios_usart_dev * usart_dev; + + usart_dev = (struct pios_usart_dev *) PIOS_USART_alloc(); + if (!usart_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + usart_dev->cfg = cfg; + + /* Map pins to USART function */ + /* note __builtin_ctz() due to the difference between GPIO_PinX and GPIO_PinSourceX */ + if (usart_dev->cfg->remap) { + GPIO_PinAFConfig(usart_dev->cfg->rx.gpio, + __builtin_ctz(usart_dev->cfg->rx.init.GPIO_Pin), + usart_dev->cfg->remap); + GPIO_PinAFConfig(usart_dev->cfg->tx.gpio, + __builtin_ctz(usart_dev->cfg->tx.init.GPIO_Pin), + usart_dev->cfg->remap); + } + + /* Initialize the USART Rx and Tx pins */ + GPIO_Init(usart_dev->cfg->rx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->rx.init); + GPIO_Init(usart_dev->cfg->tx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->tx.init); + + /* Configure the USART */ + USART_Init(usart_dev->cfg->regs, (USART_InitTypeDef *)&usart_dev->cfg->init); + + *usart_id = (uint32_t)usart_dev; + + /* Configure USART Interrupts */ + switch ((uint32_t)usart_dev->cfg->regs) { + case (uint32_t)USART1: + PIOS_USART_1_id = (uint32_t)usart_dev; + break; + case (uint32_t)USART2: + PIOS_USART_2_id = (uint32_t)usart_dev; + break; + case (uint32_t)USART3: + PIOS_USART_3_id = (uint32_t)usart_dev; + break; + case (uint32_t)UART4: + PIOS_USART_4_id = (uint32_t)usart_dev; + break; + case (uint32_t)UART5: + PIOS_USART_5_id = (uint32_t)usart_dev; + break; + case (uint32_t)USART6: + PIOS_USART_6_id = (uint32_t)usart_dev; + break; + } + NVIC_Init((NVIC_InitTypeDef *)&(usart_dev->cfg->irq.init)); + USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE); + USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE); + + // FIXME XXX Clear / reset uart here - sends NUL char else + + /* Enable USART */ + USART_Cmd(usart_dev->cfg->regs, ENABLE); + + return(0); + +out_fail: + return(-1); +} + +static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail) +{ + struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id; + + bool valid = PIOS_USART_validate(usart_dev); + PIOS_Assert(valid); + + USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE); +} +static void PIOS_USART_TxStart(uint32_t usart_id, uint16_t tx_bytes_avail) +{ + struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id; + + bool valid = PIOS_USART_validate(usart_dev); + PIOS_Assert(valid); + + USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE); +} + +/** +* Changes the baud rate of the USART peripheral without re-initialising. +* \param[in] usart_id USART name (GPS, TELEM, AUX) +* \param[in] baud Requested baud rate +*/ +static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud) +{ + struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id; + + bool valid = PIOS_USART_validate(usart_dev); + PIOS_Assert(valid); + + USART_InitTypeDef USART_InitStructure; + + /* Start with a copy of the default configuration for the peripheral */ + USART_InitStructure = usart_dev->cfg->init; + + /* Adjust the baud rate */ + USART_InitStructure.USART_BaudRate = baud; + + /* Write back the new configuration */ + USART_Init(usart_dev->cfg->regs, &USART_InitStructure); +} + +static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context) +{ + struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id; + + bool valid = PIOS_USART_validate(usart_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + usart_dev->rx_in_context = context; + usart_dev->rx_in_cb = rx_in_cb; +} + +static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context) +{ + struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id; + + bool valid = PIOS_USART_validate(usart_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + usart_dev->tx_out_context = context; + usart_dev->tx_out_cb = tx_out_cb; +} + +static void PIOS_USART_generic_irq_handler(uint32_t usart_id) +{ + struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id; + + bool valid = PIOS_USART_validate(usart_dev); + PIOS_Assert(valid); + + /* Force read of dr after sr to make sure to clear error flags */ + volatile uint16_t sr = usart_dev->cfg->regs->SR; + volatile uint8_t dr = usart_dev->cfg->regs->DR; + + /* Check if RXNE flag is set */ + bool rx_need_yield = false; + if (sr & USART_SR_RXNE) { + uint8_t byte = dr; + if (usart_dev->rx_in_cb) { + (void) (usart_dev->rx_in_cb)(usart_dev->rx_in_context, &byte, 1, NULL, &rx_need_yield); + } + } + + /* Check if TXE flag is set */ + bool tx_need_yield = false; + if (sr & USART_SR_TXE) { + if (usart_dev->tx_out_cb) { + uint8_t b; + uint16_t bytes_to_send; + + bytes_to_send = (usart_dev->tx_out_cb)(usart_dev->tx_out_context, &b, 1, NULL, &tx_need_yield); + + if (bytes_to_send > 0) { + /* Send the byte we've been given */ + usart_dev->cfg->regs->DR = b; + } else { + /* No bytes to send, disable TXE interrupt */ + USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, DISABLE); + } + } else { + /* No bytes to send, disable TXE interrupt */ + USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, DISABLE); + } + } + +#if defined(PIOS_INCLUDE_FREERTOS) + if (rx_need_yield || tx_need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_usb.c b/flight/PiOS/STM32F4xx/pios_usb.c new file mode 100644 index 000000000..5369ea672 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_usb.c @@ -0,0 +1,269 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB USB Setup Functions + * @brief PIOS USB device implementation + * @{ + * + * @file pios_usb.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief USB device functions (STM32 dependent code) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" +#include "usb_core.h" +#include "pios_usb_board_data.h" +#include "pios_usb.h" +#include "pios_usb_priv.h" + +#if defined(PIOS_INCLUDE_USB) + +/* Rx/Tx status */ +static uint8_t transfer_possible = 0; + +enum pios_usb_dev_magic { + PIOS_USB_DEV_MAGIC = 0x17365904, +}; + +struct pios_usb_dev { + enum pios_usb_dev_magic magic; + const struct pios_usb_cfg * cfg; +}; + +/** + * @brief Validate the usb device structure + * @returns true if valid device or false otherwise + */ +static bool PIOS_USB_validate(struct pios_usb_dev * usb_dev) +{ + return (usb_dev && (usb_dev->magic == PIOS_USB_DEV_MAGIC)); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_usb_dev * PIOS_USB_alloc(void) +{ + struct pios_usb_dev * usb_dev; + + usb_dev = (struct pios_usb_dev *)pvPortMalloc(sizeof(*usb_dev)); + if (!usb_dev) return(NULL); + + usb_dev->magic = PIOS_USB_DEV_MAGIC; + return(usb_dev); +} +#else +static struct pios_usb_dev pios_usb_devs[PIOS_USB_MAX_DEVS]; +static uint8_t pios_usb_num_devs; +static struct pios_usb_dev * PIOS_USB_alloc(void) +{ + struct pios_usb_dev * usb_dev; + + if (pios_usb_num_devs >= PIOS_USB_MAX_DEVS) { + return (NULL); + } + + usb_dev = &pios_usb_devs[pios_usb_num_devs++]; + usb_dev->magic = PIOS_USB_DEV_MAGIC; + + return (usb_dev); +} +#endif + + +/** + * Bind configuration to USB BSP layer + * \return < 0 if initialisation failed + */ +static uint32_t pios_usb_id; +int32_t PIOS_USB_Init(uint32_t * usb_id, const struct pios_usb_cfg * cfg) +{ + PIOS_Assert(usb_id); + PIOS_Assert(cfg); + + struct pios_usb_dev * usb_dev; + + usb_dev = (struct pios_usb_dev *) PIOS_USB_alloc(); + if (!usb_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + usb_dev->cfg = cfg; + + /* + * This is a horrible hack to make this available to + * the interrupt callbacks. This should go away ASAP. + */ + pios_usb_id = (uint32_t) usb_dev; + + *usb_id = (uint32_t) usb_dev; + + return 0; /* No error */ + +out_fail: + return(-1); +} + +/** + * This function is called by the USB driver on cable connection/disconnection + * \param[in] connected connection status (1 if connected) + * \return < 0 on errors + * \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions + */ +int32_t PIOS_USB_ChangeConnectionState(bool connected) +{ + // In all cases: re-initialise USB HID driver + if (connected) { + transfer_possible = 1; + + //TODO: Check SetEPRxValid(ENDP1); + +#if defined(USB_LED_ON) + USB_LED_ON; // turn the USB led on +#endif + } else { + // Cable disconnected: disable transfers + transfer_possible = 0; + +#if defined(USB_LED_OFF) + USB_LED_OFF; // turn the USB led off +#endif + } + + return 0; +} + +/** + * This function returns the connection status of the USB interface + * \return 1: interface available + * \return 0: interface not available + */ +uint32_t usb_found; +bool PIOS_USB_CheckAvailable(uint8_t id) +{ + struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_id; + + if(!PIOS_USB_validate(usb_dev)) + return false; + + usb_found = (usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin); + return usb_found; + return usb_found != 0 && transfer_possible ? 1 : 0; +} + +/* + * + * Provide STM32 USB OTG BSP layer API + * + */ + +#include "usb_bsp.h" + +void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev) +{ + struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_id; + + bool valid = PIOS_USB_validate(usb_dev); + PIOS_Assert(valid); + +#define FORCE_DISABLE_USB_IRQ 1 +#if FORCE_DISABLE_USB_IRQ + /* Make sure we disable the USB interrupt since it may be left on by bootloader */ + NVIC_InitTypeDef NVIC_InitStructure; + NVIC_InitStructure = usb_dev->cfg->irq.init; + NVIC_InitStructure.NVIC_IRQChannelCmd = DISABLE; + NVIC_Init(&NVIC_InitStructure); +#endif + + /* Configure USB D-/D+ (DM/DP) pins */ + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + GPIO_Init(GPIOA, &GPIO_InitStructure); + + GPIO_PinAFConfig(GPIOA, GPIO_PinSource11, GPIO_AF_OTG1_FS); + GPIO_PinAFConfig(GPIOA, GPIO_PinSource12, GPIO_AF_OTG1_FS); + + /* Configure VBUS sense pin */ + GPIO_Init(usb_dev->cfg->vsense.gpio, &usb_dev->cfg->vsense.init); + + /* Enable USB OTG Clock */ + RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, ENABLE); +} + +void USB_OTG_BSP_EnableInterrupt(USB_OTG_CORE_HANDLE *pdev) +{ + struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_id; + + bool valid = PIOS_USB_validate(usb_dev); + PIOS_Assert(valid); + + NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1); + + NVIC_Init(&usb_dev->cfg->irq.init); +} + +#ifdef USE_HOST_MODE +void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev, uint8_t state) +{ + +} + +void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev) +{ + +} +#endif /* USE_HOST_MODE */ + +void USB_OTG_BSP_TimeInit ( void ) +{ + +} + +void USB_OTG_BSP_uDelay (const uint32_t usec) +{ + uint32_t count = 0; + const uint32_t utime = (120 * usec / 7); + do { + if (++count > utime) { + return ; + } + } + while (1); +} + +void USB_OTG_BSP_mDelay (const uint32_t msec) +{ + USB_OTG_BSP_uDelay(msec * 1000); +} + +void USB_OTG_BSP_TimerIRQ (void) +{ + +} + +#endif /* PIOS_INCLUDE_USB */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F4xx/pios_usb_cdc.c b/flight/PiOS/STM32F4xx/pios_usb_cdc.c new file mode 100644 index 000000000..cb468b6d1 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_usb_cdc.c @@ -0,0 +1,400 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_COM USB COM Functions + * @brief PIOS USB COM implementation for CDC interfaces + * @notes This implements a CDC Serial Port + * @{ + * + * @file pios_usb_com_cdc.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief USB COM functions (STM32 dependent code) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_USB_CDC) + +#include "pios_usb.h" +#include "pios_usb_cdc_priv.h" +#include "pios_usb_board_data.h" /* PIOS_BOARD_*_DATA_LENGTH */ + +static void PIOS_USB_CDC_RegisterTxCallback(uint32_t usbcdc_id, pios_com_callback tx_out_cb, uint32_t context); +static void PIOS_USB_CDC_RegisterRxCallback(uint32_t usbcdc_id, pios_com_callback rx_in_cb, uint32_t context); +static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, uint16_t tx_bytes_avail); +static void PIOS_USB_CDC_RxStart(uint32_t usbcdc_id, uint16_t rx_bytes_avail); + +const struct pios_com_driver pios_usb_cdc_com_driver = { + .tx_start = PIOS_USB_CDC_TxStart, + .rx_start = PIOS_USB_CDC_RxStart, + .bind_tx_cb = PIOS_USB_CDC_RegisterTxCallback, + .bind_rx_cb = PIOS_USB_CDC_RegisterRxCallback, +}; + +enum pios_usb_cdc_dev_magic { + PIOS_USB_CDC_DEV_MAGIC = 0xAABBCCDD, +}; + +struct pios_usb_cdc_dev { + enum pios_usb_cdc_dev_magic magic; + const struct pios_usb_cdc_cfg * cfg; + + uint32_t lower_id; + + pios_com_callback rx_in_cb; + uint32_t rx_in_context; + pios_com_callback tx_out_cb; + uint32_t tx_out_context; + + uint8_t rx_packet_buffer[PIOS_USB_BOARD_CDC_DATA_LENGTH]; + uint8_t tx_packet_buffer[PIOS_USB_BOARD_CDC_DATA_LENGTH]; + + uint32_t rx_dropped; + uint32_t rx_oversize; +}; + +static bool PIOS_USB_CDC_validate(struct pios_usb_cdc_dev * usb_cdc_dev) +{ + return (usb_cdc_dev && (usb_cdc_dev->magic == PIOS_USB_CDC_DEV_MAGIC)); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_usb_cdc_dev * PIOS_USB_CDC_alloc(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev; + + usb_cdc_dev = (struct pios_usb_cdc_dev *)pvPortMalloc(sizeof(*usb_cdc_dev)); + if (!usb_cdc_dev) return(NULL); + + usb_cdc_dev->magic = PIOS_USB_CDC_DEV_MAGIC; + return(usb_cdc_dev); +} +#else +static struct pios_usb_cdc_dev pios_usb_cdc_devs[PIOS_USB_CDC_MAX_DEVS]; +static uint8_t pios_usb_cdc_num_devs; +static struct pios_usb_cdc_dev * PIOS_USB_CDC_alloc(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev; + + if (pios_usb_cdc_num_devs >= PIOS_USB_CDC_MAX_DEVS) { + return (NULL); + } + + usb_cdc_dev = &pios_usb_cdc_devs[pios_usb_cdc_num_devs++]; + usb_cdc_dev->magic = PIOS_USB_CDC_DEV_MAGIC; + + return (usb_cdc_dev); +} +#endif + +static void PIOS_USB_CDC_DATA_EP_IN_Callback(void); +static void PIOS_USB_CDC_DATA_EP_OUT_Callback(void); +static void PIOS_USB_CDC_CTRL_EP_IN_Callback(void); + +static uint32_t pios_usb_cdc_id; + +/* Need a better way to pull these in */ +extern void (*pEpInt_IN[7])(void); +extern void (*pEpInt_OUT[7])(void); + +int32_t PIOS_USB_CDC_Init(uint32_t * usbcdc_id, const struct pios_usb_cdc_cfg * cfg, uint32_t lower_id) +{ + PIOS_Assert(usbcdc_id); + PIOS_Assert(cfg); + + struct pios_usb_cdc_dev * usb_cdc_dev; + + usb_cdc_dev = (struct pios_usb_cdc_dev *) PIOS_USB_CDC_alloc(); + if (!usb_cdc_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + usb_cdc_dev->cfg = cfg; + usb_cdc_dev->lower_id = lower_id; + + pios_usb_cdc_id = (uint32_t) usb_cdc_dev; + + /* Bind lower level callbacks into the USB infrastructure */ + pEpInt_OUT[cfg->ctrl_tx_ep - 1] = PIOS_USB_CDC_CTRL_EP_IN_Callback; + pEpInt_IN[cfg->data_tx_ep - 1] = PIOS_USB_CDC_DATA_EP_IN_Callback; + pEpInt_OUT[cfg->data_rx_ep - 1] = PIOS_USB_CDC_DATA_EP_OUT_Callback; + + *usbcdc_id = (uint32_t) usb_cdc_dev; + + return 0; + +out_fail: + return -1; +} + + + +static void PIOS_USB_CDC_RegisterRxCallback(uint32_t usbcdc_id, pios_com_callback rx_in_cb, uint32_t context) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + usb_cdc_dev->rx_in_context = context; + usb_cdc_dev->rx_in_cb = rx_in_cb; +} + +static void PIOS_USB_CDC_RegisterTxCallback(uint32_t usbcdc_id, pios_com_callback tx_out_cb, uint32_t context) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + usb_cdc_dev->tx_out_context = context; + usb_cdc_dev->tx_out_cb = tx_out_cb; +} + +static void PIOS_USB_CDC_RxStart(uint32_t usbcdc_id, uint16_t rx_bytes_avail) { + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + if (!PIOS_USB_CheckAvailable(usb_cdc_dev->lower_id)) { + return; + } + + // If endpoint was stalled and there is now space make it valid + PIOS_IRQ_Disable(); + if ((GetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep) != EP_RX_VALID) && + (rx_bytes_avail >= sizeof(usb_cdc_dev->rx_packet_buffer))) { + SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_VALID); + } + PIOS_IRQ_Enable(); +} + +static void PIOS_USB_CDC_SendData(struct pios_usb_cdc_dev * usb_cdc_dev) +{ + uint16_t bytes_to_tx; + + if (!usb_cdc_dev->tx_out_cb) { + return; + } + + bool need_yield = false; + bytes_to_tx = (usb_cdc_dev->tx_out_cb)(usb_cdc_dev->tx_out_context, + usb_cdc_dev->tx_packet_buffer, + sizeof(usb_cdc_dev->tx_packet_buffer), + NULL, + &need_yield); + if (bytes_to_tx == 0) { + return; + } + + UserToPMABufferCopy(usb_cdc_dev->tx_packet_buffer, + GetEPTxAddr(usb_cdc_dev->cfg->data_tx_ep), + bytes_to_tx); + SetEPTxCount(usb_cdc_dev->cfg->data_tx_ep, bytes_to_tx); + SetEPTxValid(usb_cdc_dev->cfg->data_tx_ep); + +#if defined(PIOS_INCLUDE_FREERTOS) + if (need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ +} + +static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, uint16_t tx_bytes_avail) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + if (!PIOS_USB_CheckAvailable(usb_cdc_dev->lower_id)) { + return; + } + + if (GetEPTxStatus(usb_cdc_dev->cfg->data_tx_ep) == EP_TX_VALID) { + /* Endpoint is already transmitting */ + return; + } + + PIOS_USB_CDC_SendData(usb_cdc_dev); +} + +static void PIOS_USB_CDC_DATA_EP_IN_Callback(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + PIOS_USB_CDC_SendData(usb_cdc_dev); +} + +static void PIOS_USB_CDC_DATA_EP_OUT_Callback(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + uint32_t DataLength; + + /* Get the number of received data on the selected Endpoint */ + DataLength = GetEPRxCount(usb_cdc_dev->cfg->data_rx_ep); + if (DataLength > sizeof(usb_cdc_dev->rx_packet_buffer)) { + usb_cdc_dev->rx_oversize++; + DataLength = sizeof(usb_cdc_dev->rx_packet_buffer); + } + + /* Use the memory interface function to read from the selected endpoint */ + PMAToUserBufferCopy((uint8_t *) usb_cdc_dev->rx_packet_buffer, + GetEPRxAddr(usb_cdc_dev->cfg->data_rx_ep), + DataLength); + + if (!usb_cdc_dev->rx_in_cb) { + /* No Rx call back registered, disable the receiver */ + SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_NAK); + return; + } + + uint16_t headroom; + bool need_yield = false; + uint16_t rc; + rc = (usb_cdc_dev->rx_in_cb)(usb_cdc_dev->rx_in_context, + usb_cdc_dev->rx_packet_buffer, + DataLength, + &headroom, + &need_yield); + + if (rc < DataLength) { + /* Lost bytes on rx */ + usb_cdc_dev->rx_dropped += (DataLength - rc); + } + + if (headroom >= sizeof(usb_cdc_dev->rx_packet_buffer)) { + /* We have room for a maximum length message */ + SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_VALID); + } else { + /* Not enough room left for a message, apply backpressure */ + SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_NAK); + } + +#if defined(PIOS_INCLUDE_FREERTOS) + if (need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ +} + +RESULT PIOS_USB_CDC_SetControlLineState(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + static uint16_t control_line_state; + + uint8_t wValue0 = pInformation->USBwValue0; + uint8_t wValue1 = pInformation->USBwValue1; + + control_line_state = wValue1 << 8 | wValue0; + + return USB_SUCCESS; +} + +static struct usb_cdc_line_coding line_coding = { + .dwDTERate = htousbl(57600), + .bCharFormat = USB_CDC_LINE_CODING_STOP_1, + .bParityType = USB_CDC_LINE_CODING_PARITY_NONE, + .bDataBits = 8, +}; + +RESULT PIOS_USB_CDC_SetLineCoding(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + return USB_SUCCESS; +} + +const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + if (Length == 0) { + pInformation->Ctrl_Info.Usb_wLength = sizeof(line_coding); + return NULL; + } else { + return ((uint8_t *) &line_coding); + } +} + +struct usb_cdc_serial_state_report uart_state = { + .bmRequestType = 0xA1, + .bNotification = USB_CDC_NOTIFICATION_SERIAL_STATE, + .wValue = 0, + .wIndex = htousbs(1), + .wLength = htousbs(2), + .bmUartState = htousbs(0), +}; + +static void PIOS_USB_CDC_CTRL_EP_IN_Callback(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + /* Give back UART State Bitmap */ + /* UART State Bitmap + * 15-7: reserved + * 6: bOverRun overrun error + * 5: bParity parity error + * 4: bFraming framing error + * 3: bRingSignal RI + * 2: bBreak break reception + * 1: bTxCarrier DSR + * 0: bRxCarrier DCD + */ + uart_state.bmUartState = htousbs(0x0003); + + UserToPMABufferCopy((uint8_t *) &uart_state, + GetEPTxAddr(usb_cdc_dev->cfg->data_tx_ep), + sizeof(uart_state)); + SetEPTxCount(usb_cdc_dev->cfg->data_tx_ep, PIOS_USB_BOARD_CDC_MGMT_LENGTH); + SetEPTxValid(usb_cdc_dev->cfg->data_tx_ep); +} + +#endif /* PIOS_INCLUDE_USB_CDC */ diff --git a/flight/PiOS/STM32F4xx/pios_usb_hid.c b/flight/PiOS/STM32F4xx/pios_usb_hid.c new file mode 100644 index 000000000..eb03debec --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_usb_hid.c @@ -0,0 +1,527 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_HID USB COM Functions + * @brief PIOS USB COM implementation for HID interfaces + * @notes This implements serial emulation over HID reports + * @{ + * + * @file pios_usb_hid.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief USB COM functions (STM32 dependent code) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_USB_HID) + +#include "pios_usb.h" +#include "pios_usb_hid_priv.h" +#include "pios_usb_board_data.h" /* PIOS_BOARD_*_DATA_LENGTH */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ + +#define MIN(x,y) (((x) < (y)) ? (x) : (y)) +#define MAX(x,y) (((x) > (y)) ? (x) : (y)) + +static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbhid_id, pios_com_callback tx_out_cb, uint32_t context); +static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbhid_id, pios_com_callback rx_in_cb, uint32_t context); +static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, uint16_t tx_bytes_avail); +static void PIOS_USB_HID_RxStart(uint32_t usbhid_id, uint16_t rx_bytes_avail); + +const struct pios_com_driver pios_usb_hid_com_driver = { + .tx_start = PIOS_USB_HID_TxStart, + .rx_start = PIOS_USB_HID_RxStart, + .bind_tx_cb = PIOS_USB_HID_RegisterTxCallback, + .bind_rx_cb = PIOS_USB_HID_RegisterRxCallback, +}; + +enum pios_usb_hid_dev_magic { + PIOS_USB_HID_DEV_MAGIC = 0xAA00BB00, +}; + +struct pios_usb_hid_dev { + enum pios_usb_hid_dev_magic magic; + const struct pios_usb_hid_cfg * cfg; + + uint32_t lower_id; + + pios_com_callback rx_in_cb; + uint32_t rx_in_context; + pios_com_callback tx_out_cb; + uint32_t tx_out_context; + + bool usb_if_enabled; + + uint8_t rx_packet_buffer[PIOS_USB_BOARD_HID_DATA_LENGTH]; + bool rx_active; + + uint8_t tx_packet_buffer[PIOS_USB_BOARD_HID_DATA_LENGTH]; + bool tx_active; + + uint32_t rx_dropped; + uint32_t rx_oversize; +}; + +static bool PIOS_USB_HID_validate(struct pios_usb_hid_dev * usb_hid_dev) +{ + return (usb_hid_dev && (usb_hid_dev->magic == PIOS_USB_HID_DEV_MAGIC)); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_usb_hid_dev * PIOS_USB_HID_alloc(void) +{ + struct pios_usb_hid_dev * usb_hid_dev; + + usb_hid_dev = (struct pios_usb_hid_dev *)pvPortMalloc(sizeof(*usb_hid_dev)); + if (!usb_hid_dev) return(NULL); + + usb_hid_dev->magic = PIOS_USB_HID_DEV_MAGIC; + return(usb_hid_dev); +} +#else +static struct pios_usb_hid_dev pios_usb_hid_devs[PIOS_USB_HID_MAX_DEVS]; +static uint8_t pios_usb_hid_num_devs; +static struct pios_usb_hid_dev * PIOS_USB_HID_alloc(void) +{ + struct pios_usb_hid_dev * usb_hid_dev; + + if (pios_usb_hid_num_devs >= PIOS_USB_HID_MAX_DEVS) { + return (NULL); + } + + usb_hid_dev = &pios_usb_hid_devs[pios_usb_hid_num_devs++]; + usb_hid_dev->magic = PIOS_USB_HID_DEV_MAGIC; + + return (usb_hid_dev); +} +#endif + +static void PIOS_USB_HID_IF_Init(uint32_t usb_hid_id); +static void PIOS_USB_HID_IF_DeInit(uint32_t usb_hid_id); +static bool PIOS_USB_HID_IF_Setup(uint32_t usb_hid_id, struct usb_setup_request *req); +static void PIOS_USB_HID_IF_CtrlDataOut(uint32_t usb_hid_id, struct usb_setup_request *req); + +static struct pios_usb_ifops usb_hid_ifops = { + .init = PIOS_USB_HID_IF_Init, + .deinit = PIOS_USB_HID_IF_DeInit, + .setup = PIOS_USB_HID_IF_Setup, + .ctrl_data_out = PIOS_USB_HID_IF_CtrlDataOut, +}; + +static bool PIOS_USB_HID_EP_IN_Callback(uint32_t usb_hid_id, uint8_t epnum, uint16_t len); +static bool PIOS_USB_HID_EP_OUT_Callback(uint32_t usb_hid_id, uint8_t epnum, uint16_t len); + +int32_t PIOS_USB_HID_Init(uint32_t * usbhid_id, const struct pios_usb_hid_cfg * cfg, uint32_t lower_id) +{ + PIOS_Assert(usbhid_id); + PIOS_Assert(cfg); + + struct pios_usb_hid_dev * usb_hid_dev; + + usb_hid_dev = (struct pios_usb_hid_dev *) PIOS_USB_HID_alloc(); + if (!usb_hid_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + usb_hid_dev->cfg = cfg; + usb_hid_dev->lower_id = lower_id; + + /* Rx and Tx are not active yet */ + usb_hid_dev->rx_active = false; + usb_hid_dev->tx_active = false; + + /* Register class specific interface callbacks with the USBHOOK layer */ + usb_hid_dev->usb_if_enabled = false; + PIOS_USBHOOK_RegisterIfOps(cfg->data_if, &usb_hid_ifops, (uint32_t) usb_hid_dev); + + *usbhid_id = (uint32_t) usb_hid_dev; + + return 0; + +out_fail: + return -1; +} + + +static struct pios_usbhook_descriptor hid_desc; + +void PIOS_USB_HID_RegisterHidDescriptor(const uint8_t * desc, uint16_t length) +{ + hid_desc.descriptor = desc; + hid_desc.length = length; +} + +static struct pios_usbhook_descriptor hid_report_desc; + +void PIOS_USB_HID_RegisterHidReport(const uint8_t * desc, uint16_t length) +{ + hid_report_desc.descriptor = desc; + hid_report_desc.length = length; +} + +static bool PIOS_USB_HID_SendReport(struct pios_usb_hid_dev * usb_hid_dev) +{ + uint16_t bytes_to_tx; + + if (!usb_hid_dev->tx_out_cb) { + return false; + } + + bool need_yield = false; +#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + bytes_to_tx = (usb_hid_dev->tx_out_cb)(usb_hid_dev->tx_out_context, + &usb_hid_dev->tx_packet_buffer[1], + sizeof(usb_hid_dev->tx_packet_buffer)-1, + NULL, + &need_yield); +#else + bytes_to_tx = (usb_hid_dev->tx_out_cb)(usb_hid_dev->tx_out_context, + &usb_hid_dev->tx_packet_buffer[2], + sizeof(usb_hid_dev->tx_packet_buffer)-2, + NULL, + &need_yield); +#endif + if (bytes_to_tx == 0) { + return false; + } + + /* + * Mark this endpoint as being tx active _before_ actually transmitting + * to make sure we don't race with the Tx completion interrupt + */ + usb_hid_dev->tx_active = true; + + /* Always set type as report ID */ + usb_hid_dev->tx_packet_buffer[0] = 1; + +#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + PIOS_USBHOOK_EndpointTx(usb_hid_dev->cfg->data_tx_ep, + usb_hid_dev->tx_packet_buffer, + sizeof(usb_hid_dev->tx_packet_buffer)); +#else + usb_hid_dev->tx_packet_buffer[1] = bytes_to_tx; + PIOS_USBHOOK_EndpointTx(usb_hid_dev->cfg->data_tx_ep, + usb_hid_dev->tx_packet_buffer, + sizeof(usb_hid_dev->tx_packet_buffer)); +#endif + +#if defined(PIOS_INCLUDE_FREERTOS) + if (need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ + + return true; +} + +static void PIOS_USB_HID_RxStart(uint32_t usbhid_id, uint16_t rx_bytes_avail) { + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id; + + bool valid = PIOS_USB_HID_validate(usb_hid_dev); + PIOS_Assert(valid); + + /* Make sure this USB interface has been initialized */ + if (!usb_hid_dev->usb_if_enabled) { + return; + } + + if (!PIOS_USB_CheckAvailable(usb_hid_dev->lower_id)) { + return; + } + + // If endpoint was stalled and there is now space make it valid +#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 1; +#else + uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 2; +#endif + + if (!usb_hid_dev->rx_active && (rx_bytes_avail >= max_payload_length)) { + PIOS_USBHOOK_EndpointRx(usb_hid_dev->cfg->data_rx_ep, + usb_hid_dev->rx_packet_buffer, + sizeof(usb_hid_dev->rx_packet_buffer)); + usb_hid_dev->rx_active = true; + } +} + +static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, uint16_t tx_bytes_avail) +{ + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id; + + bool valid = PIOS_USB_HID_validate(usb_hid_dev); + PIOS_Assert(valid); + + /* Make sure this USB interface has been initialized */ + if (!usb_hid_dev->usb_if_enabled) { + return; + } + + if (!PIOS_USB_CheckAvailable(usb_hid_dev->lower_id)) { + return; + } + + if (!usb_hid_dev->tx_active) { + /* Transmitter is not currently active, send a report */ + PIOS_USB_HID_SendReport(usb_hid_dev); + } +} + +static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbhid_id, pios_com_callback rx_in_cb, uint32_t context) +{ + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id; + + bool valid = PIOS_USB_HID_validate(usb_hid_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + usb_hid_dev->rx_in_context = context; + usb_hid_dev->rx_in_cb = rx_in_cb; +} + +static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbhid_id, pios_com_callback tx_out_cb, uint32_t context) +{ + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id; + + bool valid = PIOS_USB_HID_validate(usb_hid_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + usb_hid_dev->tx_out_context = context; + usb_hid_dev->tx_out_cb = tx_out_cb; +} + +static void PIOS_USB_HID_IF_Init(uint32_t usb_hid_id) +{ + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usb_hid_id; + + if (!PIOS_USB_HID_validate(usb_hid_dev)) { + return; + } + + /* Register endpoint specific callbacks with the USBHOOK layer */ + PIOS_USBHOOK_RegisterEpInCallback(usb_hid_dev->cfg->data_tx_ep, + sizeof(usb_hid_dev->tx_packet_buffer), + PIOS_USB_HID_EP_IN_Callback, + (uint32_t) usb_hid_dev); + PIOS_USBHOOK_RegisterEpOutCallback(usb_hid_dev->cfg->data_rx_ep, + sizeof(usb_hid_dev->rx_packet_buffer), + PIOS_USB_HID_EP_OUT_Callback, + (uint32_t) usb_hid_dev); + usb_hid_dev->usb_if_enabled = true; + +} + +static void PIOS_USB_HID_IF_DeInit(uint32_t usb_hid_id) +{ + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usb_hid_id; + + if (!PIOS_USB_HID_validate(usb_hid_dev)) { + return; + } + + /* DeRegister endpoint specific callbacks with the USBHOOK layer */ + usb_hid_dev->usb_if_enabled = false; + PIOS_USBHOOK_DeRegisterEpInCallback(usb_hid_dev->cfg->data_tx_ep); + PIOS_USBHOOK_DeRegisterEpOutCallback(usb_hid_dev->cfg->data_rx_ep); +} + +static uint8_t hid_protocol; +static uint8_t hid_altset; + +static bool PIOS_USB_HID_IF_Setup(uint32_t usb_hid_id, struct usb_setup_request *req) +{ + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usb_hid_id; + + if (!PIOS_USB_HID_validate(usb_hid_dev)) { + return false; + } + + /* Make sure this is a request for an interface we know about */ + uint8_t ifnum = req->wIndex & 0xFF; + if (ifnum != usb_hid_dev->cfg->data_if) { + return (false); + } + + switch (req->bmRequestType & (USB_REQ_TYPE_MASK | USB_REQ_RECIPIENT_MASK)) { + case (USB_REQ_TYPE_STANDARD | USB_REQ_RECIPIENT_INTERFACE): + switch (req->bRequest) { + case USB_REQ_GET_DESCRIPTOR: + switch (req->wValue >> 8) { + case USB_DESC_TYPE_REPORT: + PIOS_USBHOOK_CtrlTx(hid_report_desc.descriptor, + MIN(hid_report_desc.length, req->wLength)); + break; + case USB_DESC_TYPE_HID: + PIOS_USBHOOK_CtrlTx(hid_desc.descriptor, + MIN(hid_desc.length, req->wLength)); + break; + default: + /* Unhandled descriptor request */ + return false; + break; + } + break; + case USB_REQ_GET_INTERFACE: + PIOS_USBHOOK_CtrlTx(&hid_altset, 1); + break; + case USB_REQ_SET_INTERFACE: + hid_altset = (uint8_t)(req->wValue); + break; + default: + /* Unhandled standard request */ + return false; + break; + } + break; + case (USB_REQ_TYPE_CLASS | USB_REQ_RECIPIENT_INTERFACE): + switch (req->bRequest) { + case USB_HID_REQ_SET_PROTOCOL: + hid_protocol = (uint8_t)(req->wValue); + break; + case USB_HID_REQ_GET_PROTOCOL: + PIOS_USBHOOK_CtrlTx(&hid_protocol, 1); + break; + case USB_HID_REQ_GET_REPORT: + { + /* Give back a dummy input report */ + uint8_t dummy_report[2] = { + [0] = req->wValue >> 8, /* Report ID */ + [1] = 0x00, + }; + PIOS_USBHOOK_CtrlTx(dummy_report, sizeof(dummy_report)); + } + break; + default: + /* Unhandled class request */ + return false; + break; + } + break; + default: + /* Unhandled request */ + return false; + } + + return true; +} + +static void PIOS_USB_HID_IF_CtrlDataOut(uint32_t usb_hid_id, struct usb_setup_request *req) +{ + /* HID devices don't have any OUT data stages on the control endpoint */ + PIOS_Assert(0); +} + +/** + * @brief Callback used to indicate a transmission from device INto host completed + * Checks if any data remains, pads it into HID packet and sends. + */ +static bool PIOS_USB_HID_EP_IN_Callback(uint32_t usb_hid_id, uint8_t epnum, uint16_t len) +{ + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usb_hid_id; + + if (!PIOS_USB_HID_validate(usb_hid_dev)) { + return false; + } + + if (PIOS_USB_CheckAvailable(usb_hid_dev->lower_id) && + PIOS_USB_HID_SendReport(usb_hid_dev)) { + /* More data has been queued, leave tx_active set to true */ + return true; + } else { + /* Nothing new sent, transmitter is now inactive */ + usb_hid_dev->tx_active = false; + return false; + } +} + +/** + * EP1 OUT Callback Routine + */ +static bool PIOS_USB_HID_EP_OUT_Callback(uint32_t usb_hid_id, uint8_t epnum, uint16_t len) +{ + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usb_hid_id; + + if (!PIOS_USB_HID_validate(usb_hid_dev)) { + return false; + } + + if (len > sizeof(usb_hid_dev->rx_packet_buffer)) { + len = sizeof(usb_hid_dev->rx_packet_buffer); + } + + if (!usb_hid_dev->rx_in_cb) { + /* No Rx call back registered, disable the receiver */ + usb_hid_dev->rx_active = false; + return false; + } + + /* The first byte is report ID (not checked), the second byte is the valid data length */ + uint16_t headroom; + bool need_yield = false; +#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + (usb_hid_dev->rx_in_cb)(usb_hid_dev->rx_in_context, + &usb_hid_dev->rx_packet_buffer[1], + len-1, + &headroom, + &need_yield); +#else + (usb_hid_dev->rx_in_cb)(usb_hid_dev->rx_in_context, + &usb_hid_dev->rx_packet_buffer[2], + usb_hid_dev->rx_packet_buffer[1], + &headroom, + &need_yield); +#endif + +#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 1; +#else + uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 2; +#endif + + bool rc; + if (headroom >= max_payload_length) { + /* We have room for a maximum length message */ + PIOS_USBHOOK_EndpointRx(usb_hid_dev->cfg->data_rx_ep, + usb_hid_dev->rx_packet_buffer, + sizeof(usb_hid_dev->rx_packet_buffer)); + rc = true; + } else { + /* Not enough room left for a message, apply backpressure */ + usb_hid_dev->rx_active = false; + rc = false; + } + +#if defined(PIOS_INCLUDE_FREERTOS) + if (need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ + + return rc; +} + +#endif /* PIOS_INCLUDE_USB_HID */ diff --git a/flight/PiOS/STM32F4xx/pios_usbhook.c b/flight/PiOS/STM32F4xx/pios_usbhook.c new file mode 100644 index 000000000..08653a74a --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_usbhook.c @@ -0,0 +1,472 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USBHOOK USB glue code + * @brief Glue between PiOS and STM32 libs + * @{ + * + * @file pios_usbhook.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Glue between PiOS and STM32 libs + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios.h" +#include "pios_usb.h" /* PIOS_USB_* */ +#include "pios_usbhook.h" +#include "pios_usb_defs.h" /* struct usb_* */ +#include "pios_usb_cdc_priv.h" /* PIOS_USB_CDC_* */ +#include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */ + + +/* STM32 USB Library Definitions */ +#include "usb_core.h" /* USBD_Class_cb_TypeDef */ +#include "usbd_core.h" /* USBD_Init USBD_OK*/ +#include "usbd_ioreq.h" /* USBD_CtlPrepareRx, USBD_CtlSendData */ +#include "usbd_req.h" /* USBD_CtlError */ +#include "usb_dcd_int.h" /* USBD_OTG_ISR_Handler */ + +/* + * External API + */ +static struct pios_usbhook_descriptor Device_Descriptor; + +void PIOS_USBHOOK_RegisterDevice(const uint8_t * desc, uint16_t length) +{ + Device_Descriptor.descriptor = desc; + Device_Descriptor.length = length; +} + +static struct pios_usbhook_descriptor String_Descriptor[4]; + +void PIOS_USBHOOK_RegisterString(enum usb_string_desc string_id, const uint8_t * desc, uint16_t desc_size) +{ + if (string_id < NELEMENTS(String_Descriptor)) { + String_Descriptor[string_id].descriptor = desc; + String_Descriptor[string_id].length = desc_size; + } +} + +static struct pios_usbhook_descriptor Config_Descriptor; + +void PIOS_USBHOOK_RegisterConfig(uint8_t config_id, const uint8_t * desc, uint16_t desc_size) +{ + Config_Descriptor.descriptor = desc; + Config_Descriptor.length = desc_size; +} + +static USB_OTG_CORE_HANDLE pios_usb_otg_core_handle; +static USBD_Class_cb_TypeDef class_callbacks; +static USBD_DEVICE device_callbacks; +static USBD_Usr_cb_TypeDef user_callbacks; + +void PIOS_USBHOOK_Activate(void) +{ + USBD_Init(&pios_usb_otg_core_handle, + USB_OTG_FS_CORE_ID, + &device_callbacks, + &class_callbacks, + &user_callbacks); +} + +void PIOS_USBHOOK_Deactivate(void) +{ + DCD_DevDisconnect(&pios_usb_otg_core_handle); + USBD_DeInit(&pios_usb_otg_core_handle); + USB_OTG_StopDevice(&pios_usb_otg_core_handle); +} + +void OTG_FS_IRQHandler(void) +{ + if(!USBD_OTG_ISR_Handler(&pios_usb_otg_core_handle)) { + /* spurious interrupt, disable IRQ */ + + } +} + +struct usb_if_entry { + struct pios_usb_ifops *ifops; + uint32_t context; +}; +static struct usb_if_entry usb_if_table[3]; +void PIOS_USBHOOK_RegisterIfOps(uint8_t ifnum, struct pios_usb_ifops * ifops, uint32_t context) +{ + PIOS_Assert(ifnum < NELEMENTS(usb_if_table)); + PIOS_Assert(ifops); + + usb_if_table[ifnum].ifops = ifops; + usb_if_table[ifnum].context = context; +} + +struct usb_ep_entry { + pios_usbhook_epcb cb; + uint32_t context; + uint16_t max_len; +}; +static struct usb_ep_entry usb_epin_table[6]; +void PIOS_USBHOOK_RegisterEpInCallback(uint8_t epnum, uint16_t max_len, pios_usbhook_epcb cb, uint32_t context) +{ + PIOS_Assert(epnum < NELEMENTS(usb_epin_table)); + PIOS_Assert(cb); + + usb_epin_table[epnum].cb = cb; + usb_epin_table[epnum].context = context; + usb_epin_table[epnum].max_len = max_len; + + DCD_EP_Open(&pios_usb_otg_core_handle, + epnum | 0x80, + max_len, + USB_OTG_EP_INT); + /* + * FIXME do not hardcode endpoint type + */ +} + +extern void PIOS_USBHOOK_DeRegisterEpInCallback(uint8_t epnum) +{ + PIOS_Assert(epnum < NELEMENTS(usb_epin_table)); + + usb_epin_table[epnum].cb = NULL; + + DCD_EP_Close(&pios_usb_otg_core_handle, epnum | 0x80); +} + +static struct usb_ep_entry usb_epout_table[6]; +void PIOS_USBHOOK_RegisterEpOutCallback(uint8_t epnum, uint16_t max_len, pios_usbhook_epcb cb, uint32_t context) +{ + PIOS_Assert(epnum < NELEMENTS(usb_epout_table)); + PIOS_Assert(cb); + + usb_epout_table[epnum].cb = cb; + usb_epout_table[epnum].context = context; + usb_epout_table[epnum].max_len = max_len; + + DCD_EP_Open(&pios_usb_otg_core_handle, + epnum, + max_len, + USB_OTG_EP_INT); + /* + * FIXME do not hardcode endpoint type + */ +} + +extern void PIOS_USBHOOK_DeRegisterEpOutCallback(uint8_t epnum) +{ + PIOS_Assert(epnum < NELEMENTS(usb_epout_table)); + + usb_epout_table[epnum].cb = NULL; + + DCD_EP_Close(&pios_usb_otg_core_handle, epnum); +} + +void PIOS_USBHOOK_CtrlTx(const uint8_t *buf, uint16_t len) +{ + USBD_CtlSendData(&pios_usb_otg_core_handle, buf, len); +} + +void PIOS_USBHOOK_CtrlRx(uint8_t *buf, uint16_t len) +{ + USBD_CtlPrepareRx(&pios_usb_otg_core_handle, buf, len); +} + +void PIOS_USBHOOK_EndpointTx(uint8_t epnum, const uint8_t *buf, uint16_t len) +{ + if (pios_usb_otg_core_handle.dev.device_status == USB_OTG_CONFIGURED) { + DCD_EP_Tx(&pios_usb_otg_core_handle, epnum, buf, len); + } +} + +void PIOS_USBHOOK_EndpointRx(uint8_t epnum, uint8_t *buf, uint16_t len) +{ + DCD_EP_PrepareRx(&pios_usb_otg_core_handle, epnum, buf, len); +} + +/* + * Device level hooks into STM USB library + */ + +static const uint8_t * PIOS_USBHOOK_DEV_GetDeviceDescriptor(uint8_t speed, uint16_t *length) +{ + *length = Device_Descriptor.length; + return Device_Descriptor.descriptor; +} + +static const uint8_t * PIOS_USBHOOK_DEV_GetLangIDStrDescriptor(uint8_t speed, uint16_t *length) +{ + *length = String_Descriptor[USB_STRING_DESC_LANG].length; + return String_Descriptor[USB_STRING_DESC_LANG].descriptor; +} + +static const uint8_t * PIOS_USBHOOK_DEV_GetManufacturerStrDescriptor(uint8_t speed, uint16_t *length) +{ + *length = String_Descriptor[USB_STRING_DESC_VENDOR].length; + return String_Descriptor[USB_STRING_DESC_VENDOR].descriptor; +} + +static const uint8_t * PIOS_USBHOOK_DEV_GetProductStrDescriptor(uint8_t speed, uint16_t *length) +{ + *length = String_Descriptor[USB_STRING_DESC_PRODUCT].length; + return String_Descriptor[USB_STRING_DESC_PRODUCT].descriptor; +} + +static const uint8_t * PIOS_USBHOOK_DEV_GetSerialStrDescriptor(uint8_t speed, uint16_t *length) +{ + *length = String_Descriptor[USB_STRING_DESC_SERIAL].length; + return String_Descriptor[USB_STRING_DESC_SERIAL].descriptor; +} + +static const uint8_t * PIOS_USBHOOK_DEV_GetConfigurationStrDescriptor(uint8_t speed, uint16_t *length) +{ + return NULL; +} + +static const uint8_t * PIOS_USBHOOK_DEV_GetInterfaceStrDescriptor(uint8_t speed, uint16_t *length) +{ + return NULL; +} + +static USBD_DEVICE device_callbacks = { + .GetDeviceDescriptor = PIOS_USBHOOK_DEV_GetDeviceDescriptor, + .GetLangIDStrDescriptor = PIOS_USBHOOK_DEV_GetLangIDStrDescriptor, + .GetManufacturerStrDescriptor = PIOS_USBHOOK_DEV_GetManufacturerStrDescriptor, + .GetProductStrDescriptor = PIOS_USBHOOK_DEV_GetProductStrDescriptor, + .GetSerialStrDescriptor = PIOS_USBHOOK_DEV_GetSerialStrDescriptor, + .GetConfigurationStrDescriptor = PIOS_USBHOOK_DEV_GetConfigurationStrDescriptor, + .GetInterfaceStrDescriptor = PIOS_USBHOOK_DEV_GetInterfaceStrDescriptor, +}; + +static void PIOS_USBHOOK_USR_Init(void) +{ + PIOS_USB_ChangeConnectionState(false); + +#if 1 + /* Force a physical disconnect/reconnect */ + DCD_DevDisconnect(&pios_usb_otg_core_handle); + DCD_DevConnect(&pios_usb_otg_core_handle); +#endif +} + +static void PIOS_USBHOOK_USR_DeviceReset(uint8_t speed) +{ + PIOS_USB_ChangeConnectionState(false); +} + +static void PIOS_USBHOOK_USR_DeviceConfigured(void) +{ + PIOS_USB_ChangeConnectionState(true); +} + +static void PIOS_USBHOOK_USR_DeviceSuspended(void) +{ + /* Unhandled */ +} + +static void PIOS_USBHOOK_USR_DeviceResumed(void) +{ + /* Unhandled */ +} + +static void PIOS_USBHOOK_USR_DeviceConnected(void) +{ + /* NOP */ +} + +static void PIOS_USBHOOK_USR_DeviceDisconnected(void) +{ + PIOS_USB_ChangeConnectionState(false); +} + +static USBD_Usr_cb_TypeDef user_callbacks = { + .Init = PIOS_USBHOOK_USR_Init, + .DeviceReset = PIOS_USBHOOK_USR_DeviceReset, + .DeviceConfigured = PIOS_USBHOOK_USR_DeviceConfigured, + .DeviceSuspended = PIOS_USBHOOK_USR_DeviceSuspended, + .DeviceResumed = PIOS_USBHOOK_USR_DeviceResumed, + .DeviceConnected = PIOS_USBHOOK_USR_DeviceConnected, + .DeviceDisconnected = PIOS_USBHOOK_USR_DeviceDisconnected, +}; + +static uint8_t PIOS_USBHOOK_CLASS_Init(void *pdev, uint8_t cfgidx) +{ + /* Call all of the registered init callbacks */ + for (uint8_t i = 0; i < NELEMENTS(usb_if_table); i++) { + struct usb_if_entry * usb_if = &(usb_if_table[i]); + if (usb_if->ifops && usb_if->ifops->init) { + usb_if->ifops->init(usb_if->context); + } + } + return USBD_OK; +} + +static uint8_t PIOS_USBHOOK_CLASS_DeInit(void *pdev, uint8_t cfgidx) +{ + /* Call all of the registered deinit callbacks */ + for (uint8_t i = 0; i < NELEMENTS(usb_if_table); i++) { + struct usb_if_entry * usb_if = &(usb_if_table[i]); + if (usb_if->ifops && usb_if->ifops->deinit) { + usb_if->ifops->deinit(usb_if->context); + } + } + return USBD_OK; +} + +static struct usb_setup_request usb_ep0_active_req; +static uint8_t PIOS_USBHOOK_CLASS_Setup(void *pdev, USB_SETUP_REQ *req) +{ + switch (req->bmRequest & (USB_REQ_TYPE_MASK | USB_REQ_RECIPIENT_MASK)) { + case (USB_REQ_TYPE_STANDARD | USB_REQ_RECIPIENT_INTERFACE): + case (USB_REQ_TYPE_CLASS | USB_REQ_RECIPIENT_INTERFACE): + { + uint8_t ifnum = LOBYTE(req->wIndex); + if ((ifnum < NELEMENTS(usb_if_table)) && + (usb_if_table[ifnum].ifops && usb_if_table[ifnum].ifops->setup)) { + usb_if_table[ifnum].ifops->setup(usb_if_table[ifnum].context, + (struct usb_setup_request *)req); + if (req->bmRequest & 0x80 && req->wLength > 0) { + /* Request is a host-to-device data setup packet, keep track of the request details for the EP0_RxReady call */ + usb_ep0_active_req.bmRequestType = req->bmRequest; + usb_ep0_active_req.bRequest = req->bRequest; + usb_ep0_active_req.wValue = req->wValue; + usb_ep0_active_req.wIndex = req->wIndex; + usb_ep0_active_req.wLength = req->wLength; + } + } else { + /* No Setup handler or Setup handler failed */ + USBD_CtlError (&pios_usb_otg_core_handle, req); + } + break; + } + default: + /* Unhandled Setup */ + USBD_CtlError (&pios_usb_otg_core_handle, req); + break; + } + + return USBD_OK; +} + +static uint8_t PIOS_USBHOOK_CLASS_EP0_TxSent(void *pdev) +{ + return USBD_OK; +} + +static uint8_t PIOS_USBHOOK_CLASS_EP0_RxReady(void *pdev) +{ + uint8_t ifnum = LOBYTE(usb_ep0_active_req.wIndex); + + if ((ifnum < NELEMENTS(usb_if_table)) && + (usb_if_table[ifnum].ifops && usb_if_table[ifnum].ifops->ctrl_data_out)) { + usb_if_table[ifnum].ifops->ctrl_data_out(usb_if_table[ifnum].context, + &usb_ep0_active_req); + } + + return USBD_OK; +} + +static uint8_t PIOS_USBHOOK_CLASS_DataIn(void *pdev, uint8_t epnum) +{ + /* Make sure the previous transfer has completed before starting a new one */ + DCD_EP_Flush(pdev, epnum); /* NOT SURE IF THIS IS REQUIRED */ + + /* Remove the direction bit so we can use this as an index */ + uint8_t epnum_idx = epnum & 0x7F; + + if ((epnum_idx < NELEMENTS(usb_epin_table)) && usb_epin_table[epnum_idx].cb) { + struct usb_ep_entry *ep = &(usb_epin_table[epnum_idx]); + if (!ep->cb(ep->context, epnum_idx, ep->max_len)) { + /* NOTE: use real endpoint number including direction bit */ + DCD_SetEPStatus(pdev, epnum, USB_OTG_EP_TX_NAK); + } + } + + return USBD_OK; +} + +static uint8_t PIOS_USBHOOK_CLASS_DataOut(void *pdev, uint8_t epnum) +{ + /* Remove the direction bit so we can use this as an index */ + uint8_t epnum_idx = epnum & 0x7F; + + if ((epnum_idx < NELEMENTS(usb_epout_table)) && usb_epout_table[epnum_idx].cb) { + struct usb_ep_entry *ep = &(usb_epout_table[epnum_idx]); + if (!ep->cb(ep->context, epnum_idx, ep->max_len)) { + /* NOTE: use real endpoint number including direction bit */ + DCD_SetEPStatus(pdev, epnum, USB_OTG_EP_RX_NAK); + } + } + + return USBD_OK; +} + +static uint8_t PIOS_USBHOOK_CLASS_SOF(void *pdev) +{ + return USBD_OK; +} + +static uint8_t PIOS_USBHOOK_CLASS_IsoINIncomplete(void *pdev) +{ + return USBD_OK; +} + +static uint8_t PIOS_USBHOOK_CLASS_IsoOUTIncomplete(void *pdev) +{ + return USBD_OK; +} + +static const uint8_t * PIOS_USBHOOK_CLASS_GetConfigDescriptor(uint8_t speed, uint16_t *length) +{ + *length = Config_Descriptor.length; + return Config_Descriptor.descriptor; +} + +#ifdef USB_OTG_HS_CORE +static const uint8_t * PIOS_USBHOOK_CLASS_GetOtherConfigDescriptor(uint8_t speed, uint16_t *length) +{ + return PIOS_USBHOOK_CLASS_GetConfigDescriptor(speed, length); +} +#endif /* USB_OTG_HS_CORE */ + +#ifdef USB_SUPPORT_USER_STRING_DESC +static const uint8_t * PIOS_USBHOOK_CLASS_GetUsrStrDescriptor(uint8_t speed, uint8_t index, uint16_t *length) +{ + return NULL; +} +#endif /* USB_SUPPORT_USER_STRING_DESC */ + +static USBD_Class_cb_TypeDef class_callbacks = { + .Init = PIOS_USBHOOK_CLASS_Init, + .DeInit = PIOS_USBHOOK_CLASS_DeInit, + .Setup = PIOS_USBHOOK_CLASS_Setup, + .EP0_TxSent = PIOS_USBHOOK_CLASS_EP0_TxSent, + .EP0_RxReady = PIOS_USBHOOK_CLASS_EP0_RxReady, + .DataIn = PIOS_USBHOOK_CLASS_DataIn, + .DataOut = PIOS_USBHOOK_CLASS_DataOut, + .SOF = PIOS_USBHOOK_CLASS_SOF, + .IsoINIncomplete = PIOS_USBHOOK_CLASS_IsoINIncomplete, + .IsoOUTIncomplete = PIOS_USBHOOK_CLASS_IsoOUTIncomplete, + .GetConfigDescriptor = PIOS_USBHOOK_CLASS_GetConfigDescriptor, +#ifdef USB_OTG_HS_CORE + .GetOtherConfigDescriptor = PIOS_USBHOOK_CLASS_GetOtherConfigDescriptor, +#endif /* USB_OTG_HS_CORE */ +#ifdef USB_SUPPORT_USER_STRING_DESC + .GetUsrStrDescriptor = PIOS_USBHOOK_CLASS_GetUsrStrDescriptor, +#endif /* USB_SUPPORT_USER_STRING_DESC */ +}; + diff --git a/flight/PiOS/STM32F4xx/pios_wdg.c b/flight/PiOS/STM32F4xx/pios_wdg.c new file mode 100644 index 000000000..3e66acfdc --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_wdg.c @@ -0,0 +1,176 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_WDG Watchdog Functions + * @brief PIOS Comamnds to initialize and clear watchdog timer + * @{ + * + * @file pios_spi.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Hardware Abstraction Layer for SPI ports of STM32 + * @see The GNU Public License (GPL) Version 3 + * @notes + * + * The PIOS Watchdog provides a HAL to initialize a watchdog + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* + * @todo This is virtually identical to the F1xx code and should be merged. + */ + +#include "pios.h" +#include "stm32f4xx_iwdg.h" +#include "stm32f4xx_dbgmcu.h" +#include "stm32f4xx_rtc.h" + +static struct wdg_configuration { + uint16_t used_flags; + uint16_t bootup_flags; +} wdg_configuration; + +/** + * @brief Initialize the watchdog timer for a specified timeout + * + * It is important to note that this function returns the achieved timeout + * for this hardware. For hardware independence this should be checked when + * scheduling updates. Other hardware dependent details may need to be + * considered such as a window time which sets a minimum update time, + * and this function should return a recommended delay for clearing. + * + * For the STM32 nominal clock rate is 32 khz, but for the maximum clock rate of + * 60 khz and a prescaler of 4 yields a clock rate of 15 khz. The delay that is + * set in the watchdog assumes the nominal clock rate, but the delay for FreeRTOS + * to use is 75% of the minimal delay. + * + * @returns Maximum recommended delay between updates based on PIOS_WATCHDOG_TIMEOUT constant + */ +uint16_t PIOS_WDG_Init() +{ + uint16_t delay = ((uint32_t) PIOS_WATCHDOG_TIMEOUT * 60) / 16; + if (delay > 0x0fff) + delay = 0x0fff; +#if defined(PIOS_INCLUDE_WDG) + DBGMCU_Config(DBGMCU_IWDG_STOP, ENABLE); // make the watchdog stop counting in debug mode + IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable); + IWDG_SetPrescaler(IWDG_Prescaler_16); + IWDG_SetReload(delay); + IWDG_ReloadCounter(); + IWDG_Enable(); + + // watchdog flags now stored in backup registers + PWR_BackupAccessCmd(ENABLE); + + wdg_configuration.bootup_flags = RTC_ReadBackupRegister(PIOS_WDG_REGISTER); +#endif + return delay; +} + +/** + * @brief Register a module against the watchdog + * + * There are two ways to use PIOS WDG: this is for when + * multiple modules must be monitored. In this case they + * must first register against the watchdog system and + * only when all of the modules have been updated with the + * watchdog be cleared. Each module must have its own + * bit in the 16 bit + * + * @param[in] flag the bit this module wants to use + * @returns True if that bit is unregistered + */ +bool PIOS_WDG_RegisterFlag(uint16_t flag_requested) +{ + + /* Fail if flag already registered */ + if(wdg_configuration.used_flags & flag_requested) + return false; + + // FIXME: Protect with semaphore + wdg_configuration.used_flags |= flag_requested; + + return true; +} + +/** + * @brief Function called by modules to indicate they are still running + * + * This function will set this flag in the active flags register (which is + * a backup regsiter) and if all the registered flags are set will clear + * the watchdog and set only this flag in the backup register + * + * @param[in] flag the flag to set + * @return true if the watchdog cleared, false if flags are pending + */ +bool PIOS_WDG_UpdateFlag(uint16_t flag) +{ + // we can probably avoid using a semaphore here which will be good for + // efficiency and not blocking critical tasks. race condition could + // overwrite their flag update, but unlikely to block _all_ of them + // for the timeout window + uint16_t cur_flags = RTC_ReadBackupRegister(PIOS_WDG_REGISTER); + + if((cur_flags | flag) == wdg_configuration.used_flags) { + PIOS_WDG_Clear(); + RTC_WriteBackupRegister(PIOS_WDG_REGISTER, flag); + return true; + } else { + RTC_WriteBackupRegister(PIOS_WDG_REGISTER, cur_flags | flag); + return false; + } + +} + +/** + * @brief Returns the flags that were set at bootup + * + * This is used for diagnostics, if only one flag not set this + * was likely the module that wasn't running before reset + * + * @return The active flags register from bootup + */ +uint16_t PIOS_WDG_GetBootupFlags() +{ + return wdg_configuration.bootup_flags; +} + +/** + * @brief Returns the currently active flags + * + * For external monitoring + * + * @return The active flags register + */ +uint16_t PIOS_WDG_GetActiveFlags() +{ + return RTC_ReadBackupRegister(PIOS_WDG_REGISTER); +} + +/** + * @brief Clear the watchdog timer + * + * This function must be called at the appropriate delay to prevent a reset event occuring + */ +void PIOS_WDG_Clear(void) +{ +#if defined(PIOS_INCLUDE_WDG) + IWDG_ReloadCounter(); +#endif +} diff --git a/flight/PiOS/STM32F4xx/startup.c b/flight/PiOS/STM32F4xx/startup.c new file mode 100644 index 000000000..94a3debcd --- /dev/null +++ b/flight/PiOS/STM32F4xx/startup.c @@ -0,0 +1,148 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * + * @file startup.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief C based startup of F4 + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#include +#include + +/* prototype for main() that tells us not to worry about it possibly returning */ +extern int main(void) __attribute__((noreturn)); + +/* prototype our _main() to avoid prolog/epilog insertion and other related junk */ +void _main(void) __attribute__((noreturn, naked, no_instrument_function)); + +/** default handler for CPU exceptions */ +static void default_cpu_handler(void) __attribute__((noreturn, naked, no_instrument_function)); + +/** BSS symbols XXX should have a header that defines all of these */ +extern char _sbss, _ebss; + +/** DATA symbols XXX should have a header that defines all of these */ +extern char _sidata, _sdata, _edata, _sfast, _efast; + +/** The bootstrap/IRQ stack XXX should define size somewhere else */ +char irq_stack[1024] __attribute__((section(".irqstack"))); + +/** exception handler */ +typedef const void (vector)(void); + +/** CortexM3 CPU vectors */ +struct cm3_vectors { + void *initial_stack; + vector *entry; + vector *vectors[14]; +}; + +/** + * Initial startup code. + */ +void +_main(void) +{ + // load the stack base for the current stack before we attempt to branch to any function + // that might bounds-check the stack + asm volatile ("mov r10, %0" : : "r" (&irq_stack[0]) : ); + + /* enable usage, bus and memory faults */ + SCB->SHCSR |= SCB_SHCSR_USGFAULTENA_Msk | SCB_SHCSR_BUSFAULTENA_Msk | SCB_SHCSR_MEMFAULTENA_Msk; + + /* configure FP state save behaviour - automatic, lazy save */ + FPU->FPCCR |= FPU_FPCCR_ASPEN_Msk | FPU_FPCCR_LSPEN_Msk; + + /* configure default FPU state */ + FPU->FPDSCR |= FPU_FPDSCR_DN_Msk; /* enable Default NaN */ + + /* enable the FPU */ + SCB->CPACR |= (0xf << 20); // turn on CP10/11 for FP support on cores that implement it + + /* copy initialised data from flash to RAM */ + memcpy(&_sdata, &_sidata, &_edata - &_sdata); + + /* zero the BSS */ + memset(&_sbss, 0, &_ebss - &_sbss); + + /* zero any 'fast' RAM that's been used */ + memset(&_sfast, 0, &_efast - &_sfast); + + /* fill most of the IRQ/bootstrap stack with a watermark pattern so we can measure how much is used */ + /* leave a little space at the top in case memset() isn't a leaf with no locals */ + memset(&irq_stack, 0xa5, sizeof(irq_stack) - 64); + + /* call main */ + (void)main(); +} + +/** + * Default handler for CPU exceptions. + */ +static void +default_cpu_handler(void) +{ + for (;;) ; +} + +/** Prototype for optional exception vector handlers */ +#define HANDLER(_name) extern vector _name __attribute__((weak, alias("default_cpu_handler"))) + +/* standard CMSIS vector names */ +HANDLER(NMI_Handler); +HANDLER(HardFault_Handler); +HANDLER(MemManage_Handler); +HANDLER(BusFault_Handler); +HANDLER(UsageFault_Handler); +HANDLER(DebugMon_Handler); + +/* these vectors point directly to the relevant FreeRTOS functions if they are defined */ +HANDLER(vPortSVCHandler); +HANDLER(xPortPendSVHandler); +HANDLER(xPortSysTickHandler); + +/** CortexM3 vector table */ +struct cm3_vectors cpu_vectors __attribute((section(".cpu_vectors"))) = { + .initial_stack = &irq_stack[sizeof(irq_stack)], + .entry = (vector *)_main, + .vectors = { + NMI_Handler, + HardFault_Handler, + MemManage_Handler, + BusFault_Handler, + UsageFault_Handler, + 0, + 0, + 0, + 0, + vPortSVCHandler, + DebugMon_Handler, + 0, + xPortPendSVHandler, + xPortSysTickHandler, + } +}; + +/** + * @} + */ \ No newline at end of file diff --git a/flight/PiOS/STM32F4xx/vectors_stm32f4xx.c b/flight/PiOS/STM32F4xx/vectors_stm32f4xx.c new file mode 100644 index 000000000..2b28d558c --- /dev/null +++ b/flight/PiOS/STM32F4xx/vectors_stm32f4xx.c @@ -0,0 +1,212 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * + * @file vector_stm32f4xx.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief C based vectors for F4 + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/** interrupt handler */ +typedef const void (vector)(void); + +/** default interrupt handler */ +static void +default_io_handler(void) +{ + for (;;) ; +} + +/** prototypes an interrupt handler */ +#define HANDLER(_name) extern vector _name __attribute__((weak, alias("default_io_handler"))) + +HANDLER(WWDG_IRQHandler); // Window WatchDog +HANDLER(PVD_IRQHandler); // PVD through EXTI Line detection +HANDLER(TAMP_STAMP_IRQHandler); // Tamper and TimeStamps through the EXTI line +HANDLER(RTC_WKUP_IRQHandler); // RTC Wakeup through the EXTI line +HANDLER(FLASH_IRQHandler); // FLASH +HANDLER(RCC_IRQHandler); // RCC +HANDLER(EXTI0_IRQHandler); // EXTI Line0 +HANDLER(EXTI1_IRQHandler); // EXTI Line1 +HANDLER(EXTI2_IRQHandler); // EXTI Line2 +HANDLER(EXTI3_IRQHandler); // EXTI Line3 +HANDLER(EXTI4_IRQHandler); // EXTI Line4 +HANDLER(DMA1_Stream0_IRQHandler); // DMA1 Stream 0 +HANDLER(DMA1_Stream1_IRQHandler); // DMA1 Stream 1 +HANDLER(DMA1_Stream2_IRQHandler); // DMA1 Stream 2 +HANDLER(DMA1_Stream3_IRQHandler); // DMA1 Stream 3 +HANDLER(DMA1_Stream4_IRQHandler); // DMA1 Stream 4 +HANDLER(DMA1_Stream5_IRQHandler); // DMA1 Stream 5 +HANDLER(DMA1_Stream6_IRQHandler); // DMA1 Stream 6 +HANDLER(ADC_IRQHandler); // ADC1, ADC2 and ADC3s +HANDLER(CAN1_TX_IRQHandler); // CAN1 TX +HANDLER(CAN1_RX0_IRQHandler); // CAN1 RX0 +HANDLER(CAN1_RX1_IRQHandler); // CAN1 RX1 +HANDLER(CAN1_SCE_IRQHandler); // CAN1 SCE +HANDLER(EXTI9_5_IRQHandler); // External Line[9:5]s +HANDLER(TIM1_BRK_TIM9_IRQHandler); // TIM1 Break and TIM9 +HANDLER(TIM1_UP_TIM10_IRQHandler); // TIM1 Update and TIM10 +HANDLER(TIM1_TRG_COM_TIM11_IRQHandler); // TIM1 Trigger and Commutation and TIM11 +HANDLER(TIM1_CC_IRQHandler); // TIM1 Capture Compare +HANDLER(TIM2_IRQHandler); // TIM2 +HANDLER(TIM3_IRQHandler); // TIM3 +HANDLER(TIM4_IRQHandler); // TIM4 +HANDLER(I2C1_EV_IRQHandler); // I2C1 Event +HANDLER(I2C1_ER_IRQHandler); // I2C1 Error +HANDLER(I2C2_EV_IRQHandler); // I2C2 Event +HANDLER(I2C2_ER_IRQHandler); // I2C2 Error +HANDLER(SPI1_IRQHandler); // SPI1 +HANDLER(SPI2_IRQHandler); // SPI2 +HANDLER(USART1_IRQHandler); // USART1 +HANDLER(USART2_IRQHandler); // USART2 +HANDLER(USART3_IRQHandler); // USART3 +HANDLER(EXTI15_10_IRQHandler); // External Line[15:10]s +HANDLER(RTC_Alarm_IRQHandler); // RTC Alarm (A and B) through EXTI Line +HANDLER(OTG_FS_WKUP_IRQHandler); // USB OTG FS Wakeup through EXTI line +HANDLER(TIM8_BRK_TIM12_IRQHandler); // TIM8 Break and TIM12 +HANDLER(TIM8_UP_TIM13_IRQHandler); // TIM8 Update and TIM13 +HANDLER(TIM8_TRG_COM_TIM14_IRQHandler); // TIM8 Trigger and Commutation and TIM14 +HANDLER(TIM8_CC_IRQHandler); // TIM8 Capture Compare +HANDLER(DMA1_Stream7_IRQHandler); // DMA1 Stream7 +HANDLER(FSMC_IRQHandler); // FSMC +HANDLER(SDIO_IRQHandler); // SDIO +HANDLER(TIM5_IRQHandler); // TIM5 +HANDLER(SPI3_IRQHandler); // SPI3 +HANDLER(USART4_IRQHandler); // UART4 +HANDLER(USART5_IRQHandler); // UART5 +HANDLER(TIM6_DAC_IRQHandler); // TIM6 and DAC1&2 underrun errors +HANDLER(TIM7_IRQHandler); // TIM7 +HANDLER(DMA2_Stream0_IRQHandler); // DMA2 Stream 0 +HANDLER(DMA2_Stream1_IRQHandler); // DMA2 Stream 1 +HANDLER(DMA2_Stream2_IRQHandler); // DMA2 Stream 2 +HANDLER(DMA2_Stream3_IRQHandler); // DMA2 Stream 3 +HANDLER(DMA2_Stream4_IRQHandler); // DMA2 Stream 4 +HANDLER(ETH_IRQHandler); // Ethernet +HANDLER(ETH_WKUP_IRQHandler); // Ethernet Wakeup through EXTI line +HANDLER(CAN2_TX_IRQHandler); // CAN2 TX +HANDLER(CAN2_RX0_IRQHandler); // CAN2 RX0 +HANDLER(CAN2_RX1_IRQHandler); // CAN2 RX1 +HANDLER(CAN2_SCE_IRQHandler); // CAN2 SCE +HANDLER(OTG_FS_IRQHandler); // USB OTG FS +HANDLER(DMA2_Stream5_IRQHandler); // DMA2 Stream 5 +HANDLER(DMA2_Stream6_IRQHandler); // DMA2 Stream 6 +HANDLER(DMA2_Stream7_IRQHandler); // DMA2 Stream 7 +HANDLER(USART6_IRQHandler); // USART6 +HANDLER(I2C3_EV_IRQHandler); // I2C3 event +HANDLER(I2C3_ER_IRQHandler); // I2C3 error +HANDLER(OTG_HS_EP1_OUT_IRQHandler); // USB OTG HS End Point 1 Out +HANDLER(OTG_HS_EP1_IN_IRQHandler); // USB OTG HS End Point 1 In +HANDLER(OTG_HS_WKUP_IRQHandler); // USB OTG HS Wakeup through EXTI +HANDLER(OTG_HS_IRQHandler); // USB OTG HS +HANDLER(DCMI_IRQHandler); // DCMI +HANDLER(CRYP_IRQHandler); // CRYP crypto +HANDLER(HASH_RNG_IRQHandler); // Hash and Rng +HANDLER(FPU_IRQHandler); // FPU + +/** stm32f4xx interrupt vector table */ +vector *io_vectors[] __attribute__((section(".io_vectors"))) = { + WWDG_IRQHandler, // Window WatchDog + PVD_IRQHandler, // PVD through EXTI Line detection + TAMP_STAMP_IRQHandler, // Tamper and TimeStamps through the EXTI line + RTC_WKUP_IRQHandler, // RTC Wakeup through the EXTI line + FLASH_IRQHandler, // FLASH + RCC_IRQHandler, // RCC + EXTI0_IRQHandler, // EXTI Line0 + EXTI1_IRQHandler, // EXTI Line1 + EXTI2_IRQHandler, // EXTI Line2 + EXTI3_IRQHandler, // EXTI Line3 + EXTI4_IRQHandler, // EXTI Line4 + DMA1_Stream0_IRQHandler, // DMA1 Stream 0 + DMA1_Stream1_IRQHandler, // DMA1 Stream 1 + DMA1_Stream2_IRQHandler, // DMA1 Stream 2 + DMA1_Stream3_IRQHandler, // DMA1 Stream 3 + DMA1_Stream4_IRQHandler, // DMA1 Stream 4 + DMA1_Stream5_IRQHandler, // DMA1 Stream 5 + DMA1_Stream6_IRQHandler, // DMA1 Stream 6 + ADC_IRQHandler, // ADC1, ADC2 and ADC3s + CAN1_TX_IRQHandler, // CAN1 TX + CAN1_RX0_IRQHandler, // CAN1 RX0 + CAN1_RX1_IRQHandler, // CAN1 RX1 + CAN1_SCE_IRQHandler, // CAN1 SCE + EXTI9_5_IRQHandler, // External Line[9:5]s + TIM1_BRK_TIM9_IRQHandler, // TIM1 Break and TIM9 + TIM1_UP_TIM10_IRQHandler, // TIM1 Update and TIM10 + TIM1_TRG_COM_TIM11_IRQHandler, // TIM1 Trigger and Commutation and TIM11 + TIM1_CC_IRQHandler, // TIM1 Capture Compare + TIM2_IRQHandler, // TIM2 + TIM3_IRQHandler, // TIM3 + TIM4_IRQHandler, // TIM4 + I2C1_EV_IRQHandler, // I2C1 Event + I2C1_ER_IRQHandler, // I2C1 Error + I2C2_EV_IRQHandler, // I2C2 Event + I2C2_ER_IRQHandler, // I2C2 Error + SPI1_IRQHandler, // SPI1 + SPI2_IRQHandler, // SPI2 + USART1_IRQHandler, // USART1 + USART2_IRQHandler, // USART2 + USART3_IRQHandler, // USART3 + EXTI15_10_IRQHandler, // External Line[15:10]s + RTC_Alarm_IRQHandler, // RTC Alarm (A and B) through EXTI Line + OTG_FS_WKUP_IRQHandler, // USB OTG FS Wakeup through EXTI line + TIM8_BRK_TIM12_IRQHandler, // TIM8 Break and TIM12 + TIM8_UP_TIM13_IRQHandler, // TIM8 Update and TIM13 + TIM8_TRG_COM_TIM14_IRQHandler, // TIM8 Trigger and Commutation and TIM14 + TIM8_CC_IRQHandler, // TIM8 Capture Compare + DMA1_Stream7_IRQHandler, // DMA1 Stream7 + FSMC_IRQHandler, // FSMC + SDIO_IRQHandler, // SDIO + TIM5_IRQHandler, // TIM5 + SPI3_IRQHandler, // SPI3 + USART4_IRQHandler, // UART4 + USART5_IRQHandler, // UART5 + TIM6_DAC_IRQHandler, // TIM6 and DAC1&2 underrun errors + TIM7_IRQHandler, // TIM7 + DMA2_Stream0_IRQHandler, // DMA2 Stream 0 + DMA2_Stream1_IRQHandler, // DMA2 Stream 1 + DMA2_Stream2_IRQHandler, // DMA2 Stream 2 + DMA2_Stream3_IRQHandler, // DMA2 Stream 3 + DMA2_Stream4_IRQHandler, // DMA2 Stream 4 + ETH_IRQHandler, // Ethernet + ETH_WKUP_IRQHandler, // Ethernet Wakeup through EXTI line + CAN2_TX_IRQHandler, // CAN2 TX + CAN2_RX0_IRQHandler, // CAN2 RX0 + CAN2_RX1_IRQHandler, // CAN2 RX1 + CAN2_SCE_IRQHandler, // CAN2 SCE + OTG_FS_IRQHandler, // USB OTG FS + DMA2_Stream5_IRQHandler, // DMA2 Stream 5 + DMA2_Stream6_IRQHandler, // DMA2 Stream 6 + DMA2_Stream7_IRQHandler, // DMA2 Stream 7 + USART6_IRQHandler, // USART6 + I2C3_EV_IRQHandler, // I2C3 event + I2C3_ER_IRQHandler, // I2C3 error + OTG_HS_EP1_OUT_IRQHandler, // USB OTG HS End Point 1 Out + OTG_HS_EP1_IN_IRQHandler, // USB OTG HS End Point 1 In + OTG_HS_WKUP_IRQHandler, // USB OTG HS Wakeup through EXTI + OTG_HS_IRQHandler, // USB OTG HS + DCMI_IRQHandler, // DCMI + CRYP_IRQHandler, // CRYP crypto + HASH_RNG_IRQHandler, // Hash and Rng + FPU_IRQHandler, // FPU +}; + +/** + * @} + */ \ No newline at end of file diff --git a/flight/PiOS/inc/pios_adc.h b/flight/PiOS/inc/pios_adc.h index 9b3aeb396..f72b163ee 100644 --- a/flight/PiOS/inc/pios_adc.h +++ b/flight/PiOS/inc/pios_adc.h @@ -7,8 +7,7 @@ * @{ * * @file pios_adc.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief ADC functions header. * @see The GNU Public License (GPL) Version 3 * @@ -38,7 +37,6 @@ typedef void (*ADCCallback) (float * data); /* Public Functions */ -void PIOS_ADC_Init(); void PIOS_ADC_Config(uint32_t oversampling); int32_t PIOS_ADC_PinGet(uint32_t pin); int16_t * PIOS_ADC_GetRawBuffer(void); diff --git a/flight/PiOS/inc/pios_adc_priv.h b/flight/PiOS/inc/pios_adc_priv.h index 7ec61038d..278dcb8b7 100644 --- a/flight/PiOS/inc/pios_adc_priv.h +++ b/flight/PiOS/inc/pios_adc_priv.h @@ -40,25 +40,10 @@ struct pios_adc_cfg { struct stm32_dma dma; uint32_t half_flag; uint32_t full_flag; + uint16_t max_downsample; }; -struct pios_adc_dev { - const struct pios_adc_cfg *const cfg; - ADCCallback callback_function; -#if defined(PIOS_INCLUDE_FREERTOS) - xQueueHandle data_queue; -#endif - volatile int16_t *valid_data_buffer; - volatile uint8_t adc_oversample; - uint8_t dma_block_size; - uint16_t dma_half_buffer_size; - int16_t fir_coeffs[PIOS_ADC_MAX_SAMPLES+1] __attribute__ ((aligned(4))); - volatile int16_t raw_data_buffer[PIOS_ADC_MAX_SAMPLES] __attribute__ ((aligned(4))); // Double buffer that DMA just used - float downsampled_buffer[PIOS_ADC_NUM_CHANNELS] __attribute__ ((aligned(4))); -}; - -extern struct pios_adc_dev pios_adc_devs[]; -extern uint8_t pios_adc_num_devices; +int32_t PIOS_ADC_Init(const struct pios_adc_cfg * cfg); #endif /* PIOS_ADC_PRIV_H */ diff --git a/flight/PiOS/inc/pios_adxl345.h b/flight/PiOS/inc/pios_adxl345.h index 1e0b89f6d..4701aaf55 100644 --- a/flight/PiOS/inc/pios_adxl345.h +++ b/flight/PiOS/inc/pios_adxl345.h @@ -1,12 +1,31 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_ADXL345 ADXL345 Functions + * @brief Data from the ADXL345 sensors + * @{ + * @file pios_adxl345.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief PiOS SPI ADXL345 + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ /* - * pios_adxl345.h - * OpenPilotOSX + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. * - * Created by James Cotton on 1/16/11. - * Copyright 2011 OpenPilot. All rights reserved. + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ - #ifndef PIOS_ADXL345_H #define PIOS_ADXL345_H @@ -15,6 +34,8 @@ #define ADXL_READ_BIT 0x80 #define ADXL_MULTI_BIT 0x40 +#define ADXL_WHOAMI 0x00 +#define ADXL_DEVICE_ID 0xE5 #define ADXL_X0_ADDR 0x32 #define ADXL_FIFOSTATUS_ADDR 0x39 @@ -47,12 +68,16 @@ struct pios_adxl345_data { int16_t z; }; -void PIOS_ADXL345_SelectRate(uint8_t rate); -void PIOS_ADXL345_SetRange(uint8_t range); -void PIOS_ADXL345_FifoDepth(uint8_t depth); -void PIOS_ADXL345_Attach(uint32_t spi_id); -void PIOS_ADXL345_Init(); +int32_t PIOS_ADXL345_SelectRate(uint8_t rate); +int32_t PIOS_ADXL345_SetRange(uint8_t range); +int32_t PIOS_ADXL345_Init(uint32_t spi_id, uint32_t slave_num); uint8_t PIOS_ADXL345_Read(struct pios_adxl345_data * data); -uint8_t PIOS_ADXL345_FifoElements(); +int32_t PIOS_ADXL345_FifoElements(); +int32_t PIOS_ADXL345_Test(); #endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_bma180.h b/flight/PiOS/inc/pios_bma180.h index 67e4c87bf..ef9627f00 100644 --- a/flight/PiOS/inc/pios_bma180.h +++ b/flight/PiOS/inc/pios_bma180.h @@ -7,8 +7,7 @@ * @{ * * @file pios_bma180.h - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief PiOS BMA180 digital accelerometer driver. * - Driver for the BMA180 digital accelerometer on the SPI bus. * @see The GNU Public License (GPL) Version 3 @@ -30,9 +29,13 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include "fifo_buffer.h" + #ifndef PIOS_BMA180_H #define PIOS_BMA180_H +#include + /* BMA180 Addresses */ #define BMA_CHIPID_ADDR 0x00 #define BMA_VERSION_ADDR 0x00 @@ -40,44 +43,67 @@ #define BMA_Y_LSB_ADDR 0x04 #define BMA_Z_LSB_ADDR 0x06 #define BMA_WE_ADDR 0x0D +#define BMA_RESET 0x10 #define BMA_BW_ADDR 0x20 #define BMA_RANGE_ADDR 0x35 +#define BMA_OFFSET_LSB1 0x35 +#define BMA_GAIN_Y 0x33 +#define BMA_CTRREG3 0x21 +#define BMA_CTRREG0 0x0D + +#define BMA_RESET_CODE 0x6B /* Accel range */ -#define BMA_RANGE_1G 0x00 // +/- 1G ADC resolution 0.13 mg/LSB -#define BMA_RANGE_1_5G 0x01 // +/- 1.5G ADC resolution 0.19 mg/LSB -#define BMA_RANGE_2G 0x02 // +/- 2G ADC resolution 0.25 mg/LSB *** default *** -#define BMA_RANGE_3G 0x03 // +/- 3G ADC resolution 0.38 mg/LSB -#define BMA_RANGE_4G 0x04 // +/- 4G ADC resolution 0.50 mg/LSB -#define BMA_RANGE_8G 0x05 // +/- 8G ADC resolution 0.99 mg/LSB -#define BMA_RANGE_16G 0x06 // +/- 16G ADC resolution 1.98 mg/LSB +#define BMA_RANGE_MASK 0x0E +#define BMA_RANGE_SHIFT 1 +enum bma180_range { BMA_RANGE_1G = 0x00, + BMA_RANGE_1_5G = 0x01, + BMA_RANGE_2G = 0x02, + BMA_RANGE_3G = 0x03, + BMA_RANGE_4G = 0x04, + BMA_RANGE_8G = 0x05, + BMA_RANGE_16G = 0x06 +}; /* Measurement bandwidth */ -#define BMA_BW_10HZ 0x00 -#define BMA_BW_20HZ 0x01 -#define BMA_BW_40HZ 0x02 -#define BMA_BW_75HZ 0x03 -#define BMA_BW_150HZ 0x04 // *** default *** -#define BMA_BW_300HZ 0x05 -#define BMA_BW_600HZ 0x06 -#define BMA_BW_1200HZ 0x07 -#define BMA_BW_HP1HZ 0x08 // High-pass, 1Hz -#define BMA_BW_BP0_300HZ 0x09 // Band-pass, 0.3Hz-300Hz +#define BMA_BW_MASK 0xF0 +#define BMA_BW_SHIFT 4 +enum bma180_bandwidth { BMA_BW_10HZ = 0x00, + BMA_BW_20HZ = 0x01, + BMA_BW_40HZ = 0x02, + BMA_BW_75HZ = 0x03, + BMA_BW_150HZ = 0x04, + BMA_BW_300HZ = 0x05, + BMA_BW_600HZ = 0x06, + BMA_BW_1200HZ =0x07, + BMA_BW_HP1HZ = 0x08, // High-pass, 1 Hz + BMA_BW_BP0_300HZ = 0x09 // Band-pass, 0.3Hz-300Hz +}; + +#define BMA_NEW_DAT_INT 0x02 struct pios_bma180_data { int16_t x; int16_t y; int16_t z; + int8_t temperature; +}; + + +struct pios_bma180_cfg { + const struct pios_exti_cfg * exti_cfg; /* Pointer to the EXTI configuration */ + enum bma180_bandwidth bandwidth; + enum bma180_range range; }; /* Public Functions */ -void PIOS_BMA180_WriteEnable(uint8_t _we); -uint8_t PIOS_BMA180_GetReg(uint8_t reg); -void PIOS_BMA180_SetReg(uint8_t reg, uint8_t data); -void PIOS_BMA180_Attach(uint32_t spi_id); -void PIOS_BMA180_Init(); -uint8_t PIOS_BMA180_Read(struct pios_bma180_data * data); -uint8_t PIOS_BMA180_Test(); +extern int32_t PIOS_BMA180_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_bma180_cfg * cfg); +extern void PIOS_BMA180_Attach(uint32_t spi_id); +extern float PIOS_BMA180_GetScale(); +extern int32_t PIOS_BMA180_ReadFifo(struct pios_bma180_data * buffer); +extern int32_t PIOS_BMA180_ReadAccels(struct pios_bma180_data * data); +extern int32_t PIOS_BMA180_Test(); +extern void PIOS_BMA180_IRQHandler(); #endif /* PIOS_BMA180_H */ diff --git a/flight/PiOS/inc/pios_board_info.h b/flight/PiOS/inc/pios_board_info.h index f2ff58fb4..3ff7aa886 100644 --- a/flight/PiOS/inc/pios_board_info.h +++ b/flight/PiOS/inc/pios_board_info.h @@ -1,3 +1,8 @@ +#ifndef PIOS_BOARD_INFO_H +#define PIOS_BOARD_INFO_H + +#include /* uint* */ + #define PIOS_BOARD_INFO_BLOB_MAGIC 0xBDBDBDBD struct pios_board_info { @@ -15,3 +20,5 @@ struct pios_board_info { } __attribute__((packed)); extern const struct pios_board_info pios_board_info_blob; + +#endif /* PIOS_BOARD_INFO_H */ diff --git a/flight/PiOS/inc/pios_crc.h b/flight/PiOS/inc/pios_crc.h index 3a64f8bab..612c89e49 100644 --- a/flight/PiOS/inc/pios_crc.h +++ b/flight/PiOS/inc/pios_crc.h @@ -29,3 +29,9 @@ uint8_t PIOS_CRC_updateByte(uint8_t crc, const uint8_t data); uint8_t PIOS_CRC_updateCRC(uint8_t crc, const uint8_t* data, int32_t length); + +uint16_t PIOS_CRC16_updateByte(uint16_t crc, const uint8_t data); +uint16_t PIOS_CRC16_updateCRC(uint16_t crc, const uint8_t* data, int32_t length); + +uint32_t PIOS_CRC32_updateByte(uint32_t crc, const uint8_t data); +uint32_t PIOS_CRC32_updateCRC(uint32_t crc, const uint8_t* data, int32_t length); diff --git a/flight/PiOS/inc/pios_delay.h b/flight/PiOS/inc/pios_delay.h index 545deb841..4b79e3ef1 100644 --- a/flight/PiOS/inc/pios_delay.h +++ b/flight/PiOS/inc/pios_delay.h @@ -37,6 +37,8 @@ extern int32_t PIOS_DELAY_WaituS(uint32_t uS); extern int32_t PIOS_DELAY_WaitmS(uint32_t mS); extern uint32_t PIOS_DELAY_GetuS(); extern uint32_t PIOS_DELAY_GetuSSince(uint32_t t); +extern uint32_t PIOS_DELAY_GetRaw(); +extern uint32_t PIOS_DELAY_DiffuS(uint32_t raw); #endif /* PIOS_DELAY_H */ diff --git a/flight/PiOS/inc/pios_eeprom.h b/flight/PiOS/inc/pios_eeprom.h new file mode 100644 index 000000000..14acc595e --- /dev/null +++ b/flight/PiOS/inc/pios_eeprom.h @@ -0,0 +1,50 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_EEPROM EEPROM reading/writing functions + * @brief PIOS EEPROM reading/writing functions + * @{ + * + * @file pios_eeprom.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief COM layer functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_EEPROM_H +#define PIOS_EEPROM_H + +/* Public Structures */ +struct pios_eeprom_cfg { + uint32_t base_address; + uint32_t max_size; +}; + +/* Public Functions */ +extern void PIOS_EEPROM_Init(const struct pios_eeprom_cfg *cfg); +extern int32_t PIOS_EEPROM_Save(uint8_t *data, uint32_t len); +extern int32_t PIOS_EEPROM_Load(uint8_t *data, uint32_t len); + +#endif /* PIOS_EEPROM_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_flash_jedec.h b/flight/PiOS/inc/pios_flash_jedec.h new file mode 100644 index 000000000..4fc5d2fdf --- /dev/null +++ b/flight/PiOS/inc/pios_flash_jedec.h @@ -0,0 +1,50 @@ +/** + ****************************************************************************** + * + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_FLASH Flash device handler + * @{ + * + * @file pios_flash_w25x.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Driver for talking to W25X flash chip (and most JEDEC chips) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +struct pios_flash_jedec_cfg { + uint32_t sector_erase; + uint32_t chip_erase; +}; + +struct pios_flash_chunk { + uint8_t * addr; + uint32_t len; +}; + +int32_t PIOS_Flash_Jedec_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_flash_jedec_cfg * cfg); +int32_t PIOS_Flash_Jedec_ReadStatus(); +int32_t PIOS_Flash_Jedec_ReadID(); +int32_t PIOS_Flash_Jedec_EraseChip(); +int32_t PIOS_Flash_Jedec_EraseSector(uint32_t add); +int32_t PIOS_Flash_Jedec_WriteData(uint32_t addr, uint8_t * data, uint16_t len); +int32_t PIOS_Flash_Jedec_ReadData(uint32_t addr, uint8_t * data, uint16_t len); +int32_t PIOS_Flash_Jedec_WriteChunks(uint32_t addr, struct pios_flash_chunk * p_chunk, uint32_t num); +int32_t PIOS_Flash_Jedec_StartTransaction(); +int32_t PIOS_Flash_Jedec_EndTransaction(); diff --git a/flight/PiOS/inc/pios_flash_w25x.h b/flight/PiOS/inc/pios_flash_w25x.h deleted file mode 100644 index 9d6fd49a5..000000000 --- a/flight/PiOS/inc/pios_flash_w25x.h +++ /dev/null @@ -1,16 +0,0 @@ -/* - * pios_flash_w25x.h - * OpenPilotOSX - * - * Created by James Cotton on 1/23/11. - * Copyright 2011 OpenPilot. All rights reserved. - * - */ - -int8_t PIOS_Flash_W25X_Init(); -uint8_t PIOS_Flash_W25X_ReadStatus(); -uint8_t PIOS_Flash_W25X_ReadID(); -int8_t PIOS_Flash_W25X_EraseChip(); -int8_t PIOS_Flash_W25X_EraseSector(uint32_t add); -int8_t PIOS_Flash_W25X_WriteData(uint32_t addr, uint8_t * data, uint16_t len); -int8_t PIOS_Flash_W25X_ReadData(uint32_t addr, uint8_t * data, uint16_t len); diff --git a/flight/PiOS/inc/pios_flashfs_objlist.h b/flight/PiOS/inc/pios_flashfs_objlist.h index f5c22d973..a330da230 100644 --- a/flight/PiOS/inc/pios_flashfs_objlist.h +++ b/flight/PiOS/inc/pios_flashfs_objlist.h @@ -31,7 +31,16 @@ #include "openpilot.h" #include "uavobjectmanager.h" -int32_t PIOS_FLASHFS_Init(); +struct flashfs_cfg { + uint32_t table_magic; + uint32_t obj_magic; + uint32_t obj_table_start; + uint32_t obj_table_end; + uint32_t sector_size; + uint32_t chip_size; +}; + +int32_t PIOS_FLASHFS_Init(const struct flashfs_cfg * cfg); int32_t PIOS_FLASHFS_Format(); int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data); int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data); diff --git a/flight/PiOS/inc/pios_hmc5843.h b/flight/PiOS/inc/pios_hmc5843.h index fc20ff753..21b3f426a 100644 --- a/flight/PiOS/inc/pios_hmc5843.h +++ b/flight/PiOS/inc/pios_hmc5843.h @@ -7,7 +7,7 @@ * @{ * * @file pios_hmc5843.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief HMC5843 functions header. * @see The GNU Public License (GPL) Version 3 * diff --git a/flight/PiOS/inc/pios_hmc5883.h b/flight/PiOS/inc/pios_hmc5883.h index c7a4d6c4a..037dca788 100644 --- a/flight/PiOS/inc/pios_hmc5883.h +++ b/flight/PiOS/inc/pios_hmc5883.h @@ -7,8 +7,7 @@ * @{ * * @file pios_hmc5883.h - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief HMC5883 functions header. * @see The GNU Public License (GPL) Version 3 * @@ -32,6 +31,8 @@ #ifndef PIOS_HMC5883_H #define PIOS_HMC5883_H +#include + /* HMC5883 Addresses */ #define PIOS_HMC5883_I2C_ADDR 0x1E #define PIOS_HMC5883_I2C_READ_ADDR 0x3D @@ -90,13 +91,23 @@ #define PIOS_HMC5883_Sensitivity_5_6Ga 330 // LSB/Ga #define PIOS_HMC5883_Sensitivity_8_1Ga 230 // LSB/Ga --> NOT RECOMMENDED -/* Public Functions */ -extern void PIOS_HMC5883_Init(void); -extern bool PIOS_HMC5883_NewDataAvailable(void); -extern void PIOS_HMC5883_ReadMag(int16_t out[3]); -extern void PIOS_HMC5883_ReadID(uint8_t out[4]); -extern int32_t PIOS_HMC5883_Test(void); +struct pios_hmc5883_cfg { + const struct pios_exti_cfg * exti_cfg; /* Pointer to the EXTI configuration */ + uint8_t M_ODR; /* OUTPUT DATA RATE --> here below the relative define (See datasheet page 11 for more details) */ + uint8_t Meas_Conf; /* Measurement Configuration,: Normal, positive bias, or negative bias --> here below the relative define */ + uint8_t Gain; /* Gain Configuration, select the full scale --> here below the relative define (See datasheet page 11 for more details) */ + uint8_t Mode; + +}; + +/* Public Functions */ +extern void PIOS_HMC5883_Init(const struct pios_hmc5883_cfg * cfg); +extern bool PIOS_HMC5883_NewDataAvailable(void); +extern int32_t PIOS_HMC5883_ReadMag(int16_t out[3]); +extern uint8_t PIOS_HMC5883_ReadID(uint8_t out[4]); +extern int32_t PIOS_HMC5883_Test(void); +extern void PIOS_HMC5883_IRQHandler(); #endif /* PIOS_HMC5883_H */ /** diff --git a/flight/PiOS/inc/pios_i2c.h b/flight/PiOS/inc/pios_i2c.h index cd8a0ff22..b34acf9e6 100644 --- a/flight/PiOS/inc/pios_i2c.h +++ b/flight/PiOS/inc/pios_i2c.h @@ -48,7 +48,7 @@ struct pios_i2c_txn { uint8_t *buf; }; -#define I2C_LOG_DEPTH 5 +#define I2C_LOG_DEPTH 20 enum pios_i2c_error_type { PIOS_I2C_ERROR_EVENT, PIOS_I2C_ERROR_FSM, @@ -64,7 +64,8 @@ struct pios_i2c_fault_history { }; /* Public Functions */ -extern bool PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns); +extern int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns); +extern int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, void *callback); extern void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id); extern void PIOS_I2C_ER_IRQ_Handler(uint32_t i2c_id); extern void PIOS_I2C_GetDiagnostics(struct pios_i2c_fault_history * data, uint8_t * error_counts); diff --git a/flight/PiOS/inc/pios_i2c_priv.h b/flight/PiOS/inc/pios_i2c_priv.h index a10fe0603..8a2769321 100644 --- a/flight/PiOS/inc/pios_i2c_priv.h +++ b/flight/PiOS/inc/pios_i2c_priv.h @@ -32,12 +32,12 @@ struct pios_i2c_adapter_cfg { I2C_TypeDef *regs; + uint32_t remap; I2C_InitTypeDef init; uint32_t transfer_timeout_ms; struct stm32_gpio scl; struct stm32_gpio sda; - uint32_t remap; struct stm32_irq event; struct stm32_irq error; }; @@ -85,19 +85,23 @@ enum pios_i2c_adapter_magic { struct pios_i2c_adapter { enum pios_i2c_adapter_magic magic; const struct pios_i2c_adapter_cfg * cfg; - void (*callback) (uint8_t, uint8_t); #ifdef PIOS_INCLUDE_FREERTOS xSemaphoreHandle sem_busy; xSemaphoreHandle sem_ready; +#else + uint8_t busy; #endif bool bus_error; + bool nack; volatile enum i2c_adapter_state curr_state; const struct pios_i2c_txn *first_txn; const struct pios_i2c_txn *active_txn; const struct pios_i2c_txn *last_txn; + void (*callback) (); + uint8_t *active_byte; uint8_t *last_byte; }; diff --git a/flight/PiOS/inc/pios_iap.h b/flight/PiOS/inc/pios_iap.h index 1f67d651f..d9b41170b 100644 --- a/flight/PiOS/inc/pios_iap.h +++ b/flight/PiOS/inc/pios_iap.h @@ -17,9 +17,15 @@ /***************************************************************************************** * Public Definitions/Macros ****************************************************************************************/ -#define MAGIC_REG_1 BKP_DR1 -#define MAGIC_REG_2 BKP_DR2 -#define IAP_BOOTCOUNT BKP_DR3 +#if defined(STM32F4XX) +#define MAGIC_REG_1 RTC_BKP_DR1 +#define MAGIC_REG_2 RTC_BKP_DR2 +#define IAP_BOOTCOUNT RTC_BKP_DR3 +#else +#define MAGIC_REG_1 BKP_DR1 +#define MAGIC_REG_2 BKP_DR2 +#define IAP_BOOTCOUNT BKP_DR3 +#endif /**************************************************************************************** * Public Functions diff --git a/flight/PiOS/inc/pios_imu3000.h b/flight/PiOS/inc/pios_imu3000.h deleted file mode 100644 index 3302e59c9..000000000 --- a/flight/PiOS/inc/pios_imu3000.h +++ /dev/null @@ -1,126 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_IMU3000 IMU3000 Functions - * @brief Deals with the hardware interface to the 3-axis gyro - * @{ - * - * @file pios_imu3000.h - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @brief IMU3000 3-axis gyor function headers - * @see The GNU Public License (GPL) Version 3 - * - ****************************************************************************** - */ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_IMU3000_H -#define PIOS_IMU3000_H - -/* IMU3000 Addresses */ -#define PIOS_IMU3000_I2C_ADDR 0x69 -#define PIOS_IMU3000_I2C_READ_ADDR 0xD2 -#define PIOS_IMU3000_I2C_WRITE_ADDR 0xD3 -#define PIOS_IMU3000_X_MSB_OFFSET_REG 0x0C -#define PIOS_IMU3000_X_LSB_OFFSET_REG 0x0D -#define PIOS_IMU3000_Y_MSB_OFFSET_REG 0x0E -#define PIOS_IMU3000_Y_LSB_OFFSET_REG 0x0F -#define PIOS_IMU3000_Z_MSB_OFFSET_REG 0x10 -#define PIOS_IMU3000_Z_LSB_OFFSET_REG 0x11 -#define PIOS_IMU3000_FIFO_EN_REG 0x12 -#define PIOS_IMU3000_SMPLRT_DIV_REG 0X15 -#define PIOS_IMU3000_DLPF_CFG_REG 0X16 -#define PIOS_IMU3000_INT_CFG_REG 0x17 -#define PIOS_IMU3000_INT_STATUS_REG 0x1A -#define PIOS_IMU3000_TEMP_OUT_MSB 0x1B -#define PIOS_IMU3000_TEMP_OUT_LSB 0x1C -#define PIOS_IMU3000_GYRO_X_OUT_MSB 0x1D -#define PIOS_IMU3000_GYRO_X_OUT_LSB 0x1E -#define PIOS_IMU3000_GYRO_Y_OUT_MSB 0x1F -#define PIOS_IMU3000_GYRO_Y_OUT_LSB 0x20 -#define PIOS_IMU3000_GYRO_Z_OUT_MSB 0x21 -#define PIOS_IMU3000_GYRO_Z_OUT_LSB 0x22 -#define PIOS_IMU3000_FIFO_CNT_MSB 0x3A -#define PIOS_IMU3000_FIFO_CNT_LSB 0x3B -#define PIOS_IMU3000_FIFO_REG 0x3C -#define PIOS_IMU3000_USER_CTRL_REG 0x3D -#define PIOS_IMU3000_PWR_MGMT_REG 0x3E - -/* FIFO enable for storing different values */ -#define PIOS_IMU3000_FIFO_TEMP_OUT 0x80 -#define PIOS_IMU3000_FIFO_GYRO_X_OUT 0x40 -#define PIOS_IMU3000_FIFO_GYRO_Y_OUT 0x20 -#define PIOS_IMU3000_FIFO_GYRO_Z_OUT 0x10 -#define PIOS_IMU3000_FIFO_FOOTER 0x01 - -/* Gyro full-scale range */ -#define PIOS_IMU3000_SCALE_250_DEG 0x00 -#define PIOS_IMU3000_SCALE_500_DEG 0x01 -#define PIOS_IMU3000_SCALE_1000_DEG 0x02 -#define PIOS_IMU3000_SCALE_2000_DEG 0x03 - -/* Digital low-pass filter configuration */ -#define PIOS_IMU3000_LOWPASS_256_HZ 0x00 -#define PIOS_IMU3000_LOWPASS_188_HZ 0x01 -#define PIOS_IMU3000_LOWPASS_98_HZ 0x02 -#define PIOS_IMU3000_LOWPASS_42_HZ 0x03 -#define PIOS_IMU3000_LOWPASS_20_HZ 0x04 -#define PIOS_IMU3000_LOWPASS_10_HZ 0x05 -#define PIOS_IMU3000_LOWPASS_5_HZ 0x06 - -/* Interrupt Configuration */ -#define PIOS_IMU3000_INT_ACTL 0x80 -#define PIOS_IMU3000_INT_OPEN 0x40 -#define PIOS_IMU3000_INT_LATCH_EN 0x20 -#define PIOS_IMU3000_INT_CLR_ANYRD 0x10 -#define PIOS_IMU3000_INT_IMU_RDY 0x04 -#define PIOS_IMU3000_INT_DATA_RDY 0x01 - -/* Interrupt status */ -#define PIOS_IMU3000_INT_STATUS_FIFO_FULL 0x80 -#define PIOS_IMU3000_INT_STATUS_IMU_RDY 0X04 -#define PIOS_IMU3000_INT_STATUS_DATA_RDY 0X01 - -/* User control functionality */ -#define PIOS_IMU3000_USERCTL_FIFO_EN 0X40 -#define PIOS_IMU3000_USERCTL_FIFO_RST 0X02 -#define PIOS_IMU3000_USERCTL_GYRO_RST 0X01 - -/* Power management and clock selection */ -#define PIOS_IMU3000_PWRMGMT_IMU_RST 0X80 -#define PIOS_IMU3000_PWRMGMT_INTERN_CLK 0X00 -#define PIOS_IMU3000_PWRMGMT_PLL_X_CLK 0X01 -#define PIOS_IMU3000_PWRMGMT_PLL_Y_CLK 0X02 -#define PIOS_IMU3000_PWRMGMT_PLL_Z_CLK 0X03 -#define PIOS_IMU3000_PWRMGMT_STOP_CLK 0X07 - - -/* Public Functions */ -extern void PIOS_IMU3000_Init(void); -extern bool PIOS_IMU3000_NewDataAvailable(void); -extern void PIOS_IMU3000_ReadGyros(int16_t out[3]); -extern uint8_t PIOS_IMU3000_ReadID(); -extern uint8_t PIOS_IMU3000_Test(); - -#endif /* PIOS_IMU3000_H */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS/inc/pios_l3gd20.h b/flight/PiOS/inc/pios_l3gd20.h new file mode 100644 index 000000000..83b2070b6 --- /dev/null +++ b/flight/PiOS/inc/pios_l3gd20.h @@ -0,0 +1,151 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_L3GD20 L3GD20 Functions + * @brief Deals with the hardware interface to the 3-axis gyro + * @{ + * + * @file PIOS_L3GD20.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief L3GD20 3-axis gyor function headers + * @see The GNU Public License (GPL) Version 3 + * + ****************************************************************************** + */ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_L3GD20_H +#define PIOS_L3GD20_H + +#include "pios.h" + +/* L3GD20 Addresses */ +#define PIOS_L3GD20_WHOAMI 0x0F +#define PIOS_L3GD20_CTRL_REG1 0X20 +#define PIOS_L3GD20_CTRL_REG2 0X21 +#define PIOS_L3GD20_CTRL_REG3 0X22 +#define PIOS_L3GD20_CTRL_REG4 0X23 +#define PIOS_L3GD20_CTRL_REG5 0X24 +#define PIOS_L3GD20_REFERENCE 0X25 +#define PIOS_L3GD20_OUT_TEMP 0x26 +#define PIOS_L3GD20_STATUS_REG 0x27 +#define PIOS_L3GD20_GYRO_X_OUT_LSB 0x28 +#define PIOS_L3GD20_GYRO_X_OUT_MSB 0x29 +#define PIOS_L3GD20_GYRO_Y_OUT_LSB 0x2A +#define PIOS_L3GD20_GYRO_Y_OUT_MSB 0x2B +#define PIOS_L3GD20_GYRO_Z_OUT_LSB 0x2C +#define PIOS_L3GD20_GYRO_Z_OUT_MSB 0x2D +#define PIOS_L3GD20_FIFO_CTRL_REG 0x2E +#define PIOS_L3GD20_FIFO_SRC_REG 0x2F +#define PIOS_L3GD20_INT1_CFG 0x30 +#define PIOS_L3GD20_INT1_SRC 0x31 +#define PIOS_L3GD20_INT1_TSH_XH 0x32 +#define PIOS_L3GD20_INT1_TSH_XL 0x33 +#define PIOS_L3GD20_INT1_TSH_YH 0x34 +#define PIOS_L3GD20_INT1_TSH_YL 0x35 +#define PIOS_L3GD20_INT1_TSH_ZH 0x36 +#define PIOS_L3GD20_INT1_TSH_ZL 0x37 +#define PIOS_L3GD20_INT1_DURATION 0x38 + +/* Ctrl1 flags */ +#define PIOS_L3GD20_CTRL1_FASTEST 0xF0 +#define PIOS_L3GD20_CTRL1_380HZ_100HZ 0xB0 +#define PIOS_L3GD20_CTRL1_PD 0x08 +#define PIOS_L3GD20_CTRL1_ZEN 0x04 +#define PIOS_L3GD20_CTRL1_YEN 0x02 +#define PIOS_L3GD20_CTRL1_XEN 0x01 + +/* FIFO enable for storing different values */ +#define PIOS_L3GD20_FIFO_TEMP_OUT 0x80 +#define PIOS_L3GD20_FIFO_GYRO_X_OUT 0x40 +#define PIOS_L3GD20_FIFO_GYRO_Y_OUT 0x20 +#define PIOS_L3GD20_FIFO_GYRO_Z_OUT 0x10 +#define PIOS_L3GD20_ACCEL_OUT 0x08 + +/* Interrupt Configuration */ +#define PIOS_L3GD20_INT_ACTL 0x80 +#define PIOS_L3GD20_INT_OPEN 0x40 +#define PIOS_L3GD20_INT_LATCH_EN 0x20 +#define PIOS_L3GD20_INT_CLR_ANYRD 0x10 + +#define PIOS_L3GD20_INTEN_OVERFLOW 0x10 +#define PIOS_L3GD20_INTEN_DATA_RDY 0x01 + +/* Interrupt status */ +#define PIOS_L3GD20_INT_STATUS_FIFO_FULL 0x80 +#define PIOS_L3GD20_INT_STATUS_IMU_RDY 0X04 +#define PIOS_L3GD20_INT_STATUS_DATA_RDY 0X01 + +/* User control functionality */ +#define PIOS_L3GD20_USERCTL_FIFO_EN 0X40 +#define PIOS_L3GD20_USERCTL_FIFO_RST 0X02 +#define PIOS_L3GD20_USERCTL_GYRO_RST 0X01 + +/* Power management and clock selection */ +#define PIOS_L3GD20_PWRMGMT_IMU_RST 0X80 +#define PIOS_L3GD20_PWRMGMT_INTERN_CLK 0X00 +#define PIOS_L3GD20_PWRMGMT_PLL_X_CLK 0X01 +#define PIOS_L3GD20_PWRMGMT_PLL_Y_CLK 0X02 +#define PIOS_L3GD20_PWRMGMT_PLL_Z_CLK 0X03 +#define PIOS_L3GD20_PWRMGMT_STOP_CLK 0X07 + +enum pios_l3gd20_range { + PIOS_L3GD20_SCALE_250_DEG = 0x00, + PIOS_L3GD20_SCALE_500_DEG = 0x10, + PIOS_L3GD20_SCALE_2000_DEG = 0x3 +}; + +enum pios_l3gd20_filter { + PIOS_L3GD20_LOWPASS_256_HZ = 0x00, + PIOS_L3GD20_LOWPASS_188_HZ = 0x01, + PIOS_L3GD20_LOWPASS_98_HZ = 0x02, + PIOS_L3GD20_LOWPASS_42_HZ = 0x03, + PIOS_L3GD20_LOWPASS_20_HZ = 0x04, + PIOS_L3GD20_LOWPASS_10_HZ = 0x05, + PIOS_L3GD20_LOWPASS_5_HZ = 0x06 +}; + +struct pios_l3gd20_data { + int16_t gyro_x; + int16_t gyro_y; + int16_t gyro_z; + int16_t temperature; +}; + +struct pios_l3gd20_cfg { + const struct pios_exti_cfg * exti_cfg; /* Pointer to the EXTI configuration */ + + enum pios_l3gd20_range range; +}; + +/* Public Functions */ +extern int32_t PIOS_L3GD20_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_l3gd20_cfg * cfg); +extern xQueueHandle PIOS_L3GD20_GetQueue(); +extern int32_t PIOS_L3GD20_ReadGyros(struct pios_l3gd20_data * buffer); +extern int32_t PIOS_L3GD20_SetRange(enum pios_l3gd20_range range); +extern float PIOS_L3GD20_GetScale(); +extern int32_t PIOS_L3GD20_ReadID(); +extern uint8_t PIOS_L3GD20_Test(); +extern void PIOS_L3GD20_IRQHandler(); + +#endif /* PIOS_L3GD20_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_mpu6000.h b/flight/PiOS/inc/pios_mpu6000.h new file mode 100644 index 000000000..2a301bc4c --- /dev/null +++ b/flight/PiOS/inc/pios_mpu6000.h @@ -0,0 +1,166 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_MPU6000 MPU6000 Functions + * @brief Deals with the hardware interface to the 3-axis gyro + * @{ + * + * @file PIOS_MPU6000.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief MPU6000 3-axis gyor function headers + * @see The GNU Public License (GPL) Version 3 + * + ****************************************************************************** + */ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_MPU6000_H +#define PIOS_MPU6000_H + +#include "pios.h" + +/* MPU6000 Addresses */ +#define PIOS_MPU6000_SMPLRT_DIV_REG 0X19 +#define PIOS_MPU6000_DLPF_CFG_REG 0X1A +#define PIOS_MPU6000_GYRO_CFG_REG 0X1B +#define PIOS_MPU6000_ACCEL_CFG_REG 0X1C +#define PIOS_MPU6000_FIFO_EN_REG 0x23 +#define PIOS_MPU6000_INT_CFG_REG 0x37 +#define PIOS_MPU6000_INT_EN_REG 0x38 +#define PIOS_MPU6000_INT_STATUS_REG 0x3A +#define PIOS_MPU6000_ACCEL_X_OUT_MSB 0x3B +#define PIOS_MPU6000_ACCEL_X_OUT_LSB 0x3C +#define PIOS_MPU6000_ACCEL_Y_OUT_MSB 0x3D +#define PIOS_MPU6000_ACCEL_Y_OUT_LSB 0x3E +#define PIOS_MPU6000_ACCEL_Z_OUT_MSB 0x3F +#define PIOS_MPU6000_ACCEL_Z_OUT_LSB 0x40 +#define PIOS_MPU6000_TEMP_OUT_MSB 0x41 +#define PIOS_MPU6000_TEMP_OUT_LSB 0x42 +#define PIOS_MPU6000_GYRO_X_OUT_MSB 0x43 +#define PIOS_MPU6000_GYRO_X_OUT_LSB 0x44 +#define PIOS_MPU6000_GYRO_Y_OUT_MSB 0x45 +#define PIOS_MPU6000_GYRO_Y_OUT_LSB 0x46 +#define PIOS_MPU6000_GYRO_Z_OUT_MSB 0x47 +#define PIOS_MPU6000_GYRO_Z_OUT_LSB 0x48 +#define PIOS_MPU6000_USER_CTRL_REG 0x6A +#define PIOS_MPU6000_PWR_MGMT_REG 0x6B +#define PIOS_MPU6000_FIFO_CNT_MSB 0x72 +#define PIOS_MPU6000_FIFO_CNT_LSB 0x73 +#define PIOS_MPU6000_FIFO_REG 0x74 +#define PIOS_MPU6000_WHOAMI 0x75 + +/* FIFO enable for storing different values */ +#define PIOS_MPU6000_FIFO_TEMP_OUT 0x80 +#define PIOS_MPU6000_FIFO_GYRO_X_OUT 0x40 +#define PIOS_MPU6000_FIFO_GYRO_Y_OUT 0x20 +#define PIOS_MPU6000_FIFO_GYRO_Z_OUT 0x10 +#define PIOS_MPU6000_ACCEL_OUT 0x08 + +/* Interrupt Configuration */ +#define PIOS_MPU6000_INT_ACTL 0x80 +#define PIOS_MPU6000_INT_OPEN 0x40 +#define PIOS_MPU6000_INT_LATCH_EN 0x20 +#define PIOS_MPU6000_INT_CLR_ANYRD 0x10 + +#define PIOS_MPU6000_INTEN_OVERFLOW 0x10 +#define PIOS_MPU6000_INTEN_DATA_RDY 0x01 + +/* Interrupt status */ +#define PIOS_MPU6000_INT_STATUS_FIFO_FULL 0x80 +#define PIOS_MPU6000_INT_STATUS_IMU_RDY 0X04 +#define PIOS_MPU6000_INT_STATUS_DATA_RDY 0X01 + +/* User control functionality */ +#define PIOS_MPU6000_USERCTL_FIFO_EN 0X40 +#define PIOS_MPU6000_USERCTL_FIFO_RST 0X02 +#define PIOS_MPU6000_USERCTL_GYRO_RST 0X01 + +/* Power management and clock selection */ +#define PIOS_MPU6000_PWRMGMT_IMU_RST 0X80 +#define PIOS_MPU6000_PWRMGMT_INTERN_CLK 0X00 +#define PIOS_MPU6000_PWRMGMT_PLL_X_CLK 0X01 +#define PIOS_MPU6000_PWRMGMT_PLL_Y_CLK 0X02 +#define PIOS_MPU6000_PWRMGMT_PLL_Z_CLK 0X03 +#define PIOS_MPU6000_PWRMGMT_STOP_CLK 0X07 + +enum pios_mpu6000_range { + PIOS_MPU6000_SCALE_250_DEG = 0x00, + PIOS_MPU6000_SCALE_500_DEG = 0x08, + PIOS_MPU6000_SCALE_1000_DEG = 0x10, + PIOS_MPU6000_SCALE_2000_DEG = 0x18 +}; + +enum pios_mpu6000_filter { + PIOS_MPU6000_LOWPASS_256_HZ = 0x00, + PIOS_MPU6000_LOWPASS_188_HZ = 0x01, + PIOS_MPU6000_LOWPASS_98_HZ = 0x02, + PIOS_MPU6000_LOWPASS_42_HZ = 0x03, + PIOS_MPU6000_LOWPASS_20_HZ = 0x04, + PIOS_MPU6000_LOWPASS_10_HZ = 0x05, + PIOS_MPU6000_LOWPASS_5_HZ = 0x06 +}; + +enum pios_mpu6000_accel_range { + PIOS_MPU6000_ACCEL_2G = 0x00, + PIOS_MPU6000_ACCEL_4G = 0x08, + PIOS_MPU6000_ACCEL_8G = 0x10, + PIOS_MPU6000_ACCEL_16G = 0x18 +}; + +struct pios_mpu6000_data { + int16_t gyro_x; + int16_t gyro_y; + int16_t gyro_z; +#if defined(PIOS_MPU6000_ACCEL) + int16_t accel_x; + int16_t accel_y; + int16_t accel_z; +#endif /* PIOS_MPU6000_ACCEL */ + int16_t temperature; +}; + +struct pios_mpu6000_cfg { + const struct pios_exti_cfg * exti_cfg; /* Pointer to the EXTI configuration */ + + uint8_t Fifo_store; /* FIFO storage of different readings (See datasheet page 31 for more details) */ + uint8_t Smpl_rate_div; /* Sample rate divider to use (See datasheet page 32 for more details) */ + uint8_t interrupt_cfg; /* Interrupt configuration (See datasheet page 35 for more details) */ + uint8_t interrupt_en; /* Interrupt configuration (See datasheet page 35 for more details) */ + uint8_t User_ctl; /* User control settings (See datasheet page 41 for more details) */ + uint8_t Pwr_mgmt_clk; /* Power management and clock selection (See datasheet page 32 for more details) */ + enum pios_mpu6000_accel_range accel_range; + enum pios_mpu6000_range gyro_range; + enum pios_mpu6000_filter filter; +}; + +/* Public Functions */ +extern int32_t PIOS_MPU6000_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_mpu6000_cfg * new_cfg); +extern xQueueHandle PIOS_MPU6000_GetQueue(); +extern int32_t PIOS_MPU6000_ReadGyros(struct pios_mpu6000_data * buffer); +extern int32_t PIOS_MPU6000_ReadID(); +extern uint8_t PIOS_MPU6000_Test(); +extern float PIOS_MPU6000_GetScale(); +extern float PIOS_MPU6000_GetAccelScale(); +extern void PIOS_MPU6000_IRQHandler(void); + +#endif /* PIOS_MPU6000_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_ms5611.h b/flight/PiOS/inc/pios_ms5611.h new file mode 100644 index 000000000..7068988c4 --- /dev/null +++ b/flight/PiOS/inc/pios_ms5611.h @@ -0,0 +1,83 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_MS5611 MS5611 Functions + * @brief Hardware functions to deal with the altitude pressure sensor + * @{ + * + * @file pios_ms5611.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief MS5611 functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_MS5611_H +#define PIOS_MS5611_H + +#include + +/* BMP085 Addresses */ +#define MS5611_I2C_ADDR 0x77 +#define MS5611_RESET 0x1E +#define MS5611_CALIB_ADDR 0xA2 /* First sample is factory stuff */ +#define MS5611_CALIB_LEN 16 +#define MS5611_ADC_READ 0x00 +#define MS5611_PRES_ADDR 0x40 +#define MS5611_TEMP_ADDR 0x50 +#define MS5611_ADC_MSB 0xF6 +#define MS5611_P0 101.3250f + +/* Local Types */ +typedef struct { + uint16_t C[6]; +} MS5611CalibDataTypeDef; + +typedef enum { + PressureConv, + TemperatureConv +} ConversionTypeTypeDef; + +struct pios_ms5611_cfg { + uint32_t oversampling; +}; + +enum pios_ms5611_osr { + MS5611_OSR_256 = 0, + MS5611_OSR_512 = 2, + MS5611_OSR_1024 = 4, + MS5611_OSR_2048 = 6, + MS5611_OSR_4096 = 8, +}; + +/* Public Functions */ +extern void PIOS_MS5611_Init(const struct pios_ms5611_cfg * cfg, int32_t i2c_device); +extern int32_t PIOS_MS5611_StartADC(ConversionTypeTypeDef Type); +extern int32_t PIOS_MS5611_ReadADC(void); +extern float PIOS_MS5611_GetTemperature(void); +extern float PIOS_MS5611_GetPressure(void); +extern int32_t PIOS_MS5611_Test(); +extern int32_t PIOS_MS5611_GetDelay(); + +#endif /* PIOS_MS5611_H */ + +/** + * @} + * @} + */ diff --git a/flight/AHRS/ahrs_timer.c b/flight/PiOS/inc/pios_rfm22b.h similarity index 56% rename from flight/AHRS/ahrs_timer.c rename to flight/PiOS/inc/pios_rfm22b.h index d30a6c9f6..aa00a835e 100644 --- a/flight/AHRS/ahrs_timer.c +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -1,19 +1,16 @@ /** ****************************************************************************** - * @addtogroup AHRS AHRS - * @brief The AHRS Modules perform + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_RFM22B Radio Functions + * @brief PIOS interface for RFM22B Radio + * @{ * - * @{ - * @addtogroup AHRS_TIMER AHRS Timer - * @brief Sets up a simple timer that can be polled to estimate idle time - * @{ - * - * - * @file ahrs.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief INSGPS Test Program + * @file pios_rfm22b.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief RFM22B functions header. * @see The GNU Public License (GPL) Version 3 - * + * *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -31,31 +28,28 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "ahrs_timer.h" +#ifndef PIOS_RFM22B_H +#define PIOS_RFM22B_H -void timer_start() -{ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_BKP | RCC_APB1Periph_PWR, - ENABLE); - PWR_BackupAccessCmd(ENABLE); +/* Global Types */ +struct pios_rfm22b_cfg { + uint32_t frequencyHz; + uint32_t minFrequencyHz; + uint32_t maxFrequencyHz; + uint8_t RFXtalCap; + uint32_t maxRFBandwidth; + uint8_t maxTxPower; +}; - RCC_RTCCLKConfig(RCC_RTCCLKSource_HSE_Div128); - RCC_RTCCLKCmd(ENABLE); - RTC_WaitForLastTask(); - RTC_WaitForSynchro(); - RTC_WaitForLastTask(); - RTC_SetPrescaler(0); // counting at 8e6 / 128 - RTC_WaitForLastTask(); - RTC_SetCounter(0); - RTC_WaitForLastTask(); -} +/* Public Functions */ +extern int32_t PIOS_RFM22B_Init(uint32_t *rfb22b_id, const struct pios_rfm22b_cfg *cfg); +extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); +extern int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id); +extern int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id); -uint32_t timer_count() -{ - return RTC_GetCounter(); -} +#endif /* PIOS_RFM22B_H */ -uint32_t timer_rate() -{ - return TIMER_RATE; -} +/** + * @} + * @} + */ diff --git a/flight/PipXtreme/inc/rfm22b.h b/flight/PiOS/inc/pios_rfm22b_priv.h similarity index 95% rename from flight/PipXtreme/inc/rfm22b.h rename to flight/PiOS/inc/pios_rfm22b_priv.h index 25ef47e96..792915546 100644 --- a/flight/PipXtreme/inc/rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b_priv.h @@ -1,9 +1,14 @@ /** ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_RFM22B Radio Functions + * @brief PIOS interface for RFM22B Radio + * @{ * - * @file rfm22b.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RF Module hardware layer + * @file pios_rfm22b_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief RFM22B private definitions. * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -23,10 +28,14 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef __RFM22B_H__ -#define __RFM22B_H__ +#ifndef PIOS_RFM22B_PRIV_H +#define PIOS_RFM22B_PRIV_H -#include "stdint.h" +#include +#include "fifo_buffer.h" +#include "pios_rfm22b.h" + +extern const struct pios_com_driver pios_rfm22b_com_driver; // ************************************ @@ -386,11 +395,13 @@ enum { RX_SCAN_SPECTRUM = 0, #define RFM22_header_cntl1_bcen_none 0x00 // No broadcast address enable. #define RFM22_header_cntl1_bcen_0 0x10 // Broadcast address enable for header byte 0. #define RFM22_header_cntl1_bcen_1 0x20 // Broadcast address enable for header byte 1. -#define RFM22_header_cntl1_bcen_01 0x30 // Broadcast address enable for header bytes 0 & 1. +#define RFM22_header_cntl1_bcen_2 0x40 // Broadcast address enable for header byte 2. +#define RFM22_header_cntl1_bcen_3 0x80 // Broadcast address enable for header byte 3. #define RFM22_header_cntl1_hdch_none 0x00 // No Received Header check #define RFM22_header_cntl1_hdch_0 0x01 // Received Header check for byte 0. #define RFM22_header_cntl1_hdch_1 0x02 // Received Header check for byte 1. -#define RFM22_header_cntl1_hdch_01 0x03 // Received Header check for bytes 0 & 1. +#define RFM22_header_cntl1_hdch_2 0x04 // Received Header check for byte 2. +#define RFM22_header_cntl1_hdch_3 0x08 // Received Header check for byte 3. #define RFM22_header_control2 0x33 // R/W #define RFM22_header_cntl2_prealen 0x01 // MSB of Preamble Length. See register Preamble Length. @@ -598,9 +609,9 @@ uint32_t rfm22_getDatarate(void); void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode); -int16_t rfm22_getRSSI(void); +int8_t rfm22_getRSSI(void); -int16_t rfm22_receivedRSSI(void); +int8_t rfm22_receivedRSSI(void); int32_t rfm22_receivedAFCHz(void); uint16_t rfm22_receivedLength(void); uint8_t * rfm22_receivedPointer(void); @@ -628,7 +639,6 @@ bool rfm22_channelIsClear(void); bool rfm22_txReady(void); void rfm22_1ms_tick(void); -void rfm22_process(void); void rfm22_TxDataByte_SetCallback(t_rfm22_TxDataByteCallback new_function); void rfm22_RxData_SetCallback(t_rfm22_RxDataCallback new_function); @@ -636,8 +646,11 @@ void rfm22_RxData_SetCallback(t_rfm22_RxDataCallback new_function); int rfm22_init_scan_spectrum(uint32_t min_frequency_hz, uint32_t max_frequency_hz); int rfm22_init_tx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz); int rfm22_init_rx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz); -int rfm22_init_normal(uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size); +int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size); -// ************************************ +#endif /* PIOS_RFM22B_PRIV_H */ -#endif +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_spi.h b/flight/PiOS/inc/pios_spi.h index e34b7e4c9..759855c13 100644 --- a/flight/PiOS/inc/pios_spi.h +++ b/flight/PiOS/inc/pios_spi.h @@ -44,13 +44,15 @@ typedef enum { /* Public Functions */ extern int32_t PIOS_SPI_SetClockSpeed(uint32_t spi_id, SPIPrescalerTypeDef spi_prescaler); -extern int32_t PIOS_SPI_RC_PinSet(uint32_t spi_id, uint8_t pin_value); +extern int32_t PIOS_SPI_RC_PinSet(uint32_t spi_id, uint32_t slave_id, uint8_t pin_value); extern int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b); extern int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback); extern int32_t PIOS_SPI_Busy(uint32_t spi_id); extern int32_t PIOS_SPI_ClaimBus(uint32_t spi_id); +extern int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id); extern int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id); extern void PIOS_SPI_IRQ_Handler(uint32_t spi_id); +extern void PIOS_SPI_SetPrescalar(uint32_t spi_id, uint32_t prescalar); #endif /* PIOS_SPI_H */ diff --git a/flight/PiOS/inc/pios_spi_priv.h b/flight/PiOS/inc/pios_spi_priv.h index 71468b63a..fd8a6a4e5 100644 --- a/flight/PiOS/inc/pios_spi_priv.h +++ b/flight/PiOS/inc/pios_spi_priv.h @@ -36,13 +36,15 @@ struct pios_spi_cfg { SPI_TypeDef *regs; + uint32_t remap; /* GPIO_Remap_* or GPIO_AF_* */ SPI_InitTypeDef init; bool use_crc; struct stm32_dma dma; - struct stm32_gpio ssel; struct stm32_gpio sclk; struct stm32_gpio miso; struct stm32_gpio mosi; + uint32_t slave_count; + struct stm32_gpio ssel[]; }; struct pios_spi_dev { @@ -52,6 +54,8 @@ struct pios_spi_dev { uint8_t rx_dummy_byte; #if defined(PIOS_INCLUDE_FREERTOS) xSemaphoreHandle busy; +#else + uint8_t busy; #endif }; diff --git a/flight/PiOS/inc/pios_stm32.h b/flight/PiOS/inc/pios_stm32.h index 4e63d6937..f9ca892e2 100644 --- a/flight/PiOS/inc/pios_stm32.h +++ b/flight/PiOS/inc/pios_stm32.h @@ -32,6 +32,7 @@ #define PIOS_STM32_H struct stm32_irq { + void (*handler) (uint32_t); uint32_t flags; NVIC_InitTypeDef init; }; @@ -41,12 +42,16 @@ struct stm32_exti { }; struct stm32_dma_chan { +#if defined(STM32F2XX) || defined(STM32F4XX) + DMA_Stream_TypeDef *channel; +#else DMA_Channel_TypeDef *channel; +#endif DMA_InitTypeDef init; }; struct stm32_dma { - uint32_t ahb_clk; + uint32_t ahb_clk; /* ignored on STM32F2XX */ struct stm32_irq irq; struct stm32_dma_chan rx; struct stm32_dma_chan tx; @@ -55,6 +60,7 @@ struct stm32_dma { struct stm32_gpio { GPIO_TypeDef *gpio; GPIO_InitTypeDef init; + uint8_t pin_source; }; /** diff --git a/flight/PiOS/inc/pios_sys.h b/flight/PiOS/inc/pios_sys.h index 9407fa720..7f183a892 100644 --- a/flight/PiOS/inc/pios_sys.h +++ b/flight/PiOS/inc/pios_sys.h @@ -32,12 +32,15 @@ #ifndef PIOS_SYS_H #define PIOS_SYS_H +#define PIOS_SYS_SERIAL_NUM_BINARY_LEN 12 +#define PIOS_SYS_SERIAL_NUM_ASCII_LEN (PIOS_SYS_SERIAL_NUM_BINARY_LEN * 2) + /* Public Functions */ extern void PIOS_SYS_Init(void); extern int32_t PIOS_SYS_Reset(void); extern uint32_t PIOS_SYS_getCPUFlashSize(void); -extern int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array); -extern int32_t PIOS_SYS_SerialNumberGet(char *str); +extern int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t array[PIOS_SYS_SERIAL_NUM_BINARY_LEN]); +extern int32_t PIOS_SYS_SerialNumberGet(char str[PIOS_SYS_SERIAL_NUM_ASCII_LEN+1]); #endif /* PIOS_SYS_H */ diff --git a/flight/PiOS/inc/pios_usb.h b/flight/PiOS/inc/pios_usb.h index 1c6347a0d..ad63ae3a8 100644 --- a/flight/PiOS/inc/pios_usb.h +++ b/flight/PiOS/inc/pios_usb.h @@ -30,9 +30,12 @@ #ifndef PIOS_USB_H #define PIOS_USB_H +#include + /* Global functions */ extern int32_t PIOS_USB_Reenumerate(); -extern int32_t PIOS_USB_ChangeConnectionState(uint32_t Connected); +extern int32_t PIOS_USB_ChangeConnectionState(bool connected); +extern bool PIOS_USB_CableConnected(uint8_t id); extern bool PIOS_USB_CheckAvailable(uint8_t id); #endif /* PIOS_USB_H */ diff --git a/flight/PiOS/inc/pios_usb_cdc_priv.h b/flight/PiOS/inc/pios_usb_cdc_priv.h index 74d6e347d..b87bd50cc 100644 --- a/flight/PiOS/inc/pios_usb_cdc_priv.h +++ b/flight/PiOS/inc/pios_usb_cdc_priv.h @@ -31,8 +31,6 @@ #ifndef PIOS_USB_CDC_PRIV_H #define PIOS_USB_CDC_PRIV_H -#include "usb_core.h" /* RESULT */ - struct pios_usb_cdc_cfg { uint8_t ctrl_if; uint8_t ctrl_tx_ep; @@ -46,10 +44,6 @@ extern const struct pios_com_driver pios_usb_cdc_com_driver; extern int32_t PIOS_USB_CDC_Init(uint32_t * usbcdc_id, const struct pios_usb_cdc_cfg * cfg, uint32_t lower_id); -extern const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length); -extern RESULT PIOS_USB_CDC_SetControlLineState(void); -extern RESULT PIOS_USB_CDC_SetLineCoding(void); - #endif /* PIOS_USB_CDC_PRIV_H */ /** diff --git a/flight/PiOS/inc/pios_usb_defs.h b/flight/PiOS/inc/pios_usb_defs.h index 2e63a8fa4..be827a494 100644 --- a/flight/PiOS/inc/pios_usb_defs.h +++ b/flight/PiOS/inc/pios_usb_defs.h @@ -219,6 +219,57 @@ struct usb_endpoint_desc { uint8_t bInterval; } __attribute__((packed)); +struct usb_setup_request { + uint8_t bmRequestType; + uint8_t bRequest; + uint16_t wValue; + uint16_t wIndex; + uint16_t wLength; +} __attribute__((packed)); + +#define USB_REQ_TYPE_STANDARD 0x00 +#define USB_REQ_TYPE_CLASS 0x20 +#define USB_REQ_TYPE_VENDOR 0x40 +#define USB_REQ_TYPE_MASK 0x60 + +#define USB_REQ_RECIPIENT_DEVICE 0x00 +#define USB_REQ_RECIPIENT_INTERFACE 0x01 +#define USB_REQ_RECIPIENT_ENDPOINT 0x02 +#define USB_REQ_RECIPIENT_MASK 0x03 + +enum usb_standard_requests { + USB_REQ_GET_STATUS = 0x00, + USB_REQ_CLEAR_FEATURE = 0x01, + /* what is 0x02? */ + USB_REQ_SET_FEATURE = 0x03, + /* what is 0x04? */ + USB_REQ_SET_ADDRESS = 0x05, + USB_REQ_GET_DESCRIPTOR = 0x06, + USB_REQ_SET_DESCRIPTOR = 0x07, + USB_REQ_GET_CONFIGURATION = 0x08, + USB_REQ_SET_CONFIGURATION = 0x09, + USB_REQ_GET_INTERFACE = 0x0A, + USB_REQ_SET_INTERFACE = 0x0B, + USB_REQ_SYNCH_FRAME = 0x0C, +}; + +enum usb_hid_requests { + USB_HID_REQ_GET_REPORT = 0x01, + USB_HID_REQ_GET_IDLE = 0x02, + USB_HID_REQ_GET_PROTOCOL = 0x03, + /* 0x04-0x08 Reserved */ + USB_HID_REQ_SET_REPORT = 0x09, + USB_HID_REQ_SET_IDLE = 0x0A, + USB_HID_REQ_SET_PROTOCOL = 0x0B, +}; + +enum usb_cdc_requests { + USB_CDC_REQ_SET_LINE_CODING = 0x20, + USB_CDC_REQ_GET_LINE_CODING = 0x21, + + USB_CDC_REQ_SET_CONTROL_LINE_STATE = 0x23, +}; + struct usb_cdc_header_func_desc { uint8_t bLength; uint8_t bDescriptorType; @@ -249,7 +300,7 @@ struct usb_cdc_union_func_desc { uint8_t bSlaveInterface; } __attribute__((packed)); -#define USB_LANGID_ENGLISH_UK 0x0809 +#define USB_LANGID_ENGLISH_US 0x0409 struct usb_string_langid { uint8_t bLength; @@ -301,6 +352,10 @@ enum usb_product_ids { USB_PRODUCT_ID_OPENPILOT_MAIN = 0x415A, USB_PRODUCT_ID_COPTERCONTROL = 0x415B, USB_PRODUCT_ID_PIPXTREME = 0x415C, + USB_PRODUCT_ID_CC3D = 0x415D, + USB_PRODUCT_ID_REVOLUTION = 0x415E, + USB_PRODUCT_ID_OSD = 0x4194, + USB_PRODUCT_ID_SPARE = 0x4195, } __attribute__((packed)); enum usb_op_board_ids { @@ -308,6 +363,7 @@ enum usb_op_board_ids { /* Board ID 2 may be unused or AHRS */ USB_OP_BOARD_ID_PIPXTREME = 3, USB_OP_BOARD_ID_COPTERCONTROL = 4, + USB_OP_BOARD_ID_REVOLUTION = 5, } __attribute__((packed)); enum usb_op_board_modes { diff --git a/flight/PiOS/inc/pios_usb_hid.h b/flight/PiOS/inc/pios_usb_hid.h index 7a7409631..2f7a1d598 100644 --- a/flight/PiOS/inc/pios_usb_hid.h +++ b/flight/PiOS/inc/pios_usb_hid.h @@ -31,10 +31,13 @@ #define PIOS_USB_HID_H /* Global functions */ -extern int32_t PIOS_USB_HID_Reenumerate(); +extern int32_t PIOS_USB_HID_Reenumerate(void); extern int32_t PIOS_USB_HID_ChangeConnectionState(uint32_t Connected); extern bool PIOS_USB_HID_CheckAvailable(uint8_t id); +extern void PIOS_USB_HID_RegisterHidDescriptor(const uint8_t * desc, uint16_t length); +extern void PIOS_USB_HID_RegisterHidReport(const uint8_t * desc, uint16_t length); + #endif /* PIOS_USB_HID_H */ /** diff --git a/flight/PiOS/inc/pios_usb_hid_priv.h b/flight/PiOS/inc/pios_usb_hid_priv.h index ac638cd54..fba585c18 100644 --- a/flight/PiOS/inc/pios_usb_hid_priv.h +++ b/flight/PiOS/inc/pios_usb_hid_priv.h @@ -31,8 +31,6 @@ #ifndef PIOS_USB_HID_PRIV_H #define PIOS_USB_HID_PRIV_H -#include "usb_core.h" /* RESULT */ - struct pios_usb_hid_cfg { uint8_t data_if; uint8_t data_rx_ep; diff --git a/flight/PiOS/inc/pios_usb_hid_pwr.h b/flight/PiOS/inc/pios_usb_hid_pwr.h index c44f4164c..614344437 100644 --- a/flight/PiOS/inc/pios_usb_hid_pwr.h +++ b/flight/PiOS/inc/pios_usb_hid_pwr.h @@ -17,6 +17,8 @@ #ifndef __USB_PWR_H #define __USB_PWR_H +#include "usb_core.h" + /* Includes ------------------------------------------------------------------*/ /* Exported types ------------------------------------------------------------*/ typedef enum _RESUME_STATE { diff --git a/flight/PiOS/inc/pios_usb_priv.h b/flight/PiOS/inc/pios_usb_priv.h index dd3f949ee..6f7edf652 100644 --- a/flight/PiOS/inc/pios_usb_priv.h +++ b/flight/PiOS/inc/pios_usb_priv.h @@ -36,6 +36,7 @@ struct pios_usb_cfg { struct stm32_irq irq; + struct stm32_gpio vsense; }; extern int32_t PIOS_USB_Init(uint32_t * usb_id, const struct pios_usb_cfg * cfg); diff --git a/flight/PipXtreme/inc/api_config.h b/flight/PiOS/inc/pios_usb_util.h similarity index 68% rename from flight/PipXtreme/inc/api_config.h rename to flight/PiOS/inc/pios_usb_util.h index 5fcc2e064..114cd9a70 100644 --- a/flight/PipXtreme/inc/api_config.h +++ b/flight/PiOS/inc/pios_usb_util.h @@ -1,9 +1,14 @@ /** ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_UTIL USB utility functions + * @brief USB utility functions + * @{ * - * @file api_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RF Module hardware layer + * @file pios_usb_util.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief USB utility functions * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -23,18 +28,11 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef __API_CONFIG_H__ -#define __API_CONFIG_H__ +#ifndef PIOS_USB_UTIL_H +#define PIOS_USB_UTIL_H -#include "stdint.h" +#include /* uint8_t */ -// ***************************************************************************** +uint8_t * PIOS_USB_UTIL_AsciiToUtf8(uint8_t * dst, uint8_t * src, uint16_t srclen); -void apiconfig_1ms_tick(void); -void apiconfig_process(void); - -void apiconfig_init(void); - -// ***************************************************************************** - -#endif +#endif /* PIOS_USB_UTIL_H */ diff --git a/flight/PiOS/inc/pios_usbhook.h b/flight/PiOS/inc/pios_usbhook.h index f005a6fa1..d6ca8648f 100644 --- a/flight/PiOS/inc/pios_usbhook.h +++ b/flight/PiOS/inc/pios_usbhook.h @@ -31,21 +31,14 @@ #ifndef PIOS_USBHOOK_H #define PIOS_USBHOOK_H -typedef enum _HID_REQUESTS { - GET_REPORT = 1, - GET_IDLE, - GET_PROTOCOL, +#include +#include +#include "pios_usb_defs.h" /* usb_setup_request */ - SET_REPORT = 9, - SET_IDLE, - SET_PROTOCOL -} HID_REQUESTS; - -typedef enum CDC_REQUESTS { - SET_LINE_CODING = 0x20, - GET_LINE_CODING = 0x21, - SET_CONTROL_LINE_STATE = 0x23, -} CDC_REQUESTS; +struct pios_usbhook_descriptor { + const uint8_t * descriptor; + uint16_t length; +}; enum usb_string_desc { USB_STRING_DESC_LANG = 0, @@ -57,8 +50,29 @@ enum usb_string_desc { extern void PIOS_USBHOOK_RegisterDevice(const uint8_t * desc, uint16_t desc_size); extern void PIOS_USBHOOK_RegisterConfig(uint8_t config_id, const uint8_t * desc, uint16_t desc_size); extern void PIOS_USBHOOK_RegisterString(enum usb_string_desc string_id, const uint8_t * desc, uint16_t desc_size); -extern void PIOS_USBHOOK_RegisterHidInterface(const uint8_t * desc, uint16_t desc_size); -extern void PIOS_USBHOOK_RegisterHidReport(const uint8_t * desc, uint16_t desc_size); + +struct pios_usb_ifops { + void (*init)(uint32_t context); + void (*deinit)(uint32_t context); + bool (*setup)(uint32_t context, struct usb_setup_request * req); + void (*ctrl_data_out)(uint32_t context, struct usb_setup_request * req); +}; + +extern void PIOS_USBHOOK_RegisterIfOps(uint8_t ifnum, struct pios_usb_ifops * ifops, uint32_t context); + +typedef bool (*pios_usbhook_epcb)(uint32_t context, uint8_t epnum, uint16_t len); + +extern void PIOS_USBHOOK_RegisterEpInCallback(uint8_t epnum, uint16_t max_len, pios_usbhook_epcb cb, uint32_t context); +extern void PIOS_USBHOOK_RegisterEpOutCallback(uint8_t epnum, uint16_t max_len, pios_usbhook_epcb cb, uint32_t context); +extern void PIOS_USBHOOK_DeRegisterEpInCallback(uint8_t epnum); +extern void PIOS_USBHOOK_DeRegisterEpOutCallback(uint8_t epnum); + +extern void PIOS_USBHOOK_CtrlTx(const uint8_t *buf, uint16_t len); +extern void PIOS_USBHOOK_CtrlRx(uint8_t *buf, uint16_t len); +extern void PIOS_USBHOOK_EndpointTx(uint8_t epnum, const uint8_t *buf, uint16_t len); +extern void PIOS_USBHOOK_EndpointRx(uint8_t epnum, uint8_t *buf, uint16_t len); +extern void PIOS_USBHOOK_Activate(void); +extern void PIOS_USBHOOK_Deactivate(void); #endif /* PIOS_USBHOOK_H */ diff --git a/flight/PiOS/inc/stm32f2xx_conf.h b/flight/PiOS/inc/stm32f2xx_conf.h new file mode 100644 index 000000000..0ee7ea36e --- /dev/null +++ b/flight/PiOS/inc/stm32f2xx_conf.h @@ -0,0 +1,88 @@ +/** + ****************************************************************************** + * @file Project/STM32F2xx_StdPeriph_Template/stm32f2xx_conf.h + * @author MCD Application Team + * @version V0.0.4 + * @date 13-January-2011 + * @brief Library configuration file. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F2xx_CONF_H +#define __STM32F2xx_CONF_H + +/* Includes ------------------------------------------------------------------*/ +/* Uncomment the line below to enable peripheral header file inclusion */ +#include "stm32f2xx_adc.h" +//#include "stm32f2xx_can.h" +#include "stm32f2xx_crc.h" +//#include "stm32f2xx_cryp.h" +#include "stm32f2xx_dac.h" +//#include "stm32f2xx_dbgmcu.h" +//#include "stm32f2xx_dcmi.h" +#include "stm32f2xx_dma.h" +#include "stm32f2xx_exti.h" +#include "stm32f2xx_flash.h" +//#include "stm32f2xx_fsmc.h" +//#include "stm32f2xx_hash.h" +#include "stm32f2xx_gpio.h" +#include "stm32f2xx_i2c.h" +//#include "stm32f2xx_iwdg.h" +#include "stm32f2xx_pwr.h" +#include "stm32f2xx_rcc.h" +//#include "stm32f2xx_rng.h" +#include "stm32f2xx_rtc.h" +//#include "stm32f2xx_sdio.h" +#include "stm32f2xx_spi.h" +#include "stm32f2xx_syscfg.h" +#include "stm32f2xx_tim.h" +#include "stm32f2xx_usart.h" +#include "stm32f2xx_wwdg.h" +#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* If an external clock source is used, then the value of the following define + should be set to the value of the external clock source, else, if no external + clock is used, keep this define commented */ +/*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */ + + +/* Uncomment the line below to expanse the "assert_param" macro in the + Standard Peripheral Library drivers code */ +/* #define USE_FULL_ASSERT 1 */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT + +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + +#endif /* __STM32F2xx_CONF_H */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/inc/stm32f4xx_conf.h b/flight/PiOS/inc/stm32f4xx_conf.h new file mode 100644 index 000000000..ef9dd5342 --- /dev/null +++ b/flight/PiOS/inc/stm32f4xx_conf.h @@ -0,0 +1,88 @@ +/** + ****************************************************************************** + * @file Project/STM32F4xx_StdPeriph_Template/stm32f4xx_conf.h + * @author MCD Application Team + * @version V0.0.4 + * @date 13-January-2011 + * @brief Library configuration file. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_CONF_H +#define __STM32F4xx_CONF_H + +/* Includes ------------------------------------------------------------------*/ +/* Uncomment the line below to enable peripheral header file inclusion */ +#include "stm32f4xx_adc.h" +//#include "stm32f4xx_can.h" +#include "stm32f4xx_crc.h" +//#include "stm32f2xx_cryp.h" +#include "stm32f4xx_dac.h" +//#include "stm32f4xx_dbgmcu.h" +//#include "stm32f4xx_dcmi.h" +#include "stm32f4xx_dma.h" +#include "stm32f4xx_exti.h" +#include "stm32f4xx_flash.h" +//#include "stm32f4xx_fsmc.h" +//#include "stm32f4xx_hash.h" +#include "stm32f4xx_gpio.h" +#include "stm32f4xx_i2c.h" +//#include "stm32f4xx_iwdg.h" +#include "stm32f4xx_pwr.h" +#include "stm32f4xx_rcc.h" +//#include "stm32f4xx_rng.h" +#include "stm32f4xx_rtc.h" +//#include "stm32f4xx_sdio.h" +#include "stm32f4xx_spi.h" +#include "stm32f4xx_syscfg.h" +#include "stm32f4xx_tim.h" +#include "stm32f4xx_usart.h" +#include "stm32f4xx_wwdg.h" +#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* If an external clock source is used, then the value of the following define + should be set to the value of the external clock source, else, if no external + clock is used, keep this define commented */ +/*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */ + + +/* Uncomment the line below to expanse the "assert_param" macro in the + Standard Peripheral Library drivers code */ +/* #define USE_FULL_ASSERT 1 */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT + +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + +#endif /* __STM32F4xx_CONF_H */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/pios.h b/flight/PiOS/pios.h index e7d02dfd2..560eb9b39 100644 --- a/flight/PiOS/pios.h +++ b/flight/PiOS/pios.h @@ -46,9 +46,17 @@ #include #include +#include "pios_config.h" /* STM32 Std Perf Lib */ +#if defined(STM32F4XX) +# include +# include +#elif defined(STM32F2XX) +#include +#include +#else #include -#include +#endif #if defined(PIOS_INCLUDE_SDCARD) /* Dosfs Includes */ @@ -86,9 +94,7 @@ #include #include #include -#if defined(PIOS_INCLUDE_EXTI) #include -#endif #include /* PIOS Hardware Includes (Common) */ @@ -112,21 +118,30 @@ #if defined(PIOS_INCLUDE_IMU3000) #include #endif - +#if defined(PIOS_INCLUDE_MPU6050) +#include +#endif +#if defined(PIOS_INCLUDE_MPU6000) +#include +#endif +#if defined(PIOS_INCLUDE_L3GD20) +#include +#endif +#if defined(PIOS_INCLUDE_MS5611) +#include +#endif #if defined(PIOS_INCLUDE_IAP) #include #endif - #if defined(PIOS_INCLUDE_ADXL345) #include #endif - #if defined(PIOS_INCLUDE_BMA180) #include #endif #if defined(PIOS_INCLUDE_FLASH) -#include +#include #include #endif @@ -135,8 +150,6 @@ #endif #if defined(PIOS_INCLUDE_USB) -/* USB Libs */ -#include #include #endif diff --git a/flight/PipXtreme/Makefile b/flight/PipXtreme/Makefile index a21fdb74a..9ef5e9842 100644 --- a/flight/PipXtreme/Makefile +++ b/flight/PipXtreme/Makefile @@ -1,24 +1,24 @@ ##### - # Project: OpenPilot Pip Modems - # - # - # Makefile for OpenPilot Pip Modem project + # Project: OpenPilot + # + # + # Makefile for OpenPilot project build PiOS and the AP. # # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. - # + # # - # This program is free software; you can redistribute it and/or modify - # it under the terms of the GNU General Public License as published by - # the Free Software Foundation; either version 3 of the License, or + # This program is free software; you can redistribute it and/or modify + # it under the terms of the GNU General Public License as published by + # the Free Software Foundation; either version 3 of the License, or # (at your option) any later version. - # - # This program is distributed in the hope that it will be useful, but - # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + # + # This program is distributed in the hope that it will be useful, but + # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License # for more details. - # - # You should have received a copy of the GNU General Public License along - # with this program; if not, write to the Free Software Foundation, Inc., + # + # You should have received a copy of the GNU General Public License along + # with this program; if not, write to the Free Software Foundation, Inc., # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA ##### @@ -33,12 +33,29 @@ TARGET := fw_$(BOARD_NAME) # Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) OUTDIR := $(TOP)/build/$(TARGET) -# Debugging (YES/NO) ? +# Set developer code and compile options +# Set to YES to compile for debugging DEBUG ?= NO -# Use Code Sourcery toolchain (YES/NO) ? +# Include objects that are just nice information to show +DIAGNOSTICS ?= NO + +# Set to YES to build a FW version that will erase all flash memory +ERASE_FLASH ?= NO +# Set to YES to use the Servo output pins for debugging via scope or logic analyser +ENABLE_DEBUG_PINS ?= NO + +# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs +ENABLE_AUX_UART ?= NO + +USE_GPS ?= NO + +USE_I2C ?= YES + +# Set to YES when using Code Sourcery toolchain CODE_SOURCERY ?= YES +# Remove command is different for Code Sourcery on Windows ifeq ($(CODE_SOURCERY), YES) REMOVE_CMD = cs-rm else @@ -47,56 +64,85 @@ endif FLASH_TOOL = OPENOCD -# Include the USB files (YES/NO) ? -USE_USB = YES +# List of modules to include +OPTMODULES = +MODULES = RadioComBridge # Paths -HOME_DIR = ./ -HOME_DIR_INC = $(HOME_DIR)/inc -PIOS = ../PiOS -PIOSINC = $(PIOS)/inc +OPSYSTEM = ./System +OPSYSTEMINC = $(OPSYSTEM)/inc +OPUAVTALK = ../UAVTalk +OPUAVTALKINC = $(OPUAVTALK)/inc +OPUAVOBJ = ../UAVObjects +OPUAVOBJINC = $(OPUAVOBJ)/inc +OPTESTS = ./Tests +OPMODULEDIR = ../Modules FLIGHTLIB = ../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc +RSCODEINC = $(FLIGHTLIB)/rscode +PIOS = ../PiOS +PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards APPLIBDIR = $(PIOSSTM32F10X)/Libraries STMLIBDIR = $(APPLIBDIR) STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver -ifeq ($(USE_USB), YES) - STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver -endif +STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc -ifeq ($(USE_USB), YES) - STMUSBSRCDIR = $(STMUSBDIR)/src - STMUSBINCDIR = $(STMUSBDIR)/inc -endif +STMUSBSRCDIR = $(STMUSBDIR)/src +STMUSBINCDIR = $(STMUSBDIR)/inc CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 -BOOT = ../Bootloaders/AHRS -BOOTINC = $(BOOT)/inc +DOSFSDIR = $(APPLIBDIR)/dosfs +MSDDIR = $(APPLIBDIR)/msd +RTOSDIR = $(APPLIBDIR)/FreeRTOS +RTOSSRCDIR = $(RTOSDIR)/Source +RTOSINCDIR = $(RTOSSRCDIR)/include +DOXYGENDIR = ../Doc/Doxygen +AHRSBOOTLOADER = ../Bootloaders/AHRS/ +AHRSBOOTLOADERINC = $(AHRSBOOTLOADER)/inc +PYMITE = $(FLIGHTLIB)/PyMite +PYMITELIB = $(PYMITE)/lib +PYMITEPLAT = $(PYMITE)/platform/openpilot +PYMITETOOLS = $(PYMITE)/tools +PYMITEVM = $(PYMITE)/vm +PYMITEINC = $(PYMITEVM) +PYMITEINC += $(PYMITEPLAT) +PYMITEINC += $(OUTDIR) +FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib +FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans HWDEFSINC = ../board_hw_defs/$(BOARD_NAME) +OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight + # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files -## Core: -SRC += $(HOME_DIR)/main.c -SRC += $(HOME_DIR)/pios_board.c -SRC += $(HOME_DIR)/crc.c -SRC += $(HOME_DIR)/aes.c -SRC += $(HOME_DIR)/rfm22b.c -SRC += $(HOME_DIR)/packet_handler.c -SRC += $(HOME_DIR)/stream.c -SRC += $(HOME_DIR)/ppm.c -SRC += $(HOME_DIR)/transparent_comms.c -#SRC += $(HOME_DIR)/api_comms.c -SRC += $(HOME_DIR)/api_config.c -SRC += $(HOME_DIR)/saved_settings.c -SRC += $(HOME_DIR)/gpio_in.c -SRC += $(HOME_DIR)/stopwatch.c -SRC += $(HOME_DIR)/watchdog.c -SRC += $(FLIGHTLIB)/fifo_buffer.c +ifndef TESTAPP +## MODULES +SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +## OPENPILOT CORE: +SRC += ${OPMODULEDIR}/PipXtreme/pipxtrememod.c +SRC += $(OPSYSTEM)/pipxtreme.c +SRC += $(OPSYSTEM)/pios_board.c +SRC += $(OPUAVTALK)/uavtalk.c +SRC += $(OPUAVOBJ)/uavobjectmanager.c +SRC += $(OPUAVOBJ)/eventdispatcher.c +else +## TESTCODE +SRC += $(OPTESTS)/test_common.c +SRC += $(OPTESTS)/$(TESTAPP).c +endif + +## UAVOBJECTS +ifndef TESTAPP +SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c +SRC += $(OPUAVSYNTHDIR)/pipxstatus.c +SRC += $(OPUAVSYNTHDIR)/pipxsettings.c +SRC += $(OPUAVSYNTHDIR)/objectpersistence.c + +endif ## PIOS Hardware (STM32F10x) SRC += $(PIOSSTM32F10X)/pios_sys.c @@ -104,41 +150,60 @@ SRC += $(PIOSSTM32F10X)/pios_led.c SRC += $(PIOSSTM32F10X)/pios_delay.c SRC += $(PIOSSTM32F10X)/pios_usart.c SRC += $(PIOSSTM32F10X)/pios_irq.c -SRC += $(PIOSSTM32F10X)/pios_adc.c -SRC += $(PIOSSTM32F10X)/pios_gpio.c SRC += $(PIOSSTM32F10X)/pios_spi.c SRC += $(PIOSSTM32F10X)/pios_ppm.c +SRC += $(PIOSSTM32F10X)/pios_debug.c +SRC += $(PIOSSTM32F10X)/pios_gpio.c +SRC += $(PIOSSTM32F10X)/pios_exti.c +SRC += $(PIOSSTM32F10X)/pios_rtc.c +SRC += $(PIOSSTM32F10X)/pios_wdg.c +SRC += $(PIOSSTM32F10X)/pios_tim.c +SRC += $(PIOSSTM32F10X)/pios_pwm.c +SRC += $(PIOSSTM32F10X)/pios_eeprom.c +SRC += $(PIOSSTM32F10X)/pios_bl_helper.c # PIOS USB related files (seperated to make code maintenance more easy) -ifeq ($(USE_USB), YES) - SRC += $(PIOSSTM32F10X)/pios_usb.c - SRC += $(PIOSSTM32F10X)/pios_usbhook.c - SRC += $(PIOSSTM32F10X)/pios_usb_hid.c - SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c - SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c - SRC += $(HOME_DIR)/pios_usb_board_data.c - SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c -endif +SRC += $(PIOSSTM32F10X)/pios_usb.c +SRC += $(PIOSSTM32F10X)/pios_usbhook.c +SRC += $(PIOSSTM32F10X)/pios_usb_hid.c +SRC += $(PIOSSTM32F10X)/pios_usb_cdc.c +SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c +SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c +SRC += $(OPSYSTEM)/pios_usb_board_data.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c +SRC += $(PIOSCOMMON)/pios_usb_util.c ## PIOS Hardware (Common) +SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_i2c_esc.c +SRC += $(PIOSCOMMON)/pios_rcvr.c SRC += $(PIOSCOMMON)/printf-stdarg.c +SRC += $(PIOSCOMMON)/pios_rfm22b.c +## Libraries for flight calculations +SRC += $(FLIGHTLIB)/fifo_buffer.c +SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += $(FLIGHTLIB)/taskmonitor.c +SRC += $(FLIGHTLIB)/aes.c +SRC += $(FLIGHTLIB)/packet_handler.c +## The Reed-Solomon FEC library +SRC += $(FLIGHTLIB)/rscode/rs.c +SRC += $(FLIGHTLIB)/rscode/berlekamp.c +SRC += $(FLIGHTLIB)/rscode/galois.c ## CMSIS for STM32 SRC += $(CMSISDIR)/core_cm3.c SRC += $(CMSISDIR)/system_stm32f10x.c ## Used parts of the STM-Library -SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c -SRC += $(STMSPDSRCDIR)/stm32f10x_iwdg.c SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c @@ -146,31 +211,40 @@ SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c +SRC += $(STMSPDSRCDIR)/stm32f10x_iwdg.c +SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c SRC += $(STMSPDSRCDIR)/misc.c ## STM32 USB Library -ifeq ($(USE_USB), YES) - SRC += $(STMUSBSRCDIR)/usb_core.c - SRC += $(STMUSBSRCDIR)/usb_init.c - SRC += $(STMUSBSRCDIR)/usb_int.c - SRC += $(STMUSBSRCDIR)/usb_mem.c - SRC += $(STMUSBSRCDIR)/usb_regs.c - SRC += $(STMUSBSRCDIR)/usb_sil.c -endif +SRC += $(STMUSBSRCDIR)/usb_core.c +SRC += $(STMUSBSRCDIR)/usb_init.c +SRC += $(STMUSBSRCDIR)/usb_int.c +SRC += $(STMUSBSRCDIR)/usb_mem.c +SRC += $(STMUSBSRCDIR)/usb_regs.c +SRC += $(STMUSBSRCDIR)/usb_sil.c + +## RTOS +SRC += $(RTOSSRCDIR)/list.c +SRC += $(RTOSSRCDIR)/queue.c +SRC += $(RTOSSRCDIR)/tasks.c + +## RTOS Portable +SRC += $(RTOSSRCDIR)/portable/GCC/ARM_CM3/port.c +SRC += $(RTOSSRCDIR)/portable/MemMang/heap_1.c # List C source files here which must be compiled in ARM-Mode (no -mthumb). # use file-extension c for "c-only"-files ## just for testing, timer.c could be compiled in thumb-mode too -SRCARM = +SRCARM = # List C++ source files here. # use file-extension .cpp for C++-files (not .C) -CPPSRC = +CPPSRC = # List C++ source files here which must be compiled in ARM-Mode. # use file-extension .cpp for C++-files (not .C) #CPPSRCARM = $(TARGET).cpp -CPPSRCARM = +CPPSRCARM = # List Assembler source files here. # Make them always end in a capital .S. Files ending in a lowercase .s @@ -182,35 +256,48 @@ CPPSRCARM = ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S # List Assembler source files here which must be assembled in ARM-Mode.. -ASRCARM = +ASRCARM = # List any extra directories to look for include files here. # Each directory must be seperated by a space. -EXTRAINCDIRS += $(HOME_DIR) -EXTRAINCDIRS += $(HOME_DIR_INC) +EXTRAINCDIRS = $(OPSYSTEM) +EXTRAINCDIRS += $(OPSYSTEMINC) +EXTRAINCDIRS += $(OPUAVTALK) +EXTRAINCDIRS += $(OPUAVTALKINC) +EXTRAINCDIRS += $(OPUAVOBJ) +EXTRAINCDIRS += $(OPUAVOBJINC) +EXTRAINCDIRS += $(OPUAVSYNTHDIR) EXTRAINCDIRS += $(PIOS) EXTRAINCDIRS += $(PIOSINC) EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(RSCODEINC) EXTRAINCDIRS += $(PIOSSTM32F10X) EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) EXTRAINCDIRS += $(STMSPDINCDIR) -ifeq ($(USE_USB), YES) - EXTRAINCDIRS += $(STMUSBINCDIR) -endif +EXTRAINCDIRS += $(STMUSBINCDIR) EXTRAINCDIRS += $(CMSISDIR) -EXTRAINCDIRS += $(BOOTINC) +EXTRAINCDIRS += $(DOSFSDIR) +EXTRAINCDIRS += $(MSDDIR) +EXTRAINCDIRS += $(RTOSINCDIR) +EXTRAINCDIRS += $(APPLIBDIR) +EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3 +EXTRAINCDIRS += $(AHRSBOOTLOADERINC) +EXTRAINCDIRS += $(PYMITEINC) EXTRAINCDIRS += $(HWDEFSINC) +EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES}, ${OPMODULEDIR}/${MOD}/inc} ${OPMODULEDIR}/System/inc + + # List any extra directories to look for library files here. # Also add directories where the linker should search for # includes from linker-script to the list # Each directory must be seperated by a space. -EXTRA_LIBDIRS = +EXTRA_LIBDIRS = # Extra Libraries # Each library-name must be seperated by a space. -# i.e. to link with libxyz.a, libabc.a and libefsl.a: +# i.e. to link with libxyz.a, libabc.a and libefsl.a: # EXTRA_LIBS = xyz abc efsl # for newlib-lpc (file: libnewlibc-lpc.a): # EXTRA_LIBS = newlib-lpc @@ -219,19 +306,18 @@ EXTRA_LIBS = # Path to Linker-Scripts LINKERSCRIPTPATH = $(PIOSSTM32F10X) -# Optimization level, can be [0, 1, 2, 3, s]. +# Optimization level, can be [0, 1, 2, 3, s]. # 0 = turn off optimization. s = optimize for size. # (Note: 3 is not always the best optimization level. See avr-libc FAQ.) ifeq ($(DEBUG),YES) -OPT = 0 +OPT = 1 else OPT = s -#OPT = 2 endif # Output format. (can be ihex or binary or both) -# binary to create a load-image in raw-binary format i.e. for SAM-BA, +# binary to create a load-image in raw-binary format i.e. for SAM-BA, # ihex to create a load-image in Intel hex format #LOADFORMAT = ihex #LOADFORMAT = binary @@ -240,13 +326,30 @@ LOADFORMAT = both # Debugging format. DEBUGF = dwarf-2 -# Place project-specific -D (define) and/or +# Place project-specific -D (define) and/or # -U options for C here. CDEFS = -DSTM32F10X_$(MODEL) CDEFS += -DUSE_STDPERIPH_DRIVER CDEFS += -DUSE_$(BOARD) +ifeq ($(ENABLE_DEBUG_PINS), YES) +CDEFS += -DPIOS_ENABLE_DEBUG_PINS +endif +ifeq ($(ENABLE_AUX_UART), YES) +CDEFS += -DPIOS_ENABLE_AUX_UART +endif +ifeq ($(ERASE_FLASH), YES) +CDEFS += -DERASE_FLASH +endif -# Place project-specific -D and/or -U options for +ifneq ($(USE_GPS), NO) +CDEFS += -DUSE_GPS +endif + +ifeq ($(USE_I2C), YES) +CDEFS += -DUSE_I2C +endif + +# Place project-specific -D and/or -U options for # Assembler with preprocessor here. #ADEFS = -DUSE_IRQ_ASM_WRAPPER ADEFS = -D__ASSEMBLY__ @@ -272,18 +375,27 @@ CSTANDARD = -std=gnu99 # Flags for C and C++ (arm-elf-gcc/arm-elf-g++) ifeq ($(DEBUG),YES) -CFLAGS = -g$(DEBUGF) +CFLAGS = -DDEBUG endif -CFLAGS += -O$(OPT) -ifeq ($(DEBUG),NO) -CFLAGS += -fdata-sections -ffunction-sections +ifeq ($(DIAGNOSTICS),YES) +CFLAGS = -DDIAGNOSTICS endif + +CFLAGS += -g$(DEBUGF) +CFLAGS += -O$(OPT) CFLAGS += -mcpu=$(MCU) CFLAGS += $(CDEFS) CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. -CFLAGS += -mapcs-frame +#CFLAGS += -fno-cprop-registers -fno-defer-pop -fno-guess-branch-probability -fno-section-anchors +#CFLAGS += -fno-if-conversion -fno-if-conversion2 -fno-ipa-pure-const -fno-ipa-reference -fno-merge-constants +#CFLAGS += -fno-split-wide-types -fno-tree-ccp -fno-tree-ch -fno-tree-copy-prop -fno-tree-copyrename +#CFLAGS += -fno-tree-dce -fno-tree-dominator-opts -fno-tree-dse -fno-tree-fre -fno-tree-sink -fno-tree-sra +#CFLAGS += -fno-tree-ter +#CFLAGS += -g$(DEBUGF) -DDEBUG + +CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer ifeq ($(CODE_SOURCERY), YES) CFLAGS += -fpromote-loop-indices @@ -296,7 +408,7 @@ CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basen CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d # flags only for C -#CONLYFLAGS += -Wnested-externs +#CONLYFLAGS += -Wnested-externs CONLYFLAGS += $(CSTANDARD) # Assembler flags. @@ -314,14 +426,11 @@ MATH_LIB = -lm # -Map: create map file # --cref: add cross reference to map file LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections -ifeq ($(DEBUG),NO) -LDFLAGS += -Wl,-static -Wl,-s -endif LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) LDFLAGS += -lc LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) LDFLAGS += $(MATH_LIB) -LDFLAGS += -lc -lgcc +LDFLAGS += -lc -lgcc # Set linker-script name depending on selected submodel name LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_memory.ld @@ -329,6 +438,7 @@ LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_sections.ld # Define programs and commands. REMOVE = $(REMOVE_CMD) -f +PYTHON = python # List of all source files. ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) @@ -348,13 +458,13 @@ all: build ifeq ($(LOADFORMAT),ihex) build: elf hex lss sym -else +else ifeq ($(LOADFORMAT),binary) build: elf bin lss sym -else +else ifeq ($(LOADFORMAT),both) build: elf hex bin lss sym -else +else $(error "$(MSG_FORMATERROR) $(FORMAT)") endif endif @@ -364,22 +474,22 @@ endif $(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ))) # Assemble: create object files from assembler source files. -$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) +$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) # Assemble: create object files from assembler source files. ARM-only -$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) +$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) # Compile: create object files from C source files. -$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) +$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) # Compile: create object files from C source files. ARM-only -$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) +$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) # Compile: create object files from C++ source files. -$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) +$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) # Compile: create object files from C++ source files. ARM-only -$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) +$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) # Compile: create assembler files from C source files. ARM/Thumb $(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC)) @@ -392,11 +502,11 @@ $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin $(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino opfw elf: $(OUTDIR)/$(TARGET).elf -lss: $(OUTDIR)/$(TARGET).lss +lss: $(OUTDIR)/$(TARGET).lss sym: $(OUTDIR)/$(TARGET).sym hex: $(OUTDIR)/$(TARGET).hex bin: $(OUTDIR)/$(TARGET).bin @@ -432,6 +542,8 @@ clean_list : $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).sym $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).lss $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin.o + $(V1) $(REMOVE) $(wildcard $(OUTDIR)/*.c) + $(V1) $(REMOVE) $(wildcard $(OUTDIR)/*.h) $(V1) $(REMOVE) $(ALLOBJ) $(V1) $(REMOVE) $(LSTFILES) $(V1) $(REMOVE) $(DEPFILES) diff --git a/flight/PipXtreme/System/alarms.c b/flight/PipXtreme/System/alarms.c new file mode 100755 index 000000000..01d79a1e5 --- /dev/null +++ b/flight/PipXtreme/System/alarms.c @@ -0,0 +1,214 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @brief OpenPilot System libraries are available to all OP modules. + * @{ + * @file alarms.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Library for setting and clearing system alarms + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "alarms.h" + +// Private constants + +// Private types + +// Private variables +static xSemaphoreHandle lock; + +// Private functions +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); + +/** + * Initialize the alarms library + */ +int32_t AlarmsInitialize(void) +{ + SystemAlarmsInitialize(); + + lock = xSemaphoreCreateRecursiveMutex(); + //do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that + //AlarmsClearAll(); + //AlarmsDefaultAll(); + return 0; +} + +/** + * Set an alarm + * @param alarm The system alarm to be modified + * @param severity The alarm severity + * @return 0 if success, -1 if an error + */ +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return -1; + } + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarm and update its severity only if it was changed + SystemAlarmsGet(&alarms); + if ( alarms.Alarm[alarm] != severity ) + { + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); + } + + // Release lock + xSemaphoreGiveRecursive(lock); + return 0; + +} + +/** + * Get an alarm + * @param alarm The system alarm to be read + * @return Alarm severity + */ +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return 0; + } + + // Read alarm + SystemAlarmsGet(&alarms); + return alarms.Alarm[alarm]; +} + +/** + * Set an alarm to it's default value + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); +} + +/** + * Default all alarms + */ +void AlarmsDefaultAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsDefault(n); + } +} + +/** + * Clear an alarm + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); +} + +/** + * Clear all alarms + */ +void AlarmsClearAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsClear(n); + } +} + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasWarnings() +{ + return hasSeverity(SYSTEMALARMS_ALARM_WARNING); +} + +/** + * Check if there are any alarms with error or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasErrors() +{ + return hasSeverity(SYSTEMALARMS_ALARM_ERROR); +}; + +/** + * Check if there are any alarms with critical or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasCritical() +{ + return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); +}; + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + uint32_t n; + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarms + SystemAlarmsGet(&alarms); + + // Go through alarms and check if any are of the given severity or higher + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + if ( alarms.Alarm[n] >= severity) + { + xSemaphoreGiveRecursive(lock); + return 1; + } + } + + // If this point is reached then no alarms found + xSemaphoreGiveRecursive(lock); + return 0; +} +/** + * @} + * @} + */ + diff --git a/flight/OpenPilot/System/inc/FreeRTOSConfig.h b/flight/PipXtreme/System/inc/FreeRTOSConfig.h old mode 100644 new mode 100755 similarity index 93% rename from flight/OpenPilot/System/inc/FreeRTOSConfig.h rename to flight/PipXtreme/System/inc/FreeRTOSConfig.h index 4b37f7e44..994956008 --- a/flight/OpenPilot/System/inc/FreeRTOSConfig.h +++ b/flight/PipXtreme/System/inc/FreeRTOSConfig.h @@ -9,7 +9,7 @@ * application requirements. * * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE - * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. * * See http://www.freertos.org/a00110.html. *----------------------------------------------------------*/ @@ -26,12 +26,12 @@ #define configUSE_PREEMPTION 1 #define configUSE_IDLE_HOOK 1 #define configUSE_TICK_HOOK 0 -#define configUSE_MALLOC_FAILED_HOOK 1 +#define configUSE_MALLOC_FAILED_HOOK 1 #define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) #define configTICK_RATE_HZ ( ( portTickType ) 1000 ) #define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) -#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 ) -#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 41 * 1024 ) ) +#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 48 ) +#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 54 * 256) ) #define configMAX_TASK_NAME_LEN ( 16 ) #define configUSE_TRACE_FACILITY 0 #define configUSE_16_BIT_TICKS 0 @@ -40,7 +40,6 @@ #define configUSE_RECURSIVE_MUTEXES 1 #define configUSE_COUNTING_SEMAPHORES 0 #define configUSE_ALTERNATIVE_API 0 -//#define configCHECK_FOR_STACK_OVERFLOW 2 #define configQUEUE_REGISTRY_SIZE 10 /* Co-routine definitions. */ @@ -72,6 +71,10 @@ configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest NVIC value of 255. */ #define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 +#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) +#define CHECK_IRQ_STACK +#endif + /* Enable run time stats collection */ #if defined(DIAGNOSTICS) #define configCHECK_FOR_STACK_OVERFLOW 2 @@ -88,9 +91,6 @@ do {\ #define configCHECK_FOR_STACK_OVERFLOW 1 #endif -#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) -#define CHECK_IRQ_STACK -#endif /** * @} diff --git a/flight/OpenPilot/System/inc/alarms.h b/flight/PipXtreme/System/inc/alarms.h old mode 100644 new mode 100755 similarity index 100% rename from flight/OpenPilot/System/inc/alarms.h rename to flight/PipXtreme/System/inc/alarms.h diff --git a/flight/OpenPilot/System/inc/op_config.h b/flight/PipXtreme/System/inc/op_config.h old mode 100644 new mode 100755 similarity index 100% rename from flight/OpenPilot/System/inc/op_config.h rename to flight/PipXtreme/System/inc/op_config.h diff --git a/flight/OpenPilot/System/inc/openpilot.h b/flight/PipXtreme/System/inc/openpilot.h old mode 100644 new mode 100755 similarity index 100% rename from flight/OpenPilot/System/inc/openpilot.h rename to flight/PipXtreme/System/inc/openpilot.h diff --git a/flight/OpenPilot/System/inc/pios_board_posix.h b/flight/PipXtreme/System/inc/pios_board_posix.h old mode 100644 new mode 100755 similarity index 80% rename from flight/OpenPilot/System/inc/pios_board_posix.h rename to flight/PipXtreme/System/inc/pios_board_posix.h index fe6f6ba51..741f36ba7 --- a/flight/OpenPilot/System/inc/pios_board_posix.h +++ b/flight/PipXtreme/System/inc/pios_board_posix.h @@ -52,22 +52,15 @@ //------------------------- //#define PIOS_USART_TX_BUFFER_SIZE 256 #define PIOS_COM_BUFFER_SIZE 1024 -#define PIOS_COM_MAX_DEVS 256 #define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE -extern uint32_t pios_com_telem_rf_id; -extern uint32_t pios_com_telem_usb_id; -extern uint32_t pios_com_gps_id; -extern uint32_t pios_com_aux_id; -extern uint32_t pios_com_spectrum_id; - -#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) -#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#define PIOS_COM_GPS (pios_com_gps_id) +#define PIOS_COM_TELEM_RF 0 +#define PIOS_COM_GPS 1 +#define PIOS_COM_TELEM_USB 2 #ifdef PIOS_ENABLE_AUX_UART -#define PIOS_COM_AUX (pios_com_aux_id) -#define PIOS_COM_DEBUG (PIOS_COM_AUX +#define PIOS_COM_AUX 3 +#define PIOS_COM_DEBUG PIOS_COM_AUX #endif /** diff --git a/flight/OpenPilot/System/inc/pios_config.h b/flight/PipXtreme/System/inc/pios_config.h old mode 100644 new mode 100755 similarity index 65% rename from flight/OpenPilot/System/inc/pios_config.h rename to flight/PipXtreme/System/inc/pios_config.h index b676ec291..a94b2af89 --- a/flight/OpenPilot/System/inc/pios_config.h +++ b/flight/PipXtreme/System/inc/pios_config.h @@ -1,106 +1,103 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * Central compile time config for the project. - * In particular, pios_config.h is where you define which PiOS libraries - * and features are included in the firmware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_ADC -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_I2C -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_TIM - -#define PIOS_INCLUDE_RCVR - -#define PIOS_INCLUDE_DSM -//#define PIOS_INCLUDE_SBUS -#define PIOS_INCLUDE_PWM -#define PIOS_INCLUDE_PPM - -#define PIOS_INCLUDE_TELEMETRY_RF - -#define PIOS_INCLUDE_SERVO -#define PIOS_INCLUDE_SPI -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_USART -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_USB_CDC -#define PIOS_INCLUDE_BMP085 -//#define PIOS_INCLUDE_HCSR04 -#define PIOS_INCLUDE_OPAHRS -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_GPS -#define PIOS_INCLUDE_SDCARD -#define PIOS_INCLUDE_SETTINGS -#define PIOS_INCLUDE_FREERTOS -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_EXTI -#define PIOS_INCLUDE_RTC -#define PIOS_INCLUDE_WDG -#define PIOS_INCLUDE_I2C_ESC -#define PIOS_INCLUDE_BL_HELPER - -/* Defaults for Logging */ -#define LOG_FILENAME "PIOS.LOG" -#define STARTUP_LOG_ENABLED 1 - -/* Enable a priority queue in telemetry */ -#define PIOS_TELEM_PRIORITY_QUEUE - -/* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 4000 -#define HEAP_LIMIT_CRITICAL 1000 -#define IRQSTACK_LIMIT_WARNING 150 -#define IRQSTACK_LIMIT_CRITICAL 80 -#define CPULOAD_LIMIT_WARNING 80 -#define CPULOAD_LIMIT_CRITICAL 95 - -/* Stabilization options */ -#define PIOS_QUATERNION_STABILIZATION - -/* GPS options */ -#define PIOS_GPS_SETS_HOMELOCATION - -/* PIOS Initcall infrastructure */ -#define PIOS_INCLUDE_INITCALL - -#endif /* PIOS_CONFIG_H */ -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * In particular, pios_config.h is where you define which PiOS libraries + * and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* Enable/Disable PiOS Modules */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_RFM22B +#define PIOS_INCLUDE_RCVR +#define PIOS_INCLUDE_TIM + +/* Supported receiver interfaces */ +#define PIOS_INCLUDE_PPM + +/* Supported USART-based PIOS modules */ +#define PIOS_INCLUDE_SPI +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_USART +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +#define PIOS_INCLUDE_USB_CDC +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_SETTINGS +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_RTC +#define PIOS_INCLUDE_WDG +#define PIOS_INCLUDE_BL_HELPER +#define PIOS_INCLUDE_FLASH_EEPROM + +/* Defaults for Logging */ +#define LOG_FILENAME "PIOS.LOG" +#define STARTUP_LOG_ENABLED 1 + +/* COM Module */ +#define GPS_BAUDRATE 19200 +#define TELEM_BAUDRATE 19200 +#define AUXUART_ENABLED 0 +#define AUXUART_BAUDRATE 19200 + +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 220 +#define HEAP_LIMIT_CRITICAL 40 +#define IRQSTACK_LIMIT_WARNING 100 +#define IRQSTACK_LIMIT_CRITICAL 60 +#define CPULOAD_LIMIT_WARNING 85 +#define CPULOAD_LIMIT_CRITICAL 95 + +/* Task stack sizes */ +#define PIOS_ACTUATOR_STACK_SIZE 1020 +#define PIOS_MANUAL_STACK_SIZE 724 +#define PIOS_SYSTEM_STACK_SIZE 460 +#define PIOS_STABILIZATION_STACK_SIZE 524 +#define PIOS_TELEM_STACK_SIZE 500 +#define PIOS_EVENTDISPATCHER_STACK_SIZE 130 +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998 +//#define PIOS_QUATERNION_STABILIZATION + +// This can't be too high to stop eventdispatcher thread overflowing +#define PIOS_EVENTDISAPTCHER_QUEUE 10 + +/* PIOS Initcall infrastructure */ +#define PIOS_INCLUDE_INITCALL + +#endif /* PIOS_CONFIG_H */ +/** + * @} + * @} + */ diff --git a/flight/AHRS/inc/pios_config.h b/flight/PipXtreme/System/inc/pios_config_posix.h old mode 100644 new mode 100755 similarity index 69% rename from flight/AHRS/inc/pios_config.h rename to flight/PipXtreme/System/inc/pios_config_posix.h index 77ddf0f2f..ddf7ee5d4 --- a/flight/AHRS/inc/pios_config.h +++ b/flight/PipXtreme/System/inc/pios_config_posix.h @@ -1,46 +1,54 @@ -/** - ****************************************************************************** - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * - Central compile time config for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_ADC -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_I2C -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SPI -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_USART -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_HMC5843 -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_EXTI -#define PIOS_INCLUDE_BL_HELPER -#define PIOS_INCLUDE_IAP - -#endif /* PIOS_CONFIG_H */ +/** + ****************************************************************************** + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_CONFIG_POSIX_H +#define PIOS_CONFIG_POSIX_H + + +/* Enable/Disable PiOS Modules */ +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_SDCARD +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_UDP +#define PIOS_INCLUDE_SERVO + + +/* Defaults for Logging */ +#define LOG_FILENAME "PIOS.LOG" +#define STARTUP_LOG_ENABLED 1 + +/* COM Module */ +#define GPS_BAUDRATE 19200 +#define TELEM_BAUDRATE 19200 +#define AUXUART_ENABLED 0 +#define AUXUART_BAUDRATE 19200 + + +#endif /* PIOS_CONFIG_POSIX_H */ diff --git a/flight/PipXtreme/inc/pios_usb_board_data.h b/flight/PipXtreme/System/inc/pios_usb_board_data.h similarity index 88% rename from flight/PipXtreme/inc/pios_usb_board_data.h rename to flight/PipXtreme/System/inc/pios_usb_board_data.h index d4f4daf0a..4448831d8 100644 --- a/flight/PipXtreme/inc/pios_usb_board_data.h +++ b/flight/PipXtreme/System/inc/pios_usb_board_data.h @@ -31,13 +31,16 @@ #ifndef PIOS_USB_BOARD_DATA_H #define PIOS_USB_BOARD_DATA_H +#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64 +#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32 #define PIOS_USB_BOARD_HID_DATA_LENGTH 64 -#define PIOS_USB_BOARD_EP_NUM 2 +#define PIOS_USB_BOARD_EP_NUM 4 -#include "pios_usb_defs.h" /* struct usb_* */ +#include "pios_usb_defs.h" /* USB_* macros */ #define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_PIPXTREME #define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_PIPXTREME, USB_OP_BOARD_MODE_FW) +#define PIOS_USB_BOARD_SN_SUFFIX "+FW" #endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/PipXtreme/System/pios_board.c b/flight/PipXtreme/System/pios_board.c new file mode 100644 index 000000000..d1ab4bcfd --- /dev/null +++ b/flight/PipXtreme/System/pios_board.c @@ -0,0 +1,399 @@ +/* -*- Mode: c; c-basic-offset: 2; tab-width: 2; indent-tabs-mode: t -*- */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file pios_board.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board specific static initializers for hardware for the OpenPilot board. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include +#include +#include +#include + +#define PIOS_COM_SERIAL_RX_BUF_LEN 256 +#define PIOS_COM_SERIAL_TX_BUF_LEN 256 + +#define PIOS_COM_FLEXI_RX_BUF_LEN 256 +#define PIOS_COM_FLEXI_TX_BUF_LEN 256 + +#define PIOS_COM_TELEM_USB_RX_BUF_LEN 256 +#define PIOS_COM_TELEM_USB_TX_BUF_LEN 256 + +#define PIOS_COM_VCP_USB_RX_BUF_LEN 256 +#define PIOS_COM_VCP_USB_TX_BUF_LEN 256 + +#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 256 +#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 256 + +uint32_t pios_com_telem_usb_id = 0; +uint32_t pios_com_telemetry_id; +uint32_t pios_com_flexi_id; +uint32_t pios_com_vcp_id; +uint32_t pios_com_uavtalk_com_id = 0; +uint32_t pios_com_trans_com_id = 0; +uint32_t pios_com_debug_id = 0; +uint32_t pios_com_rfm22b_id = 0; +uint32_t pios_rfm22b_id = 0; +uint32_t pios_ppm_rcvr_id = 0; + +/** + * PIOS_Board_Init() + * initializes all the core subsystems on this specific hardware + * called from System/openpilot.c + */ +void PIOS_Board_Init(void) { + + /* Delay system */ + PIOS_DELAY_Init(); + + /* Set up the SPI interface to the serial flash */ + if (PIOS_SPI_Init(&pios_spi_port_id, &pios_spi_port_cfg)) { + PIOS_Assert(0); + } + + /* Initialize UAVObject libraries */ + EventDispatcherInitialize(); + UAVObjInitialize(); + +#ifdef PIOS_INCLUDE_WDG + /* Initialize watchdog as early as possible to catch faults during init */ + PIOS_WDG_Init(); +#endif /* PIOS_INCLUDE_WDG */ + +#if defined(PIOS_INCLUDE_RTC) + /* Initialize the real-time clock and its associated tick */ + PIOS_RTC_Init(&pios_rtc_main_cfg); +#endif /* PIOS_INCLUDE_RTC */ + + PipXSettingsInitialize(); + +#if defined(PIOS_INCLUDE_LED) + PIOS_LED_Init(&pios_led_cfg); +#endif /* PIOS_INCLUDE_LED */ + + PipXSettingsData pipxSettings; +#if defined(PIOS_INCLUDE_FLASH_EEPROM) + PIOS_EEPROM_Init(&pios_eeprom_cfg); + + /* Read the settings from flash. */ + /* NOTE: We probably need to save/restore the objID here incase the object changed but the size doesn't */ + if (PIOS_EEPROM_Load((uint8_t*)&pipxSettings, sizeof(PipXSettingsData)) == 0) + PipXSettingsSet(&pipxSettings); + else + PipXSettingsGet(&pipxSettings); +#else + PipXSettingsGet(&pipxSettings); +#endif /* PIOS_INCLUDE_FLASH_EEPROM */ + + /* Initialize the task monitor library */ + TaskMonitorInitialize(); + +#if defined(PIOS_INCLUDE_TIM) + /* Set up pulse timers */ + PIOS_TIM_InitClock(&tim_1_cfg); + PIOS_TIM_InitClock(&tim_2_cfg); + PIOS_TIM_InitClock(&tim_3_cfg); + PIOS_TIM_InitClock(&tim_4_cfg); +#endif /* PIOS_INCLUDE_TIM */ + +#if defined(PIOS_INCLUDE_PACKET_HANDLER) + pios_packet_handler = PHInitialize(&pios_ph_cfg); +#endif /* PIOS_INCLUDE_PACKET_HANDLER */ + +#if defined(PIOS_INCLUDE_USB) + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + + /* Flags to determine if various USB interfaces are advertised */ + bool usb_hid_present = false; + bool usb_cdc_present = false; + +#if defined(PIOS_INCLUDE_USB_CDC) + if (PIOS_USB_DESC_HID_CDC_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; + usb_cdc_present = true; +#else + if (PIOS_USB_DESC_HID_ONLY_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; +#endif + + uint32_t pios_usb_id; + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); + +#if defined(PIOS_INCLUDE_USB_CDC) + if (!usb_cdc_present) { + /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ + pipxSettings.VCPConfig = PIPXSETTINGS_VCPCONFIG_DISABLED; + } + + switch (pipxSettings.VCPConfig) + { + case PIPXSETTINGS_VCPCONFIG_SERIAL: + case PIPXSETTINGS_VCPCONFIG_DEBUG: + { + uint32_t pios_usb_cdc_id; + if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_VCP_USB_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_VCP_USB_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + rx_buffer, PIOS_COM_VCP_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_VCP_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + switch (pipxSettings.TelemetryConfig) + { + case PIPXSETTINGS_VCPCONFIG_SERIAL: + pios_com_trans_com_id = pios_com_vcp_id; + break; + case PIPXSETTINGS_VCPCONFIG_DEBUG: + pios_com_debug_id = pios_com_vcp_id; + break; + } + break; + } + case PIPXSETTINGS_VCPCONFIG_DISABLED: + break; + } +#endif + +#if defined(PIOS_INCLUDE_USB_HID) + + /* Configure the usb HID port */ +#if defined(PIOS_INCLUDE_COM) + { + uint32_t pios_usb_hid_id; + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, + rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_COM */ + +#endif /* PIOS_INCLUDE_USB_HID */ + +#endif /* PIOS_INCLUDE_USB */ + + /* Configure USART1 (telemetry port) */ + switch (pipxSettings.TelemetryConfig) + { + case PIPXSETTINGS_TELEMETRYCONFIG_SERIAL: + case PIPXSETTINGS_TELEMETRYCONFIG_UAVTALK: + case PIPXSETTINGS_TELEMETRYCONFIG_DEBUG: + { + uint32_t pios_usart1_id; + if (PIOS_USART_Init(&pios_usart1_id, &pios_usart_serial_cfg)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_SERIAL_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_SERIAL_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telemetry_id, &pios_usart_com_driver, pios_usart1_id, + rx_buffer, PIOS_COM_SERIAL_RX_BUF_LEN, + tx_buffer, PIOS_COM_SERIAL_TX_BUF_LEN)) { + PIOS_Assert(0); + } + switch (pipxSettings.TelemetryConfig) + { + case PIPXSETTINGS_TELEMETRYCONFIG_SERIAL: + pios_com_trans_com_id = pios_com_telemetry_id; + break; + case PIPXSETTINGS_TELEMETRYCONFIG_UAVTALK: + pios_com_uavtalk_com_id = pios_com_telemetry_id; + break; + case PIPXSETTINGS_TELEMETRYCONFIG_DEBUG: + pios_com_debug_id = pios_com_telemetry_id; + break; + } + break; + } + case PIPXSETTINGS_TELEMETRYCONFIG_DISABLED: + break; + } + + /* Configure USART3 */ + switch (pipxSettings.FlexiConfig) + { + case PIPXSETTINGS_FLEXICONFIG_SERIAL: + case PIPXSETTINGS_FLEXICONFIG_UAVTALK: + case PIPXSETTINGS_FLEXICONFIG_DEBUG: + { + uint32_t pios_usart3_id; + if (PIOS_USART_Init(&pios_usart3_id, &pios_usart_telem_flexi_cfg)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_FLEXI_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_FLEXI_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_flexi_id, &pios_usart_com_driver, pios_usart3_id, + rx_buffer, PIOS_COM_FLEXI_RX_BUF_LEN, + tx_buffer, PIOS_COM_FLEXI_TX_BUF_LEN)) { + PIOS_Assert(0); + } + switch (pipxSettings.FlexiConfig) + { + case PIPXSETTINGS_FLEXICONFIG_SERIAL: + pios_com_trans_com_id = pios_com_flexi_id; + break; + case PIPXSETTINGS_FLEXICONFIG_UAVTALK: + pios_com_uavtalk_com_id = pios_com_flexi_id; + break; + case PIPXSETTINGS_FLEXICONFIG_DEBUG: + pios_com_debug_id = pios_com_flexi_id; + break; + } + break; + } + case PIPXSETTINGS_FLEXICONFIG_PPM_IN: +#if defined(PIOS_INCLUDE_PPM) + { + uint32_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_PPM */ + break; + case PIPXSETTINGS_FLEXICONFIG_PPM_OUT: + case PIPXSETTINGS_FLEXICONFIG_RSSI: + case PIPXSETTINGS_FLEXICONFIG_DISABLED: + break; + } + +#if defined(PIOS_INCLUDE_RFM22B) + struct pios_rfm22b_cfg pios_rfm22b_cfg = { + .frequencyHz = 434000000, + .minFrequencyHz = 434000000 - 2000000, + .maxFrequencyHz = 434000000 + 2000000, + .RFXtalCap = 0x7f, + .maxRFBandwidth = 128000, + .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW + }; + + /* Retrieve hardware settings. */ + pios_rfm22b_cfg.frequencyHz = pipxSettings.Frequency; + pios_rfm22b_cfg.RFXtalCap = pipxSettings.FrequencyCalibration; + switch (pipxSettings.RFSpeed) + { + case PIPXSETTINGS_RFSPEED_2400: + pios_rfm22b_cfg.maxRFBandwidth = 2000; + break; + case PIPXSETTINGS_RFSPEED_4800: + pios_rfm22b_cfg.maxRFBandwidth = 4000; + break; + case PIPXSETTINGS_RFSPEED_9600: + pios_rfm22b_cfg.maxRFBandwidth = 9600; + break; + case PIPXSETTINGS_RFSPEED_19200: + pios_rfm22b_cfg.maxRFBandwidth = 19200; + break; + case PIPXSETTINGS_RFSPEED_38400: + pios_rfm22b_cfg.maxRFBandwidth = 32000; + break; + case PIPXSETTINGS_RFSPEED_57600: + pios_rfm22b_cfg.maxRFBandwidth = 64000; + break; + case PIPXSETTINGS_RFSPEED_115200: + pios_rfm22b_cfg.maxRFBandwidth = 128000; + break; + } + switch (pipxSettings.RFSpeed) + { + case PIPXSETTINGS_MAXRFPOWER_125: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_0; + break; + case PIPXSETTINGS_MAXRFPOWER_16: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_1; + break; + case PIPXSETTINGS_MAXRFPOWER_316: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_2; + break; + case PIPXSETTINGS_MAXRFPOWER_63: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_3; + break; + case PIPXSETTINGS_MAXRFPOWER_126: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_4; + break; + case PIPXSETTINGS_MAXRFPOWER_25: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_5; + break; + case PIPXSETTINGS_MAXRFPOWER_50: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_6; + break; + case PIPXSETTINGS_MAXRFPOWER_100: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_7; + break; + } + + /* Initalize the RFM22B radio COM device. */ + { + if (PIOS_RFM22B_Init(&pios_rfm22b_id, &pios_rfm22b_cfg)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_rfm22b_id, &pios_rfm22b_com_driver, pios_rfm22b_id, + rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN, + tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_RFM22B */ + + /* Remap AFIO pin */ + GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); + +#ifdef PIOS_INCLUDE_ADC + PIOS_ADC_Init(); +#endif + PIOS_GPIO_Init(); +} + +/** + * @} + */ diff --git a/flight/OpenPilot/System/pios_board_posix.c b/flight/PipXtreme/System/pios_board_posix.c old mode 100644 new mode 100755 similarity index 52% rename from flight/OpenPilot/System/pios_board_posix.c rename to flight/PipXtreme/System/pios_board_posix.c index bb1f7d5b2..30f949830 --- a/flight/OpenPilot/System/pios_board_posix.c +++ b/flight/PipXtreme/System/pios_board_posix.c @@ -29,41 +29,41 @@ #include #include -#include "hwsettings.h" -#include "attituderaw.h" -#include "attitudeactual.h" -#include "positionactual.h" -#include "velocityactual.h" -#include "manualcontrolsettings.h" - -#if defined(PIOS_INCLUDE_RCVR) -#include "pios_rcvr_priv.h" - -/* One slot per selectable receiver group. - * eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS - * NOTE: No slot in this map for NONE. +/** + * PIOS_Board_Init() + * initializes all the core systems on this specific hardware + * called from System/openpilot.c */ -uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; +void PIOS_Board_Init(void) { -#endif /* PIOS_INCLUDE_RCVR */ + /* Delay system */ + PIOS_DELAY_Init(); + /* Initialize UAVObject libraries */ + EventDispatcherInitialize(); + UAVObjInitialize(); -void Stack_Change() { -} + /* Initialize the alarms library */ + AlarmsInitialize(); + + /* Initialize the task monitor library */ + TaskMonitorInitialize(); + + /* Initialize the PiOS library */ + PIOS_COM_Init(); -void Stack_Change_Weak() { } -const struct pios_udp_cfg pios_udp_telem_cfg = { +const struct pios_udp_cfg pios_udp0_cfg = { .ip = "0.0.0.0", .port = 9000, }; -const struct pios_udp_cfg pios_udp_gps_cfg = { +const struct pios_udp_cfg pios_udp1_cfg = { .ip = "0.0.0.0", .port = 9001, }; -const struct pios_udp_cfg pios_udp_debug_cfg = { +const struct pios_udp_cfg pios_udp2_cfg = { .ip = "0.0.0.0", .port = 9002, }; @@ -72,20 +72,15 @@ const struct pios_udp_cfg pios_udp_debug_cfg = { /* * AUX USART */ -const struct pios_udp_cfg pios_udp_aux_cfg = { +const struct pios_udp_cfg pios_udp3_cfg = { .ip = "0.0.0.0", .port = 9003, }; #endif -#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192 -#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192 -#define PIOS_COM_GPS_RX_BUF_LEN 96 - /* * Board specific number of devices. */ -/* struct pios_udp_dev pios_udp_devs[] = { #define PIOS_UDP_TELEM 0 { @@ -108,7 +103,7 @@ struct pios_udp_dev pios_udp_devs[] = { }; uint8_t pios_udp_num_devices = NELEMENTS(pios_udp_devs); -*/ + /* * COM devices */ @@ -119,78 +114,28 @@ uint8_t pios_udp_num_devices = NELEMENTS(pios_udp_devs); extern const struct pios_com_driver pios_serial_com_driver; extern const struct pios_com_driver pios_udp_com_driver; -uint32_t pios_com_telem_rf_id; -uint32_t pios_com_telem_usb_id; -uint32_t pios_com_gps_id; -uint32_t pios_com_aux_id; -uint32_t pios_com_spectrum_id; - -/** - * PIOS_Board_Init() - * initializes all the core systems on this specific hardware - * called from System/openpilot.c - */ -void PIOS_Board_Init(void) { - - /* Delay system */ - PIOS_DELAY_Init(); - - /* Initialize UAVObject libraries */ - EventDispatcherInitialize(); - UAVObjInitialize(); - UAVObjectsInitializeAll(); - - /* Initialize the alarms library */ - AlarmsInitialize(); - - /* Initialize the task monitor library */ - TaskMonitorInitialize(); - -#if defined(PIOS_INCLUDE_COM) -#if defined(PIOS_INCLUDE_TELEMETRY_RF) - { - uint32_t pios_udp_telem_rf_id; - if (PIOS_UDP_Init(&pios_udp_telem_rf_id, &pios_udp_telem_cfg)) { - PIOS_Assert(0); - } - - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_udp_com_driver, pios_udp_telem_rf_id, - rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_TELEMETRY_RF */ - -#if defined(PIOS_INCLUDE_GPS) - { - uint32_t pios_udp_gps_id; - if (PIOS_UDP_Init(&pios_udp_gps_id, &pios_udp_gps_cfg)) { - PIOS_Assert(0); - } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); - PIOS_Assert(rx_buffer); - if (PIOS_COM_Init(&pios_com_gps_id, &pios_udp_com_driver, pios_udp_gps_id, - rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, - NULL, 0)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_GPS */ +struct pios_com_dev pios_com_devs[] = { + { + .id = PIOS_UDP_TELEM, + .driver = &pios_udp_com_driver, + }, + { + .id = PIOS_UDP_GPS, + .driver = &pios_udp_com_driver, + }, + { + .id = PIOS_UDP_LOCAL, + .driver = &pios_udp_com_driver, + }, +#ifdef PIOS_COM_AUX + { + .id = PIOS_UDP_AUX, + .driver = &pios_udp_com_driver, + }, #endif +}; - // Initialize these here as posix has no AHRSComms - AttitudeRawInitialize(); - AttitudeActualInitialize(); - VelocityActualInitialize(); - PositionActualInitialize(); - HwSettingsInitialize(); - -} +const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs); /** * @} diff --git a/flight/PipXtreme/System/pios_usb_board_data.c b/flight/PipXtreme/System/pios_usb_board_data.c new file mode 100644 index 000000000..c2e0c8762 --- /dev/null +++ b/flight/PipXtreme/System/pios_usb_board_data.c @@ -0,0 +1,97 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ +#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +#include "pios_usb_util.h" /* PIOS_USB_UTIL_AsciiToUtf8 */ + +static const uint8_t usb_product_id[20] = { + sizeof(usb_product_id), + USB_DESC_TYPE_STRING, + 'P', 0, + 'i', 0, + 'p', 0, + 'X', 0, + 't', 0, + 'r', 0, + 'e', 0, + 'm', 0, + 'e', 0, +}; + +static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN*2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1)*2] = { + sizeof(usb_serial_number), + USB_DESC_TYPE_STRING, +}; + +static const struct usb_string_langid usb_lang_id = { + .bLength = sizeof(usb_lang_id), + .bDescriptorType = USB_DESC_TYPE_STRING, + .bLangID = htousbs(USB_LANGID_ENGLISH_US), +}; + +static const uint8_t usb_vendor_id[28] = { + sizeof(usb_vendor_id), + USB_DESC_TYPE_STRING, + 'o', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'p', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, + '.', 0, + 'o', 0, + 'r', 0, + 'g', 0 +}; + +int32_t PIOS_USB_BOARD_DATA_Init(void) +{ + /* Load device serial number into serial number string */ + uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1]; + PIOS_SYS_SerialNumberGet((char *)sn); + + /* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */ + uint8_t * utf8 = &(usb_serial_number[2]); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); + + return 0; +} diff --git a/flight/PipXtreme/System/pipxtreme.c b/flight/PipXtreme/System/pipxtreme.c new file mode 100755 index 000000000..7dfd28a96 --- /dev/null +++ b/flight/PipXtreme/System/pipxtreme.c @@ -0,0 +1,99 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @brief These files are the core system files of OpenPilot. + * They are the ground layer just above PiOS. In practice, OpenPilot actually starts + * in the main() function of openpilot.c + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @brief This is where the OP firmware starts. Those files also define the compile-time + * options of the firmware. + * @{ + * @file openpilot.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Sets up and runs main OpenPilot tasks. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* OpenPilot Includes */ +#include "openpilot.h" +#include "uavobjectsinit.h" +#include "hwsettings.h" +#include "systemmod.h" + +/* Task Priorities */ +#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) + +/* Global Variables */ + +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void Stack_Change(void); + +/** +* OpenPilot Main function: +* +* Initialize PiOS
+* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
+* Start FreeRTOS Scheduler (vTaskStartScheduler) (Now handled by caller) +* If something goes wrong, blink LED1 and LED2 every 100ms +* +*/ +int main() +{ + /* NOTE: Do NOT modify the following start-up sequence */ + /* Any new initialization functions should be added in OpenPilotInit() */ + + /* Brings up System using CMSIS functions, enables the LEDs. */ + PIOS_SYS_Init(); + + /* Architecture dependant Hardware and + * core subsystem initialisation + * (see pios_board.c for your arch) + * */ + PIOS_Board_Init(); + + /* Initialize modules */ + MODULE_INITIALISE_ALL + + /* swap the stack to use the IRQ stack */ + Stack_Change(); + + /* Start the FreeRTOS scheduler which should never returns.*/ + vTaskStartScheduler(); + + /* If all is well we will never reach here as the scheduler will now be running. */ + + /* Do some indication to user that something bad just happened */ + while (1) { +#if defined(PIOS_LED_HEARTBEAT) + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); +#endif /* PIOS_LED_HEARTBEAT */ + PIOS_DELAY_WaitmS(100); + } + + return 0; +} + +/** + * @} + * @} + */ + diff --git a/flight/PipXtreme/api_config.c b/flight/PipXtreme/api_config.c deleted file mode 100644 index 5aa9fc6c0..000000000 --- a/flight/PipXtreme/api_config.c +++ /dev/null @@ -1,852 +0,0 @@ -/** - ****************************************************************************** - * - * @file apiconfig_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RF Module hardware layer - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include - -#include "stm32f10x.h" -#include "gpio_in.h" -#include "api_config.h" -#include "rfm22b.h" -#include "packet_handler.h" -#include "stream.h" -#include "ppm.h" -#include "saved_settings.h" -#include "crc.h" -#include "main.h" -#include "pios_usb.h" /* PIOS_USB_* */ - -#if defined(PIOS_COM_DEBUG) -// #define APICONFIG_DEBUG -#endif - -// ***************************************************************************** -// modem configuration packets - -#define PIPX_HEADER_MARKER 0x76b38a52 - -enum { - PIPX_PACKET_TYPE_REQ_DETAILS = 0, - PIPX_PACKET_TYPE_DETAILS, - PIPX_PACKET_TYPE_REQ_SETTINGS, - PIPX_PACKET_TYPE_SETTINGS, - PIPX_PACKET_TYPE_REQ_STATE, - PIPX_PACKET_TYPE_STATE, - PIPX_PACKET_TYPE_SPECTRUM -}; - -typedef struct -{ - uint32_t marker; - uint32_t serial_number; - uint8_t type; - uint8_t spare; - uint16_t data_size; - uint32_t header_crc; - uint32_t data_crc; -// uint8_t data[0]; -} __attribute__((__packed__)) t_pipx_config_header; - -typedef struct -{ - uint8_t major_version; - uint8_t minor_version; - uint32_t serial_number; - uint32_t min_frequency_Hz; - uint32_t max_frequency_Hz; - uint8_t frequency_band; - float frequency_step_size; -} __attribute__((__packed__)) t_pipx_config_details; - -typedef struct -{ - uint8_t mode; - uint8_t link_state; - int16_t rssi; - int32_t afc; - uint16_t retries; -} __attribute__((__packed__)) t_pipx_config_state; - -typedef struct -{ - uint8_t mode; - uint32_t serial_baudrate; // serial usart baudrate - uint32_t destination_id; - uint32_t frequency_Hz; - uint32_t max_rf_bandwidth; - uint8_t max_tx_power; - uint8_t rf_xtal_cap; - bool aes_enable; - uint8_t aes_key[16]; - uint8_t rts_time; - uint8_t spare[16]; -} __attribute__((__packed__)) t_pipx_config_settings; - -typedef struct -{ - uint32_t start_frequency; - uint16_t frequency_step_size; - uint16_t magnitudes; -// int8_t magnitude[0]; -} __attribute__((__packed__)) t_pipx_config_spectrum; - -// ***************************************************************************** -// local variables - -uint32_t apiconfig_previous_com_port = 0; - -volatile uint16_t apiconfig_rx_config_timer = 0; -volatile uint16_t apiconfig_rx_timer = 0; -volatile uint16_t apiconfig_tx_timer = 0; -volatile uint16_t apiconfig_ss_timer = 0; - -uint8_t apiconfig_rx_buffer[256] __attribute__ ((aligned(4))); -uint16_t apiconfig_rx_buffer_wr; - -uint8_t apiconfig_tx_buffer[256] __attribute__ ((aligned(4))); -uint16_t apiconfig_tx_buffer_wr; - -uint8_t apiconfig_tx_config_buffer[128] __attribute__ ((aligned(4))); -uint16_t apiconfig_tx_config_buffer_wr; - -// for scanning the spectrum -int8_t apiconfig_spec_buffer[64] __attribute__ ((aligned(4))); -uint16_t apiconfig_spec_buffer_wr; -uint32_t apiconfig_spec_start_freq; -uint32_t apiconfig_spec_freq; - -bool apiconfig_usb_comms; -uint32_t apiconfig_comm_port; - -uint16_t apiconfig_connection_index; // the RF connection we are using - -uint8_t led_counter; - -// ***************************************************************************** - -int apiconfig_sendDetailsPacket(void) -{ - if (sizeof(apiconfig_tx_config_buffer) - apiconfig_tx_config_buffer_wr < sizeof(t_pipx_config_header) + sizeof(t_pipx_config_details)) - return -1; // not enough room in the tx buffer for the packet we were going to send - - t_pipx_config_header *header = (t_pipx_config_header *)(apiconfig_tx_config_buffer + apiconfig_tx_config_buffer_wr); - t_pipx_config_details *details = (t_pipx_config_details *)((uint8_t *)header + sizeof(t_pipx_config_header)); - - header->marker = PIPX_HEADER_MARKER; - header->serial_number = serial_number_crc32; - header->type = PIPX_PACKET_TYPE_DETAILS; - header->spare = 0; - header->data_size = sizeof(t_pipx_config_details); - - details->major_version = VERSION_MAJOR; - details->minor_version = VERSION_MINOR; - details->serial_number = serial_number_crc32; - details->min_frequency_Hz = saved_settings.min_frequency_Hz; - details->max_frequency_Hz = saved_settings.max_frequency_Hz; - details->frequency_band = saved_settings.frequency_band; - details->frequency_step_size = rfm22_getFrequencyStepSize(); - - header->data_crc = updateCRC32Data(0xffffffff, details, header->data_size); - header->header_crc = 0; - header->header_crc = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header)); - - int total_packet_size = sizeof(t_pipx_config_header) + header->data_size; - - apiconfig_tx_config_buffer_wr += total_packet_size; - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("TX api config: details\r\n"); - #endif - - return total_packet_size; -} - -int apiconfig_sendStatePacket(void) -{ - if (sizeof(apiconfig_tx_config_buffer) - apiconfig_tx_config_buffer_wr < sizeof(t_pipx_config_header) + sizeof(t_pipx_config_state)) - return -1; // not enough room in the tx buffer for the packet we were going to send - - t_pipx_config_header *header = (t_pipx_config_header *)(apiconfig_tx_config_buffer + apiconfig_tx_config_buffer_wr); - t_pipx_config_state *state = (t_pipx_config_state *)((uint8_t *)header + sizeof(t_pipx_config_header)); - - header->marker = PIPX_HEADER_MARKER; - header->serial_number = serial_number_crc32; - header->type = PIPX_PACKET_TYPE_STATE; - header->spare = 0; - header->data_size = sizeof(t_pipx_config_state); - - state->mode = 0; - state->link_state = ph_getCurrentLinkState(0); - state->rssi = ph_getLastRSSI(0); - state->afc = ph_getLastAFC(0); - state->retries = ph_getRetries(0); - - header->data_crc = updateCRC32Data(0xffffffff, state, header->data_size); - header->header_crc = 0; - header->header_crc = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header)); - - int total_packet_size = sizeof(t_pipx_config_header) + header->data_size; - - apiconfig_tx_config_buffer_wr += total_packet_size; - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("TX api config: state\r\n"); - #endif - - return total_packet_size; -} - -int apiconfig_sendSettingsPacket(void) -{ - if (sizeof(apiconfig_tx_config_buffer) - apiconfig_tx_config_buffer_wr < sizeof(t_pipx_config_header) + sizeof(t_pipx_config_settings)) - return -1; // not enough room in the tx buffer for the packet we were going to send - - t_pipx_config_header *header = (t_pipx_config_header *)(apiconfig_tx_config_buffer + apiconfig_tx_config_buffer_wr); - t_pipx_config_settings *settings = (t_pipx_config_settings *)((uint8_t *)header + sizeof(t_pipx_config_header)); - - header->marker = PIPX_HEADER_MARKER; - header->serial_number = serial_number_crc32; - header->type = PIPX_PACKET_TYPE_SETTINGS; - header->spare = 0; - header->data_size = sizeof(t_pipx_config_settings); - - settings->mode = saved_settings.mode; - settings->destination_id = saved_settings.destination_id; - settings->frequency_Hz = saved_settings.frequency_Hz; - settings->max_rf_bandwidth = saved_settings.max_rf_bandwidth; - settings->max_tx_power = saved_settings.max_tx_power; - settings->rf_xtal_cap = saved_settings.rf_xtal_cap; - settings->serial_baudrate = saved_settings.serial_baudrate; - settings->aes_enable = saved_settings.aes_enable; - memcpy((char *)settings->aes_key, (char *)saved_settings.aes_key, sizeof(settings->aes_key)); - settings->rts_time = saved_settings.rts_time; - memset(settings->spare, 0xff, sizeof(settings->spare)); - - header->data_crc = updateCRC32Data(0xffffffff, settings, header->data_size); - header->header_crc = 0; - header->header_crc = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header)); - - int total_packet_size = sizeof(t_pipx_config_header) + header->data_size; - - apiconfig_tx_config_buffer_wr += total_packet_size; - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("TX api config: settings\r\n"); - #endif - - return total_packet_size; -} - -int apiconfig_sendSpectrumPacket(uint32_t start_frequency, uint16_t freq_step_size, void *spectrum_data, uint32_t spectrum_data_size) -{ - if (sizeof(apiconfig_tx_config_buffer) - apiconfig_tx_config_buffer_wr < sizeof(t_pipx_config_header) + sizeof(t_pipx_config_spectrum) + spectrum_data_size) - return -1; // not enough room in the tx buffer for the packet we were going to send - - if (!spectrum_data || spectrum_data_size <= 0) - return -2; // nothing to send - - t_pipx_config_header *header = (t_pipx_config_header *)(apiconfig_tx_config_buffer + apiconfig_tx_config_buffer_wr); - t_pipx_config_spectrum *spectrum = (t_pipx_config_spectrum *)((uint8_t *)header + sizeof(t_pipx_config_header)); - uint8_t *data = (uint8_t *)spectrum + sizeof(t_pipx_config_spectrum); - - header->marker = PIPX_HEADER_MARKER; - header->serial_number = serial_number_crc32; - header->type = PIPX_PACKET_TYPE_SPECTRUM; - header->spare = 0; - header->data_size = sizeof(t_pipx_config_spectrum) + spectrum_data_size; - - spectrum->start_frequency = start_frequency; - spectrum->frequency_step_size = freq_step_size; - spectrum->magnitudes = spectrum_data_size; - memmove(data, spectrum_data, spectrum_data_size); - - header->data_crc = updateCRC32Data(0xffffffff, spectrum, header->data_size); - header->header_crc = 0; - header->header_crc = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header)); - - int total_packet_size = sizeof(t_pipx_config_header) + header->data_size; - - apiconfig_tx_config_buffer_wr += total_packet_size; - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("TX api config: spectrum\r\n"); - #endif - - return total_packet_size; -} - -void apiconfig_processInputPacket(void *buf, uint16_t len) -{ - if (len <= 0) - return; - - t_pipx_config_header *header = (t_pipx_config_header *)buf; - uint8_t *data = (uint8_t *)header + sizeof(t_pipx_config_header); - - switch (header->type) - { - case PIPX_PACKET_TYPE_REQ_DETAILS: - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("RX api config: req_details\r\n"); - #endif - - if (header->serial_number == 0 || header->serial_number == 0xffffffff || header->serial_number == serial_number_crc32) - apiconfig_sendDetailsPacket(); - - break; - - case PIPX_PACKET_TYPE_REQ_STATE: - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("RX api config: req_state\r\n"); - #endif - - if (header->serial_number == serial_number_crc32) - apiconfig_sendStatePacket(); - - break; - - case PIPX_PACKET_TYPE_REQ_SETTINGS: // they are requesting our configuration - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("RX api config: req_settings\r\n"); - #endif - - if (header->serial_number == serial_number_crc32) - apiconfig_sendSettingsPacket(); - - break; - - case PIPX_PACKET_TYPE_SETTINGS: // they have sent us new configuration settings - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("RX api config: settings\r\n"); - #endif - - if (header->serial_number == serial_number_crc32) - { // the packet is meant for us - - booting = true; - - ph_set_remote_serial_number(0, 0); // stop the packet handler trying to communicate - - // ****** - // save the new settings - - t_pipx_config_settings *settings = (t_pipx_config_settings *)data; - - saved_settings.mode = settings->mode; - saved_settings.destination_id = settings->destination_id; - saved_settings.frequency_Hz = settings->frequency_Hz; - saved_settings.max_tx_power = settings->max_tx_power; - saved_settings.max_rf_bandwidth = settings->max_rf_bandwidth; - saved_settings.rf_xtal_cap = settings->rf_xtal_cap; - saved_settings.serial_baudrate = settings->serial_baudrate; - saved_settings.aes_enable = settings->aes_enable; - memcpy((char *)saved_settings.aes_key, (char *)settings->aes_key, sizeof(saved_settings.aes_key)); - saved_settings.rts_time = settings->rts_time; - - saved_settings_save(); // save them into flash - - // ****** - - ph_deinit(); - stream_deinit(); - ppm_deinit(); - - PIOS_COM_ChangeBaud(PIOS_COM_SERIAL, saved_settings.serial_baudrate); - - switch (saved_settings.mode) - { - case MODE_NORMAL: // normal 2-way packet mode - case MODE_STREAM_TX: // 1-way continuous tx packet mode - case MODE_STREAM_RX: // 1-way continuous rx packet mode - case MODE_PPM_TX: // PPM tx mode - case MODE_PPM_RX: // PPM rx mode - case MODE_SCAN_SPECTRUM: // scan the receiver over the whole band - case MODE_TX_BLANK_CARRIER_TEST: // blank carrier Tx mode (for calibrating the carrier frequency say) - case MODE_TX_SPECTRUM_TEST: // pseudo random Tx data mode (for checking the Tx carrier spectrum) - break; - default: // unknown mode - saved_settings.mode = MODE_NORMAL; - break; - } - - switch (saved_settings.mode) - { - case MODE_NORMAL: // normal 2-way packet mode - ph_init(serial_number_crc32); // initialise the packet handler - break; - - case MODE_STREAM_TX: // 1-way continuous tx packet mode - case MODE_STREAM_RX: // 1-way continuous rx packet mode - stream_init(serial_number_crc32); // initialise the continuous packet stream module - break; - - case MODE_PPM_TX: // PPM tx mode - case MODE_PPM_RX: // PPM rx mode - ppm_init(serial_number_crc32); // initialise the PPM module - break; - - case MODE_SCAN_SPECTRUM: // scan the receiver over the whole band - rfm22_init_scan_spectrum(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz); - rfm22_setFreqCalibration(saved_settings.rf_xtal_cap); - apiconfig_spec_start_freq = saved_settings.min_frequency_Hz; - apiconfig_spec_freq = apiconfig_spec_start_freq; - apiconfig_spec_buffer_wr = 0; - apiconfig_ss_timer = 0; - break; - - case MODE_TX_BLANK_CARRIER_TEST: // blank carrier Tx mode (for calibrating the carrier frequency say) - rfm22_init_normal(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz, rfm22_freqHopSize()); - rfm22_setFreqCalibration(saved_settings.rf_xtal_cap); - rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz); - rfm22_setDatarate(saved_settings.max_rf_bandwidth, TRUE); - rfm22_setTxPower(saved_settings.max_tx_power); - rfm22_setTxCarrierMode(); - break; - - case MODE_TX_SPECTRUM_TEST: // pseudo random Tx data mode (for checking the Tx carrier spectrum) - rfm22_init_normal(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz, rfm22_freqHopSize()); - rfm22_setFreqCalibration(saved_settings.rf_xtal_cap); - rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz); - rfm22_setDatarate(saved_settings.max_rf_bandwidth, TRUE); - rfm22_setTxPower(saved_settings.max_tx_power); - rfm22_setTxPNMode(); - break; - } - - // ****** - - booting = false; - } - - break; - - default: - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("RX api config: unknown type [%u]\r\n", header->type); - #endif - break; - } -} - -uint16_t apiconfig_scanForConfigPacket(void *buf, uint16_t *len, bool rf_packet) -{ - uint16_t length = *len; - uint16_t i = 0; - - while (TRUE) - { - uint32_t crc1, crc2; - - t_pipx_config_header *header = (t_pipx_config_header *)buf + i; - uint8_t *data = (uint8_t *)header + sizeof(t_pipx_config_header); - - if (i + sizeof(t_pipx_config_header) > length) - { // not enough data for a packet - if (i >= sizeof(header->marker)) - i -= sizeof(header->marker); - else - i = 0; - break; - } - - if (header->marker != PIPX_HEADER_MARKER) - { // no packet marker found - i++; - continue; - } - - // check the header is error free - crc1 = header->header_crc; - header->header_crc = 0; - crc2 = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header)); - header->header_crc = crc1; - if (crc2 != crc1) - { // faulty header or not really a header - i++; - continue; - } - - // valid header found! - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("RX api config: header found\r\n"); - #endif - - if (!rf_packet) - { - apiconfig_rx_config_timer = 0; // reset timer - apiconfig_rx_timer = 0; // reset the timer - } - - int total_packet_size = sizeof(t_pipx_config_header) + header->data_size; - - if (i + total_packet_size > length) - { // not yet got a full packet - break; - } - - if (header->data_size > 0) - { // check the data is error free - crc1 = header->data_crc; - crc2 = updateCRC32Data(0xffffffff, data, header->data_size); - if (crc2 != crc1) - { // faulty data .. remove the entire packet - length -= total_packet_size; - if (length - i > 0) - memmove(buf + i, buf + i + total_packet_size, length - i); - continue; - } - } - - if (!rf_packet) - apiconfig_processInputPacket(buf + i, length - i); - - // remove the packet from the buffer - length -= total_packet_size; - if (length - i > 0) - memmove(buf + i, buf + i + total_packet_size, length - i); - - break; - } - - *len = length; - - return i; -} - -// ***************************************************************************** -// send the data received from the local comm-port to the RF packet handler TX buffer - -void apiconfig_processTx(void) -{ - while (TRUE) - { - // scan for a configuration packet in the rx buffer - uint16_t data_size = apiconfig_scanForConfigPacket(apiconfig_rx_buffer, &apiconfig_rx_buffer_wr, false); - - uint16_t time_out = 5; // ms - if (!apiconfig_usb_comms) time_out = (15000 * sizeof(t_pipx_config_header)) / saved_settings.serial_baudrate; // allow enough time to rx a config header - if (time_out < 5) time_out = 5; - - if (data_size == 0 && apiconfig_rx_timer >= time_out) - // no config packet found in the buffer within the timeout period, treat any data in the buffer as data to be sent over the air - data_size = apiconfig_rx_buffer_wr; - - if (data_size == 0) - break; // no data to send over the air - - if (saved_settings.mode == MODE_NORMAL || saved_settings.mode == MODE_STREAM_TX) - { - // free space size in the RF packet handler tx buffer - uint16_t ph_num = ph_putData_free(apiconfig_connection_index); - - // set the USART RTS handshaking line - if (!apiconfig_usb_comms && ph_connected(apiconfig_connection_index)) - { - if (ph_num < 32) - SERIAL_RTS_CLEAR; // lower the USART RTS line - we don't have space in the buffer for anymore bytes - else - SERIAL_RTS_SET; // release the USART RTS line - we have space in the buffer for now bytes - } - else - SERIAL_RTS_SET; // release the USART RTS line - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("RX api config: data size %u\r\n", data_size); - #endif - - if (ph_connected(apiconfig_connection_index)) - { // we have an RF link to a remote modem - - if (ph_num < data_size) - break; // not enough room in the RF packet handler TX buffer for the data - - // copy the data into the RF packet handler TX buffer for sending over the RF link - data_size = ph_putData(apiconfig_connection_index, apiconfig_rx_buffer, data_size); - } - } - else - { - SERIAL_RTS_SET; // release the USART RTS line - we have space in the buffer for now bytes - } - - // remove the data from our RX buffer - apiconfig_rx_buffer_wr -= data_size; - if (apiconfig_rx_buffer_wr > 0) - memmove(apiconfig_rx_buffer, apiconfig_rx_buffer + data_size, apiconfig_rx_buffer_wr); - } -} - -// ***************************************************************************** -// send data down the local comm port - -void apiconfig_processRx(void) -{ - if (apiconfig_tx_config_buffer_wr > 0) - { // send any config packets in the config buffer - - while (TRUE) - { - uint16_t data_size = apiconfig_tx_config_buffer_wr; - -// if (data_size > 32) -// data_size = 32; - - if (!apiconfig_usb_comms && !GPIO_IN(SERIAL_CTS_PIN)) - break; // we can't yet send data down the comm-port - - // send the data out the comm-port - int32_t res = PIOS_COM_SendBufferNonBlocking(apiconfig_comm_port, apiconfig_tx_config_buffer, data_size); - if (res < 0) - { // failed to send the data out the comm-port - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("PIOS_COM_SendBuffer %d %d\r\n", data_size, res); - #endif - - if (apiconfig_tx_timer >= 5000) - { // seems we can't send our data for at least the last 5 seconds - delete it - apiconfig_tx_config_buffer_wr = 0; - } - - break; - } - - // data was sent out the comm-port OK .. remove the sent data from our buffer - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("TX api config: data [%u]\r\n", data_size); - #endif - - apiconfig_tx_config_buffer_wr -= data_size; - if (apiconfig_tx_config_buffer_wr > 0) - memmove(apiconfig_tx_config_buffer, apiconfig_tx_config_buffer + data_size, apiconfig_tx_config_buffer_wr); - - apiconfig_tx_timer = 0; - - break; - } - - return; - } - - if (saved_settings.mode == MODE_NORMAL || saved_settings.mode == MODE_STREAM_RX) - { - // send the data received via the RF link out the comm-port - while (TRUE) - { - // get number of data bytes received via the RF link - uint16_t ph_num = ph_getData_used(apiconfig_connection_index); - - // limit to how much space we have in the temp TX buffer - if (ph_num > sizeof(apiconfig_tx_buffer) - apiconfig_tx_buffer_wr) - ph_num = sizeof(apiconfig_tx_buffer) - apiconfig_tx_buffer_wr; - - if (ph_num > 0) - { // fetch the data bytes received via the RF link and save into our temp buffer - ph_num = ph_getData(apiconfig_connection_index, apiconfig_tx_buffer + apiconfig_tx_buffer_wr, ph_num); - apiconfig_tx_buffer_wr += ph_num; - } - - uint16_t data_size = apiconfig_tx_buffer_wr; - if (data_size == 0) - break; // no data to send - - // we have data to send down the comm-port -/* - #if (defined(PIOS_COM_DEBUG) && (PIOS_COM_DEBUG == PIOS_COM_SERIAL)) - if (!apiconfig_usb_comms) - { // the serial-port is being used for debugging - don't send data down it - apiconfig_tx_buffer_wr = 0; - apiconfig_tx_timer = 0; - continue; - } - #endif -*/ - if (!apiconfig_usb_comms && !GPIO_IN(SERIAL_CTS_PIN)) - break; // we can't yet send data down the comm-port - - // send the data out the comm-port - int32_t res = PIOS_COM_SendBufferNonBlocking(apiconfig_comm_port, apiconfig_tx_buffer, data_size); - if (res < 0) - { // failed to send the data out the comm-port - - #if defined(APICONFIG_DEBUG) - DEBUG_PRINTF("PIOS_COM_SendBuffer %d %d\r\n", data_size, res); - #endif - - if (apiconfig_tx_timer >= 5000) - { // seems we can't send our data for at least the last 5 seconds - delete it - apiconfig_tx_buffer_wr = 0; - } - - break; - } - - // data was sent out the comm-port OK .. remove the sent data from our buffer - - apiconfig_tx_buffer_wr -= data_size; - if (apiconfig_tx_buffer_wr > 0) - memmove(apiconfig_tx_buffer, apiconfig_tx_buffer + data_size, apiconfig_tx_buffer_wr); - - apiconfig_tx_timer = 0; - } - } -} - -// ************************************************************* - -void apiconfig_process_scan_spectrum(void) -{ - if (saved_settings.mode != MODE_SCAN_SPECTRUM) - return; - - if (apiconfig_ss_timer < 1) return; // 1ms - apiconfig_ss_timer = 0; - - if (++led_counter >= 30) - { - led_counter = 0; -// RX_LED_TOGGLE; - LINK_LED_TOGGLE; - } - -// uint16_t freq_step_size = (uint16_t)(rfm22_getFrequencyStepSize() * 4 + 0.5f); - uint16_t freq_step_size = (uint16_t)(rfm22_getFrequencyStepSize() * 20 + 0.5f); - - // fetch the current rssi level - int16_t rssi_dbm = rfm22_getRSSI(); - if (rssi_dbm < -128) rssi_dbm = -128; - else - if (rssi_dbm > 0) rssi_dbm = 0; - - // onto next frequency - apiconfig_spec_freq += freq_step_size; - if (apiconfig_spec_freq >= rfm22_maxFrequency()) apiconfig_spec_freq = rfm22_minFrequency(); - rfm22_setNominalCarrierFrequency(apiconfig_spec_freq); -// rfm22_setRxMode(RX_SCAN_SPECTRUM, true); - - // add the RSSI value to the buffer - apiconfig_spec_buffer[apiconfig_spec_buffer_wr] = rssi_dbm; - if (++apiconfig_spec_buffer_wr >= sizeof(apiconfig_spec_buffer)) - { // send the buffer - apiconfig_sendSpectrumPacket(apiconfig_spec_start_freq, freq_step_size, apiconfig_spec_buffer, apiconfig_spec_buffer_wr); - - apiconfig_spec_buffer_wr = 0; - apiconfig_spec_start_freq = apiconfig_spec_freq; - } -} - -// ***************************************************************************** -// call this as often as possible - not from an interrupt - -void apiconfig_process(void) -{ // copy data from comm-port RX buffer to RF packet handler TX buffer, and from RF packet handler RX buffer to comm-port TX buffer - - apiconfig_process_scan_spectrum(); - - // ******************** - - // decide which comm-port we are using (usart or usb) - apiconfig_usb_comms = false; // TRUE if we are using the usb port for comms. - apiconfig_comm_port = PIOS_COM_SERIAL; // default to using the usart comm-port - #if defined(PIOS_INCLUDE_USB) - if (PIOS_USB_CheckAvailable(0)) - { // USB comms is up, use the USB comm-port instead of the USART comm-port - apiconfig_usb_comms = true; - apiconfig_comm_port = PIOS_COM_TELEM_USB; - } - #endif - - // check to see if the local communication port has changed (usart/usb) - if (apiconfig_previous_com_port == 0 && apiconfig_previous_com_port != apiconfig_comm_port) - { // the local communications port has changed .. remove any data in the buffers - apiconfig_rx_buffer_wr = 0; - apiconfig_tx_buffer_wr = 0; - apiconfig_tx_config_buffer_wr = 0; - } - else - if (apiconfig_usb_comms) - { // we're using the USB for comms - keep the USART rx buffer empty - uint8_t c; - while (PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL, &c, 1, 0) > 0); - } - apiconfig_previous_com_port = apiconfig_comm_port; // remember the current comm-port we are using - - apiconfig_connection_index = 0; // the RF connection we are using - - // ******************* - // fetch the data received via the comm-port - - // get the number of data bytes received down the comm-port - uint16_t buf_avail = sizeof(apiconfig_rx_buffer) - apiconfig_rx_buffer_wr; - - PIOS_COM_ReceiveBuffer(apiconfig_comm_port, &(apiconfig_rx_buffer[apiconfig_rx_buffer_wr]), buf_avail, 0); - - apiconfig_processTx(); - apiconfig_processRx(); - - // speed the pinging speed up if the GCS is connected and monitoring the signal level etc - ph_setFastPing(apiconfig_rx_config_timer < 2000); -} - -// ***************************************************************************** -// can be called from an interrupt if you wish - -void apiconfig_1ms_tick(void) -{ // call this once every 1ms - - if (apiconfig_rx_config_timer < 0xffff) apiconfig_rx_config_timer++; - if (apiconfig_rx_timer < 0xffff) apiconfig_rx_timer++; - if (apiconfig_tx_timer < 0xffff) apiconfig_tx_timer++; - if (apiconfig_ss_timer < 0xffff) apiconfig_ss_timer++; -} - -// ***************************************************************************** - -void apiconfig_init(void) -{ - apiconfig_previous_com_port = 0; - - apiconfig_rx_buffer_wr = 0; - - apiconfig_tx_buffer_wr = 0; - - apiconfig_tx_config_buffer_wr = 0; - - apiconfig_rx_config_timer = 0xffff; - apiconfig_rx_timer = 0; - apiconfig_tx_timer = 0; - apiconfig_ss_timer = 0; - - apiconfig_spec_buffer_wr = 0; - apiconfig_spec_start_freq = 0; - - led_counter = 0; -} - -// ***************************************************************************** diff --git a/flight/PipXtreme/crc.c b/flight/PipXtreme/crc.c deleted file mode 100644 index 1c297a165..000000000 --- a/flight/PipXtreme/crc.c +++ /dev/null @@ -1,189 +0,0 @@ -/** - ****************************************************************************** - * - * @file crc.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Serial communication port handling routines - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "crc.h" - -// ************************************************************************** - -#define Poly16 0x8408 // HDLC polynomial: 1 + x**5 + x**12 + x**16 -#define Poly32 0x04c11db7 // 32-bit polynomial .. this should produce the same as the STM32 hardware CRC - -static const uint16_t CRC_Table16[] = { // HDLC polynomial - 0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf, - 0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5, 0xe97e, 0xf8f7, - 0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e, - 0x9cc9, 0x8d40, 0xbfdb, 0xae52, 0xdaed, 0xcb64, 0xf9ff, 0xe876, - 0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd, - 0xad4a, 0xbcc3, 0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5, - 0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c, - 0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974, - 0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9, 0x2732, 0x36bb, - 0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3, - 0x5285, 0x430c, 0x7197, 0x601e, 0x14a1, 0x0528, 0x37b3, 0x263a, - 0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72, - 0x6306, 0x728f, 0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9, - 0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1, - 0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738, - 0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862, 0x9af9, 0x8b70, - 0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7, - 0x0840, 0x19c9, 0x2b52, 0x3adb, 0x4e64, 0x5fed, 0x6d76, 0x7cff, - 0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036, - 0x18c1, 0x0948, 0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e, - 0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5, - 0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd, - 0xb58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226, 0xd0bd, 0xc134, - 0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c, - 0xc60c, 0xd785, 0xe51e, 0xf497, 0x8028, 0x91a1, 0xa33a, 0xb2b3, - 0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb, - 0xd68d, 0xc704, 0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232, - 0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a, - 0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1, - 0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb, 0x0e70, 0x1ff9, - 0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330, - 0x7bc7, 0x6a4e, 0x58d5, 0x495c, 0x3de3, 0x2c6a, 0x1ef1, 0x0f78 -}; - -static const uint32_t CRC_Table32[] = { - 0x00000000, 0x04c11db7, 0x09823b6e, 0x0d4326d9, 0x130476dc, 0x17c56b6b, 0x1a864db2, 0x1e475005, - 0x2608edb8, 0x22c9f00f, 0x2f8ad6d6, 0x2b4bcb61, 0x350c9b64, 0x31cd86d3, 0x3c8ea00a, 0x384fbdbd, - 0x4c11db70, 0x48d0c6c7, 0x4593e01e, 0x4152fda9, 0x5f15adac, 0x5bd4b01b, 0x569796c2, 0x52568b75, - 0x6a1936c8, 0x6ed82b7f, 0x639b0da6, 0x675a1011, 0x791d4014, 0x7ddc5da3, 0x709f7b7a, 0x745e66cd, - 0x9823b6e0, 0x9ce2ab57, 0x91a18d8e, 0x95609039, 0x8b27c03c, 0x8fe6dd8b, 0x82a5fb52, 0x8664e6e5, - 0xbe2b5b58, 0xbaea46ef, 0xb7a96036, 0xb3687d81, 0xad2f2d84, 0xa9ee3033, 0xa4ad16ea, 0xa06c0b5d, - 0xd4326d90, 0xd0f37027, 0xddb056fe, 0xd9714b49, 0xc7361b4c, 0xc3f706fb, 0xceb42022, 0xca753d95, - 0xf23a8028, 0xf6fb9d9f, 0xfbb8bb46, 0xff79a6f1, 0xe13ef6f4, 0xe5ffeb43, 0xe8bccd9a, 0xec7dd02d, - 0x34867077, 0x30476dc0, 0x3d044b19, 0x39c556ae, 0x278206ab, 0x23431b1c, 0x2e003dc5, 0x2ac12072, - 0x128e9dcf, 0x164f8078, 0x1b0ca6a1, 0x1fcdbb16, 0x018aeb13, 0x054bf6a4, 0x0808d07d, 0x0cc9cdca, - 0x7897ab07, 0x7c56b6b0, 0x71159069, 0x75d48dde, 0x6b93dddb, 0x6f52c06c, 0x6211e6b5, 0x66d0fb02, - 0x5e9f46bf, 0x5a5e5b08, 0x571d7dd1, 0x53dc6066, 0x4d9b3063, 0x495a2dd4, 0x44190b0d, 0x40d816ba, - 0xaca5c697, 0xa864db20, 0xa527fdf9, 0xa1e6e04e, 0xbfa1b04b, 0xbb60adfc, 0xb6238b25, 0xb2e29692, - 0x8aad2b2f, 0x8e6c3698, 0x832f1041, 0x87ee0df6, 0x99a95df3, 0x9d684044, 0x902b669d, 0x94ea7b2a, - 0xe0b41de7, 0xe4750050, 0xe9362689, 0xedf73b3e, 0xf3b06b3b, 0xf771768c, 0xfa325055, 0xfef34de2, - 0xc6bcf05f, 0xc27dede8, 0xcf3ecb31, 0xcbffd686, 0xd5b88683, 0xd1799b34, 0xdc3abded, 0xd8fba05a, - 0x690ce0ee, 0x6dcdfd59, 0x608edb80, 0x644fc637, 0x7a089632, 0x7ec98b85, 0x738aad5c, 0x774bb0eb, - 0x4f040d56, 0x4bc510e1, 0x46863638, 0x42472b8f, 0x5c007b8a, 0x58c1663d, 0x558240e4, 0x51435d53, - 0x251d3b9e, 0x21dc2629, 0x2c9f00f0, 0x285e1d47, 0x36194d42, 0x32d850f5, 0x3f9b762c, 0x3b5a6b9b, - 0x0315d626, 0x07d4cb91, 0x0a97ed48, 0x0e56f0ff, 0x1011a0fa, 0x14d0bd4d, 0x19939b94, 0x1d528623, - 0xf12f560e, 0xf5ee4bb9, 0xf8ad6d60, 0xfc6c70d7, 0xe22b20d2, 0xe6ea3d65, 0xeba91bbc, 0xef68060b, - 0xd727bbb6, 0xd3e6a601, 0xdea580d8, 0xda649d6f, 0xc423cd6a, 0xc0e2d0dd, 0xcda1f604, 0xc960ebb3, - 0xbd3e8d7e, 0xb9ff90c9, 0xb4bcb610, 0xb07daba7, 0xae3afba2, 0xaafbe615, 0xa7b8c0cc, 0xa379dd7b, - 0x9b3660c6, 0x9ff77d71, 0x92b45ba8, 0x9675461f, 0x8832161a, 0x8cf30bad, 0x81b02d74, 0x857130c3, - 0x5d8a9099, 0x594b8d2e, 0x5408abf7, 0x50c9b640, 0x4e8ee645, 0x4a4ffbf2, 0x470cdd2b, 0x43cdc09c, - 0x7b827d21, 0x7f436096, 0x7200464f, 0x76c15bf8, 0x68860bfd, 0x6c47164a, 0x61043093, 0x65c52d24, - 0x119b4be9, 0x155a565e, 0x18197087, 0x1cd86d30, 0x029f3d35, 0x065e2082, 0x0b1d065b, 0x0fdc1bec, - 0x3793a651, 0x3352bbe6, 0x3e119d3f, 0x3ad08088, 0x2497d08d, 0x2056cd3a, 0x2d15ebe3, 0x29d4f654, - 0xc5a92679, 0xc1683bce, 0xcc2b1d17, 0xc8ea00a0, 0xd6ad50a5, 0xd26c4d12, 0xdf2f6bcb, 0xdbee767c, - 0xe3a1cbc1, 0xe760d676, 0xea23f0af, 0xeee2ed18, 0xf0a5bd1d, 0xf464a0aa, 0xf9278673, 0xfde69bc4, - 0x89b8fd09, 0x8d79e0be, 0x803ac667, 0x84fbdbd0, 0x9abc8bd5, 0x9e7d9662, 0x933eb0bb, 0x97ffad0c, - 0xafb010b1, 0xab710d06, 0xa6322bdf, 0xa2f33668, 0xbcb4666d, 0xb8757bda, 0xb5365d03, 0xb1f740b4 - }; - -// ************************************************************************** -// 16-bit CRC - -inline uint16_t updateCRC16(uint16_t crc, uint8_t b) -{ // update the crc - table method - return ((crc >> 8) ^ CRC_Table16[(crc & 0xff) ^ b]); -} -/* -uint16_t updateCRC16(uint16_t crc, uint8_t b) -{ // update the fcs - bit band method - register uint8_t f = (uint8_t)(crc >> 8); - crc = (crc & 0x00ff) ^ b; - for (int i = 8; i > 0; i--) - crc = (crc & 1) ? (crc >> 1) ^ Poly16 : crc >> 1; - return (crc ^ f); -} -*/ -uint16_t updateCRC16Data(uint16_t crc, void *data, uint32_t len) -{ - register uint8_t *p = (uint8_t *)data; - register uint16_t _crc = crc; - for (register uint32_t i = len; i > 0; i--) - _crc = (_crc >> 8) ^ CRC_Table16[(_crc ^ *p++) & 0xff]; -// _crc = UpdateCRC16(_crc, *p++); - return _crc; -} -/* -// Generate the CRC table -void makeCRC_Table16(void) -{ - for (uint16_t i = 0; i < 256; i++) - { - uint16_t crc = i; - for (int j = 8; j > 0; j--) - crc = (crc & 1) ? (crc >> 1) ^ Poly16 : crc >> 1; - CRC_Table16[i] = crc; - } -} -*/ -// ************************************************************************** -// 32-bit CRC - -inline uint32_t updateCRC32(uint32_t crc, uint8_t b) -{ - return ((crc << 8) ^ CRC_Table32[(crc >> 24) ^ b]); -} -/* -uint32_t updateCRC32(uint32_t crc, uint8_t b) -{ // update the crc - bit bang method - register uint32_t f = crc << 8; - crc = (crc >> 24) ^ b; - for (int i = 8; i > 0; i--) - crc = (crc & 1) ? (crc << 1) ^ Poly32 : crc << 1; - return (crc ^ f); -} -*/ -uint32_t updateCRC32Data(uint32_t crc, void *data, uint32_t len) -{ - register uint8_t *p = (uint8_t *)data; - register uint32_t _crc = crc; - for (register uint32_t i = len; i > 0; i--) - _crc = (_crc << 8) ^ CRC_Table32[(_crc >> 24) ^ *p++]; -// _crc = UpdateCRC32(_crc, *p++); - return _crc; -} -/* -// Generate the CRC table -void makeCRC_Table32(void) -{ - for (uint32_t i = 0; i < 256; i++) - { - uint32_t crc = i; - for (int j = 8; j > 0; j--) - crc = (crc & 1) ? (crc << 1) ^ Poly32 : crc << 1; - CRC_Table32[i] = crc; - } -} -*/ -// ************************************************************************** - -void CRC_init(void) -{ -// MakeCRC_Table16(); -// MakeCRC_Table32(); -} - -// ************************************************************************** diff --git a/flight/PipXtreme/gpio_in.c b/flight/PipXtreme/gpio_in.c deleted file mode 100644 index b67989b34..000000000 --- a/flight/PipXtreme/gpio_in.c +++ /dev/null @@ -1,182 +0,0 @@ -/** - ****************************************************************************** - * - * @file gpio_in.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief GPIO input functions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - - - - -/* ***************************************************************** -// Example pin definitions .. this would go into your pios_board.h file - -// GPIO_Mode_AIN Analog Input -// GPIO_Mode_IN_FLOATING Input Floating -// GPIO_Mode_IPD Input Pull-Down -// GPIO_Mode_IPU Input Pull-up - -// API mode line -#define GPIO_IN_0_PORT GPIOB -#define GPIO_IN_0_PIN GPIO_Pin_13 -#define GPIO_IN_0_MODE GPIO_Mode_IPU - -// Serial port CTS line -#define GPIO_IN_1_PORT GPIOB -#define GPIO_IN_1_PIN GPIO_Pin_14 -#define GPIO_IN_1_MODE GPIO_Mode_IPU - -#define GPIO_IN_NUM 2 -#define GPIO_IN_PORTS { GPIO_IN_0_PORT, GPIO_IN_1_PORT } -#define GPIO_IN_PINS { GPIO_IN_0_PIN, GPIO_IN_1_PIN } -#define GPIO_IN_MODES { GPIO_IN_0_MODE, GPIO_IN_1_MODE } - -#define API_MODE_PIN 0 -#define SERIAL_CTS_PIN 1 - -********************************************************************* -Example usage .. - -{ - - - - // setup all the GPIO input pins - GPIO_IN_Init(); - - - - - if (!GPIO_IN(API_MODE_PIN)) - { // pin is LOW - - - } - else - { // pin is HIGH - - - } - - - -} - -***************************************************************************** */ - - - - -#include - -#include "gpio_in.h" - -// ***************************************************************************** -// setup the GPIO input pins - -// PORT .. -// GPIOA -// GPIOB -// GPIOC -// GPIOD -// GPIOE -// GPIOF -// GPIOG - -// PIN .. -// GPIO_Pin_0 -// GPIO_Pin_1 -// GPIO_Pin_2 -// GPIO_Pin_3 -// GPIO_Pin_4 -// GPIO_Pin_5 -// GPIO_Pin_6 -// GPIO_Pin_7 -// GPIO_Pin_8 -// GPIO_Pin_9 -// GPIO_Pin_10 -// GPIO_Pin_11 -// GPIO_Pin_12 -// GPIO_Pin_13 -// GPIO_Pin_14 -// GPIO_Pin_15 - -// MODE .. -// GPIO_Mode_AIN Analog Input -// GPIO_Mode_IN_FLOATING Input Floating -// GPIO_Mode_IPD Input Pull-Down -// GPIO_Mode_IPU Input Pull-up - -#if defined(GPIO_IN_NUM) && defined(GPIO_IN_PORTS) && defined(GPIO_IN_PINS) && defined(GPIO_IN_MODES) -// #if defined(PIOS_INCLUDE_GPIO_IN) && defined(PIOS_GPIO_IN_NUM) && defined(PIOS_GPIO_IN_PORTS) && defined(PIOS_GPIO_IN_PINS) && defined(PIOS_GPIO_IN_MODES) - - // Local Variables - static GPIO_TypeDef *GPIO_IN_PORT[GPIO_IN_NUM] = GPIO_IN_PORTS; - static const uint32_t GPIO_IN_PIN[GPIO_IN_NUM] = GPIO_IN_PINS; - static const uint32_t GPIO_IN_MODE[GPIO_IN_NUM] = GPIO_IN_MODES; - - /** - * Initialises all the GPIO INPUT's - */ - void GPIO_IN_Init(void) - { - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; - - for (int i = 0; i < GPIO_IN_NUM; i++) - { - switch ((uint32_t)GPIO_IN_PORT[i]) - { - case (uint32_t)GPIOA: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); break; - case (uint32_t)GPIOB: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); break; - case (uint32_t)GPIOC: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); break; - case (uint32_t)GPIOD: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD, ENABLE); break; - case (uint32_t)GPIOE: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOE, ENABLE); break; - case (uint32_t)GPIOF: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF, ENABLE); break; - case (uint32_t)GPIOG: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOG, ENABLE); break; - } - GPIO_InitStructure.GPIO_Pin = GPIO_IN_PIN[i]; - GPIO_InitStructure.GPIO_Mode = GPIO_IN_MODE[i]; - GPIO_Init(GPIO_IN_PORT[i], &GPIO_InitStructure); - } - } - - /** - * Read input pin level - * \param[num] Pin Pin Number - */ - bool GPIO_IN(uint8_t num) - { // return .. - // FALSE if the input pin is LOW - // TRUE if the input pin is HIGH - if (num >= GPIO_IN_NUM) return FALSE; - return ((GPIO_IN_PORT[num]->IDR & GPIO_IN_PIN[num]) != 0); - } - -#endif - -// *********************************************************************************** - -/** - * @} - * @} - */ diff --git a/flight/PipXtreme/inc/main.h b/flight/PipXtreme/inc/main.h deleted file mode 100644 index b1efc1fce..000000000 --- a/flight/PipXtreme/inc/main.h +++ /dev/null @@ -1,74 +0,0 @@ -/** - ****************************************************************************** - * - * @file main.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main modem header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include - -// ***************************************************************************** - -// firmware version -#define VERSION_MAJOR 0 // 0 to 255 -#define VERSION_MINOR 9 // 0 to 255 - -// macro's for reading internal flash memory -#define mem8(addr) (*((volatile uint8_t *)(addr))) -#define mem16(addr) (*((volatile uint16_t *)(addr))) -#define mem32(addr) (*((volatile uint32_t *)(addr))) - -enum { - FREQBAND_UNKNOWN = 0, - FREQBAND_434MHz, - FREQBAND_868MHz, - FREQBAND_915MHz -}; - -enum { - MODE_NORMAL = 0, // normal 2-way packet mode - MODE_STREAM_TX, // 1-way continuous tx packet mode - MODE_STREAM_RX, // 1-way continuous rx packet mode - MODE_PPM_TX, // PPM tx mode - MODE_PPM_RX, // PPM rx mode - MODE_SCAN_SPECTRUM, // scan the receiver over the whole band - MODE_TX_BLANK_CARRIER_TEST, // blank carrier Tx mode (for calibrating the carrier frequency say) - MODE_TX_SPECTRUM_TEST // pseudo random Tx data mode (for checking the Tx carrier spectrum) -}; - -// ***************************************************************************** - -extern volatile uint32_t random32; - -extern bool booting; - -extern uint32_t flash_size; - -extern char serial_number_str[25]; -extern uint32_t serial_number_crc32; - -// ***************************************************************************** - -#endif diff --git a/flight/PipXtreme/inc/packet_handler.h b/flight/PipXtreme/inc/packet_handler.h deleted file mode 100644 index b2753bca3..000000000 --- a/flight/PipXtreme/inc/packet_handler.h +++ /dev/null @@ -1,76 +0,0 @@ -/** - ****************************************************************************** - * - * @file packet_handler.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Modem packet handling routines - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef __PACKET_HANDLER_H__ -#define __PACKET_HANDLER_H__ - -#include "stdint.h" - -// ***************************************************************************** - -#define PH_MAX_CONNECTIONS 1 // maximum number of remote connections - -// ***************************************************************************** - -void ph_1ms_tick(void); -void ph_process(void); - -bool ph_connected(const int connection_index); - -uint16_t ph_putData_free(const int connection_index); -uint16_t ph_putData(const int connection_index, const void *data, uint16_t len); - -uint16_t ph_getData_used(const int connection_index); -uint16_t ph_getData(const int connection_index, void *data, uint16_t len); - -void ph_setFastPing(bool fast); - -uint16_t ph_getRetries(const int connection_index); - -uint8_t ph_getCurrentLinkState(const int connection_index); - -int16_t ph_getLastRSSI(const int connection_index); -int32_t ph_getLastAFC(const int connection_index); - -void ph_setNominalCarrierFrequency(uint32_t frequency_hz); -uint32_t ph_getNominalCarrierFrequency(void); - -void ph_setDatarate(uint32_t datarate_bps); -uint32_t ph_getDatarate(void); - -void ph_setTxPower(uint8_t tx_power); -uint8_t ph_getTxPower(void); - -void ph_set_AES128_key(const void *key); - -int ph_set_remote_serial_number(int connection_index, uint32_t sn); -void ph_set_remote_encryption(int connection_index, bool enabled, const void *key); - -void ph_deinit(void); -void ph_init(uint32_t our_sn); - -// ***************************************************************************** - -#endif diff --git a/flight/PipXtreme/inc/pios_config.h b/flight/PipXtreme/inc/pios_config.h deleted file mode 100644 index 46728b2cb..000000000 --- a/flight/PipXtreme/inc/pios_config.h +++ /dev/null @@ -1,45 +0,0 @@ -/** - ****************************************************************************** - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * - Central compile time config for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_ADC -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SPI -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_USART -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_EXTI -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID - -#endif /* PIOS_CONFIG_H */ diff --git a/flight/PipXtreme/inc/ppm.h b/flight/PipXtreme/inc/ppm.h deleted file mode 100644 index a2163292a..000000000 --- a/flight/PipXtreme/inc/ppm.h +++ /dev/null @@ -1,40 +0,0 @@ -/** - ****************************************************************************** - * - * @file ppm.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sends or Receives the ppm values to/from the remote unit - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PPM_H_ -#define PPM_H_ - -#include "stdint.h" - -// ************************************************************* - -void ppm_1ms_tick(void); -void ppm_process(void); -void ppm_deinit(void); -void ppm_init(uint32_t our_sn); - -// ************************************************************* - -#endif diff --git a/flight/PipXtreme/inc/saved_settings.h b/flight/PipXtreme/inc/saved_settings.h deleted file mode 100644 index d174281fc..000000000 --- a/flight/PipXtreme/inc/saved_settings.h +++ /dev/null @@ -1,80 +0,0 @@ -/** - ****************************************************************************** - * - * @file saved_settings.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RF Module hardware layer - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef _SAVED_SETTINGS_H_ -#define _SAVED_SETTINGS_H_ - -// ***************************************************************** - -#include "stm32f10x.h" -#include "stm32f10x_flash.h" - -// ***************************************************************** - -typedef struct -{ - uint32_t serial_baudrate; // serial uart baudrate - - uint32_t destination_id; - - uint32_t min_frequency_Hz; - uint32_t max_frequency_Hz; - uint32_t frequency_Hz; - - uint32_t max_rf_bandwidth; - - uint8_t max_tx_power; - - uint8_t frequency_band; - - uint8_t rf_xtal_cap; - - bool aes_enable; - uint8_t aes_key[16]; - - uint8_t mode; - - uint8_t rts_time; - - uint8_t spare[30]; // allow for future unknown settings - - uint32_t crc; -} __attribute__((__packed__)) t_saved_settings; - -// ***************************************************************** -// public variables - -extern volatile t_saved_settings saved_settings __attribute__ ((aligned(4))); // a RAM copy of the settings stored in EEPROM - -// ***************************************************************** -// public functions - -int32_t saved_settings_save(void); - -void saved_settings_init(void); - -// ***************************************************************** - -#endif diff --git a/flight/PipXtreme/inc/stopwatch.h b/flight/PipXtreme/inc/stopwatch.h deleted file mode 100644 index efc8b4d86..000000000 --- a/flight/PipXtreme/inc/stopwatch.h +++ /dev/null @@ -1,40 +0,0 @@ -/** - ****************************************************************************** - * - * @file stopwatch.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Stop watch function - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef __STOPWATCH_H__ -#define __STOPWATCH_H__ - -#include "stm32f10x.h" - -// ***************************************************************************** - -void STOPWATCH_init(uint32_t resolution); -void STOPWATCH_reset(void); -uint32_t STOPWATCH_get_count(void); -uint32_t STOPWATCH_get_us(void); - -// ***************************************************************************** - -#endif diff --git a/flight/PipXtreme/inc/stream.h b/flight/PipXtreme/inc/stream.h deleted file mode 100644 index 60245c0a7..000000000 --- a/flight/PipXtreme/inc/stream.h +++ /dev/null @@ -1,40 +0,0 @@ -/** - ****************************************************************************** - * - * @file stream.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sends or Receives a continuous packet stream to/from the remote unit - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef STREAM_H_ -#define STREAM_H_ - -#include "stdint.h" - -// ************************************************************* - -void stream_1ms_tick(void); -void stream_process(void); -void stream_deinit(void); -void stream_init(uint32_t our_sn); - -// ************************************************************* - -#endif diff --git a/flight/PipXtreme/inc/transparent_comms.h b/flight/PipXtreme/inc/transparent_comms.h deleted file mode 100644 index 7a174cbf2..000000000 --- a/flight/PipXtreme/inc/transparent_comms.h +++ /dev/null @@ -1,40 +0,0 @@ -/** - ****************************************************************************** - * - * @file transparent_comms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Serial communication port handling routines - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef __TRANSPARENT_COMMS_H__ -#define __TRANSPARENT_COMMS_H__ - -#include "stdint.h" - -// ***************************************************************************** - -void trans_1ms_tick(void); -void trans_process(void); - -void trans_init(void); - -// ***************************************************************************** - -#endif diff --git a/flight/PipXtreme/main.c b/flight/PipXtreme/main.c deleted file mode 100644 index 46b9073ea..000000000 --- a/flight/PipXtreme/main.c +++ /dev/null @@ -1,939 +0,0 @@ - -/** - ****************************************************************************** - * - * @file main.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main modem functions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -// ***************************************************************************** - -#define USE_WATCHDOG // comment this out if you don't want to use the watchdog - -// ***************************************************************************** -// OpenPilot Includes - -#include - -#include "crc.h" -#include "aes.h" -#include "rfm22b.h" -#include "packet_handler.h" -#include "stream.h" -#include "ppm.h" -#include "transparent_comms.h" -//#include "api_comms.h" -#include "api_config.h" -#include "gpio_in.h" -#include "stopwatch.h" -#include "watchdog.h" -#include "saved_settings.h" - -#include "main.h" - -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); - -// ***************************************************************************** -// ADC data - -#define ADC_REF 3.3f // ADC reference voltage -#define ADC_FULL_RANGE 4096 // 12 bit ADC - -#define ADC_PSU_RESISTOR_TOP 10000.0f // 10k upper resistor -#define ADC_PSU_RESISTOR_BOTTOM 2700.0f // 2k7 lower resistor -#define ADC_PSU_RATIO (ADC_PSU_RESISTOR_BOTTOM / (ADC_PSU_RESISTOR_TOP + ADC_PSU_RESISTOR_BOTTOM)) -#define ADC_PSU_mV_SCALE ((ADC_REF * 1000) / (ADC_FULL_RANGE * ADC_PSU_RATIO)) - -// ***************************************************************************** -// Global Variables - -uint32_t flash_size; - -char serial_number_str[25]; -uint32_t serial_number_crc32; - -uint32_t reset_addr; - -bool API_Mode; - -bool booting; - -volatile uint32_t random32; - -// ***************************************************************************** -// Local Variables - -#if defined(USE_WATCHDOG) - volatile uint16_t watchdog_timer; - uint16_t watchdog_delay; -#endif - -volatile bool inside_timer_int; -volatile uint32_t uptime_ms; - -volatile uint16_t second_tick_timer; -volatile bool second_tick; - -//volatile int32_t temp_adc; -//volatile int32_t psu_adc; - -// ***************************************************************************** - -#if defined(USE_WATCHDOG) - - void processWatchdog(void) - { - // random32 = UpdateCRC32(random32, IWDG->SR); - - if (watchdog_timer < watchdog_delay) - return; - - // the watchdog needs resetting - - watchdog_timer = 0; - - watchdog_Clear(); - } - - void enableWatchdog(void) - { // enable a watchdog - watchdog_timer = 0; - watchdog_delay = watchdog_Init(1000); // 1 second watchdog timeout - } - -#endif - -// ***************************************************************************** - -void sequenceLEDs(void) -{ - for (int i = 0; i < 2; i++) - { - USB_LED_ON; - PIOS_DELAY_WaitmS(80); - USB_LED_OFF; - - LINK_LED_ON; - PIOS_DELAY_WaitmS(80); - LINK_LED_OFF; - - RX_LED_ON; - PIOS_DELAY_WaitmS(80); - RX_LED_OFF; - - TX_LED_ON; - PIOS_DELAY_WaitmS(80); - TX_LED_OFF; - - #if defined(USE_WATCHDOG) - processWatchdog(); // process the watchdog - #endif - } -} - -// ***************************************************************************** -// timer interrupt - -void TIMER_INT_FUNC(void) -{ - inside_timer_int = TRUE; - - if (TIM_GetITStatus(TIMER_INT_TIMER, TIM_IT_Update) != RESET) - { - // Clear timer interrupt pending bit - TIM_ClearITPendingBit(TIMER_INT_TIMER, TIM_IT_Update); - -// random32 = UpdateCRC32(random32, PIOS_DELAY_GetuS() >> 8); -// random32 = UpdateCRC32(random32, PIOS_DELAY_GetuS()); - - uptime_ms++; - - #if defined(USE_WATCHDOG) - watchdog_timer++; - #endif - - // *********** - - if (!booting) - { - // *********** - - if (++second_tick_timer >= 1000) - { - second_tick_timer -= 1000; - second_tick = TRUE; - } - - // *********** - - // read the chip temperature -// temp_adc = PIOS_ADC_PinGet(0); - - // read the psu voltage -// psu_adc = PIOS_ADC_PinGet(1); - - // *********** - - uint8_t mode = saved_settings.mode; -// modeTxBlankCarrierTest, // blank carrier Tx mode (for calibrating the carrier frequency say) -// modeTxSpectrumTest // pseudo random Tx data mode (for checking the Tx carrier spectrum) - - rfm22_1ms_tick(); // rf module tick - - if (mode == MODE_NORMAL) - ph_1ms_tick(); // packet handler tick - - if (mode == MODE_STREAM_TX || mode == MODE_STREAM_RX) - stream_1ms_tick(); // continuous data stream tick - - if (mode == MODE_PPM_TX || mode == MODE_PPM_RX) - ppm_1ms_tick(); // ppm tick - - if (!API_Mode) - trans_1ms_tick(); // transparent communications tick - else -// api_1ms_tick(); // api communications tick - apiconfig_1ms_tick(); // api communications tick - - // *********** - } - } - - inside_timer_int = FALSE; -} - -void setup_TimerInt(uint16_t Hz) -{ // setup the timer interrupt - - // enable timer clock - switch ((uint32_t)TIMER_INT_TIMER) - { - case (uint32_t)TIM1: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); break; - case (uint32_t)TIM2: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); break; - case (uint32_t)TIM3: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); break; - case (uint32_t)TIM4: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); break; - #ifdef STM32F10X_HD - case (uint32_t)TIM5: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); break; - case (uint32_t)TIM6: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); break; - case (uint32_t)TIM7: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); break; - case (uint32_t)TIM8: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); break; - #endif - } - - // enable timer interrupt - NVIC_InitTypeDef NVIC_InitStructure; - switch ((uint32_t)TIMER_INT_TIMER) - { -// case (uint32_t)TIM1: NVIC_InitStructure.NVIC_IRQChannel = TIM1_IRQn; break; - case (uint32_t)TIM2: NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; break; - case (uint32_t)TIM3: NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn; break; - case (uint32_t)TIM4: NVIC_InitStructure.NVIC_IRQChannel = TIM4_IRQn; break; - #ifdef STM32F10X_HD - case (uint32_t)TIM5: NVIC_InitStructure.NVIC_IRQChannel = TIM5_IRQn; break; - case (uint32_t)TIM6: NVIC_InitStructure.NVIC_IRQChannel = TIM6_IRQn; break; - case (uint32_t)TIM7: NVIC_InitStructure.NVIC_IRQChannel = TIM7_IRQn; break; -// case (uint32_t)TIM8: NVIC_InitStructure.NVIC_IRQChannel = TIM8_IRQn; break; - #endif - } - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = TIMER_INT_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); - - // Time base configuration - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); - TIM_TimeBaseStructure.TIM_Period = (1000000 / Hz) - 1; - TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1; // For 1 uS accuracy - TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseInit(TIMER_INT_TIMER, &TIM_TimeBaseStructure); - - // Enable the CC2 Interrupt Request - TIM_ITConfig(TIMER_INT_TIMER, TIM_IT_Update, ENABLE); - - // Clear update pending flag - TIM_ClearFlag(TIMER_INT_TIMER, TIM_FLAG_Update); - - // Enable counter - TIM_Cmd(TIMER_INT_TIMER, ENABLE); -} - -// ***************************************************************************** -// read the CPU's flash and ram sizes - -void get_CPUDetails(void) -{ - // read the flash size - flash_size = (uint32_t)mem16(0x1FFFF7E0) * 1024; - - int j = 0; - - // read the CPU electronic signature (12-bytes) - serial_number_str[j] = 0; - for (int i = 0; i < 12; i++) - { - uint8_t ms_nibble = mem8(0x1ffff7e8 + i) >> 4; - uint8_t ls_nibble = mem8(0x1ffff7e8 + i) & 0x0f; - if (j > sizeof(serial_number_str) - 3) break; - serial_number_str[j++] = ((ms_nibble > 9) ? ('A' - 10) : '0') + ms_nibble; - serial_number_str[j++] = ((ls_nibble > 9) ? ('A' - 10) : '0') + ls_nibble; - serial_number_str[j] = 0; - } - - // create a 32-bit crc from the serial number hex string - serial_number_crc32 = updateCRC32Data(0xffffffff, serial_number_str, j); - serial_number_crc32 = updateCRC32(serial_number_crc32, j); - -// reset_addr = (uint32_t)&Reset_Handler; -} - -// ***************************************************************************** - -void init_RF_module(void) -{ - int i = -100; - - switch (saved_settings.frequency_band) - { - case FREQBAND_434MHz: - case FREQBAND_868MHz: - case FREQBAND_915MHz: - i = rfm22_init_normal(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz, 50000); - break; - - default: - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF("UNKNOWN BAND ERROR\r\n\r\n", i); - #endif - - for (int j = 0; j < 16; j++) - { - USB_LED_ON; - LINK_LED_OFF; - RX_LED_ON; - TX_LED_OFF; - - PIOS_DELAY_WaitmS(200); - - USB_LED_OFF; - LINK_LED_ON; - RX_LED_OFF; - TX_LED_ON; - - PIOS_DELAY_WaitmS(200); - - #if defined(USE_WATCHDOG) - processWatchdog(); - #endif - } - - PIOS_DELAY_WaitmS(1000); - - PIOS_SYS_Reset(); - - while (1); - break; - } - - if (i < 0) - { // RF module error .. flash the LED's - - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF("RF ERROR res: %d\r\n\r\n", i); - #endif - - for (int j = 0; j < 16; j++) - { - USB_LED_ON; - LINK_LED_ON; - RX_LED_OFF; - TX_LED_OFF; - - PIOS_DELAY_WaitmS(200); - - USB_LED_OFF; - LINK_LED_OFF; - RX_LED_ON; - TX_LED_ON; - - PIOS_DELAY_WaitmS(200); - - #if defined(USE_WATCHDOG) - processWatchdog(); - #endif - } - - PIOS_DELAY_WaitmS(1000); - - PIOS_SYS_Reset(); - - while (1); - } - - rfm22_setFreqCalibration(saved_settings.rf_xtal_cap); - rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz); - rfm22_setDatarate(saved_settings.max_rf_bandwidth, TRUE); - rfm22_setTxPower(saved_settings.max_tx_power); -} - -// ***************************************************************************** -// find out what caused our reset and act on it - -void processReset(void) -{ - if (RCC_GetFlagStatus(RCC_FLAG_IWDGRST) != RESET) - { // Independant Watchdog Reset - - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF("\r\nINDEPENDANT WATCHDOG CAUSED A RESET\r\n"); - #endif - - // all led's ON - USB_LED_ON; - LINK_LED_ON; - RX_LED_ON; - TX_LED_ON; - - PIOS_DELAY_WaitmS(500); // delay a bit - - // all led's OFF - USB_LED_OFF; - LINK_LED_OFF; - RX_LED_OFF; - TX_LED_OFF; - - } -/* - if (RCC_GetFlagStatus(RCC_FLAG_WWDGRST) != RESET) - { // Window Watchdog Reset - - DEBUG_PRINTF("\r\nWINDOW WATCHDOG CAUSED A REBOOT\r\n"); - - // all led's ON - USB_LED_ON; - LINK_LED_ON; - RX_LED_ON; - TX_LED_ON; - - PIOS_DELAY_WaitmS(500); // delay a bit - - // all led's OFF - USB_LED_OFF; - LINK_LED_OFF; - RX_LED_OFF; - TX_LED_OFF; - } -*/ - if (RCC_GetFlagStatus(RCC_FLAG_PORRST) != RESET) - { // Power-On Reset - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF("\r\nPOWER-ON-RESET\r\n"); - #endif - } - - if (RCC_GetFlagStatus(RCC_FLAG_SFTRST) != RESET) - { // Software Reset - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF("\r\nSOFTWARE RESET\r\n"); - #endif - } - - if (RCC_GetFlagStatus(RCC_FLAG_LPWRRST) != RESET) - { // Low-Power Reset - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF("\r\nLOW POWER RESET\r\n"); - #endif - } - - if (RCC_GetFlagStatus(RCC_FLAG_PINRST) != RESET) - { // Pin Reset - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF("\r\nPIN RESET\r\n"); - #endif - } - - // Clear reset flags - RCC_ClearFlag(); -} - -// ***************************************************************************** -// Main function - -int main() -{ - // ************* - // init various variables - - booting = TRUE; - - inside_timer_int = FALSE; - - uptime_ms = 0; - - flash_size = 0; - - serial_number_str[0] = 0; - serial_number_crc32 = 0; - - reset_addr = 0; - -// temp_adc = -1; -// psu_adc = -1; - -// API_Mode = FALSE; - API_Mode = TRUE; // TEST ONLY - - second_tick_timer = 0; - second_tick = FALSE; - - saved_settings.frequency_band = FREQBAND_UNKNOWN; - - // ************* - - PIOS_Board_Init(); - - CRC_init(); - - // read the CPU details - get_CPUDetails(); - - // setup the GPIO input pins - GPIO_IN_Init(); - - // ************* - // set various GPIO pin states - - // uart serial RTS line high - SERIAL_RTS_ENABLE; - SERIAL_RTS_SET; - - // RF module chip-select line high - RF_CS_ENABLE; - RF_CS_HIGH; - - // PPM OUT low - PPM_OUT_ENABLE; - PPM_OUT_LOW; - - // pin high - SPARE1_ENABLE; - SPARE1_HIGH; - - // pin high - SPARE2_ENABLE; - SPARE2_HIGH; - - // pin high - SPARE3_ENABLE; - SPARE3_HIGH; - - // pin high - SPARE4_ENABLE; - SPARE4_HIGH; - - // pin high - SPARE5_ENABLE; - SPARE5_HIGH; - - // ************* - - random32 ^= serial_number_crc32; // try to randomise the random number -// random32 ^= serial_number_crc32 ^ CRC_IDR; // try to randomise the random number - - trans_init(); // initialise the transparent communications module - -// api_init(); // initialise the API communications module - apiconfig_init(); // initialise the API communications module - - setup_TimerInt(1000); // setup a 1kHz timer interrupt - - #if defined(USE_WATCHDOG) - enableWatchdog(); // enable the watchdog - #endif - - // ************* - // do a simple LED flash test sequence so the user knows all the led's are working and that we have booted - - PIOS_DELAY_WaitmS(100); - - // turn all the leds off - USB_LED_OFF; - LINK_LED_OFF; - RX_LED_OFF; - TX_LED_OFF; - - PIOS_DELAY_WaitmS(200); - - sequenceLEDs(); - - // turn all the leds off - USB_LED_OFF; - LINK_LED_OFF; - RX_LED_OFF; - TX_LED_OFF; - - // ************* - - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF("\r\n"); - DEBUG_PRINTF("PipXtreme v%u.%u rebooted\r\n", VERSION_MAJOR, VERSION_MINOR); - DEBUG_PRINTF("\r\n"); - DEBUG_PRINTF("CPU flash size: %u\r\n", flash_size); - DEBUG_PRINTF("CPU serial number: %s %08X\r\n", serial_number_str, serial_number_crc32); -// DEBUG_PRINTF("Reset address: %08X\r\n", reset_addr); - #endif - - // ************* - // initialise the saved settings module - - saved_settings_init(); - - if (saved_settings.mode == 0xff || - saved_settings.mode == MODE_TX_BLANK_CARRIER_TEST || - saved_settings.mode == MODE_TX_SPECTRUM_TEST || - saved_settings.mode == MODE_SCAN_SPECTRUM) - saved_settings.mode = MODE_NORMAL; // go back to NORMAL mode - - if (saved_settings.rts_time == 0xff || saved_settings.rts_time > 100) - saved_settings.rts_time = 10; // default to 10ms - - #if !defined(PIOS_COM_DEBUG) - if (saved_settings.serial_baudrate != 0xffffffff) - PIOS_COM_ChangeBaud(PIOS_COM_SERIAL, saved_settings.serial_baudrate); - #endif - - // ************* - // read the API mode pin - - if (!GPIO_IN(API_MODE_PIN)) - API_Mode = TRUE; - - #if defined(PIOS_COM_DEBUG) - if (!API_Mode) - DEBUG_PRINTF("TRANSPARENT mode\r\n"); - else - DEBUG_PRINTF("API mode\r\n"); - #endif - - // ************* - // read the 434/868/915 jumper options - - if (!GPIO_IN(_868MHz_PIN) && !GPIO_IN(_915MHz_PIN)) saved_settings.frequency_band = FREQBAND_434MHz; // 434MHz band - else - if (!GPIO_IN(_868MHz_PIN) && GPIO_IN(_915MHz_PIN)) saved_settings.frequency_band = FREQBAND_868MHz; // 868MHz band - else - if ( GPIO_IN(_868MHz_PIN) && !GPIO_IN(_915MHz_PIN)) saved_settings.frequency_band = FREQBAND_915MHz; // 915MHz band - - // set some defaults if they are not set - switch (saved_settings.frequency_band) - { - case FREQBAND_434MHz: - - if (saved_settings.min_frequency_Hz == 0xffffffff) - { - saved_settings.frequency_Hz = 434000000; - saved_settings.min_frequency_Hz = saved_settings.frequency_Hz - 2000000; - saved_settings.max_frequency_Hz = saved_settings.frequency_Hz + 2000000; - } - if (saved_settings.max_rf_bandwidth == 0xffffffff) - { - // saved_settings.max_rf_bandwidth = 500; - // saved_settings.max_rf_bandwidth = 1000; - // saved_settings.max_rf_bandwidth = 2000; - // saved_settings.max_rf_bandwidth = 4000; - // saved_settings.max_rf_bandwidth = 8000; - // saved_settings.max_rf_bandwidth = 9600; - // saved_settings.max_rf_bandwidth = 16000; - // saved_settings.max_rf_bandwidth = 19200; - // saved_settings.max_rf_bandwidth = 24000; - // saved_settings.max_rf_bandwidth = 32000; - // saved_settings.max_rf_bandwidth = 64000; - saved_settings.max_rf_bandwidth = 128000; - // saved_settings.max_rf_bandwidth = 192000; - } - if (saved_settings.max_tx_power == 0xff) - { - saved_settings.max_tx_power = RFM22_tx_pwr_txpow_0; // +1dBm ... 1.25mW - // saved_settings.max_tx_power = RFM22_tx_pwr_txpow_1; // +2dBm ... 1.6mW - // saved_settings.max_tx_power = RFM22_tx_pwr_txpow_2; // +5dBm ... 3.16mW - // saved_settings.max_tx_power = RFM22_tx_pwr_txpow_3; // +8dBm ... 6.3mW - // saved_settings.max_tx_power = RFM22_tx_pwr_txpow_4; // +11dBm .. 12.6mW - // saved_settings.max_tx_power = RFM22_tx_pwr_txpow_5; // +14dBm .. 25mW - // saved_settings.max_tx_power = RFM22_tx_pwr_txpow_6; // +17dBm .. 50mW - // saved_settings.max_tx_power = RFM22_tx_pwr_txpow_7; // +20dBm .. 100mW - } - break; - - case FREQBAND_868MHz: - if (saved_settings.min_frequency_Hz == 0xffffffff) - { - saved_settings.frequency_Hz = 868000000; - saved_settings.min_frequency_Hz = saved_settings.frequency_Hz - 10000000; - saved_settings.max_frequency_Hz = saved_settings.frequency_Hz + 10000000; - } - if (saved_settings.max_rf_bandwidth == 0xffffffff) - saved_settings.max_rf_bandwidth = 128000; - if (saved_settings.max_tx_power == 0xff) - saved_settings.max_tx_power = RFM22_tx_pwr_txpow_0; // +1dBm ... 1.25mW - break; - - case FREQBAND_915MHz: - if (saved_settings.min_frequency_Hz == 0xffffffff) - { - saved_settings.frequency_Hz = 915000000; - saved_settings.min_frequency_Hz = saved_settings.frequency_Hz - 13000000; - saved_settings.max_frequency_Hz = saved_settings.frequency_Hz + 13000000; - } - if (saved_settings.max_rf_bandwidth == 0xffffffff) - saved_settings.max_rf_bandwidth = 128000; - if (saved_settings.max_tx_power == 0xff) - saved_settings.max_tx_power = RFM22_tx_pwr_txpow_0; // +1dBm ... 1.25mW - break; - - default: - break; - } - - #if defined(PIOS_COM_DEBUG) - switch (saved_settings.frequency_band) - { - case FREQBAND_UNKNOWN: DEBUG_PRINTF("UNKNOWN band\r\n"); break; - case FREQBAND_434MHz: DEBUG_PRINTF("434MHz band\r\n"); break; - case FREQBAND_868MHz: DEBUG_PRINTF("868MHz band\r\n"); break; - case FREQBAND_915MHz: DEBUG_PRINTF("915MHz band\r\n"); break; - } - #endif - - // ************* - - processReset(); // Determine what caused the reset/reboot - - init_RF_module(); // initialise the RF module - - // ************* - - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF("\r\n"); - DEBUG_PRINTF("RF datarate: %dbps\r\n", ph_getDatarate()); - DEBUG_PRINTF("RF frequency: %dHz\r\n", rfm22_getNominalCarrierFrequency()); - DEBUG_PRINTF("RF TX power: %d\r\n", ph_getTxPower()); - - DEBUG_PRINTF("\r\nUnit mode: "); - switch (saved_settings.mode) - { - case MODE_NORMAL: DEBUG_PRINTF("NORMAL\r\n"); break; - case MODE_STREAM_TX: DEBUG_PRINTF("STREAM-TX\r\n"); break; - case MODE_STREAM_RX: DEBUG_PRINTF("STREAM-RX\r\n"); break; - case MODE_PPM_TX: DEBUG_PRINTF("PPM-TX\r\n"); break; - case MODE_PPM_RX: DEBUG_PRINTF("PPM-RX\r\n"); break; - case MODE_SCAN_SPECTRUM: DEBUG_PRINTF("SCAN-SPECTRUM\r\n"); break; - case MODE_TX_BLANK_CARRIER_TEST: DEBUG_PRINTF("TX-BLANK-CARRIER\r\n"); break; - case MODE_TX_SPECTRUM_TEST: DEBUG_PRINTF("TX_SPECTRUM\r\n"); break; - default: DEBUG_PRINTF("UNKNOWN [%u]\r\n", saved_settings.mode); break; - } - #endif - - switch (saved_settings.mode) - { - case MODE_NORMAL: - ph_init(serial_number_crc32); // initialise the packet handler - break; - - case MODE_STREAM_TX: - case MODE_STREAM_RX: - stream_init(serial_number_crc32); // initialise the continuous packet stream module - break; - - case MODE_PPM_TX: - case MODE_PPM_RX: - ppm_init(serial_number_crc32); // initialise the ppm module - break; - - case MODE_SCAN_SPECTRUM: - case MODE_TX_BLANK_CARRIER_TEST: - case MODE_TX_SPECTRUM_TEST: - break; - } - - // ************* - // Main executive loop - - saved_settings_save(); - - booting = FALSE; - - for (;;) - { - random32 = updateCRC32(random32, PIOS_DELAY_GetuS() >> 8); - random32 = updateCRC32(random32, PIOS_DELAY_GetuS()); - - if (second_tick) - { - second_tick = FALSE; - - // ************************* - // display the up-time .. HH:MM:SS - -// #if defined(PIOS_COM_DEBUG) -// uint32_t _uptime_ms = uptime_ms; -// uint32_t _uptime_sec = _uptime_ms / 1000; -// DEBUG_PRINTF("Uptime: %02d:%02d:%02d.%03d\r\n", _uptime_sec / 3600, (_uptime_sec / 60) % 60, _uptime_sec % 60, _uptime_ms % 1000); -// #endif - - // ************************* - // process the Temperature - -// if (temp_adc >= 0) -// { -// int32_t degress_C = temp_adc; -// -// #if defined(PIOS_COM_DEBUG) -// DEBUG_PRINTF("TEMP: %d %d\r\n", temp_adc, degress_C); -// #endif -// } - - // ************************* - // process the PSU voltage level - -// if (psu_adc >= 0) -// { -// int32_t psu_mV = psu_adc * ADC_PSU_mV_SCALE; -// -// #if defined(PIOS_COM_DEBUG) -// DEBUG_PRINTF("PSU: %d, %dmV\r\n", psu_adc, psu_mV); -// #endif -// } - - // ************************* - } - - rfm22_process(); // rf hardware layer processing - - uint8_t mode = saved_settings.mode; -// modeTxBlankCarrierTest, // blank carrier Tx mode (for calibrating the carrier frequency say) -// modeTxSpectrumTest // pseudo random Tx data mode (for checking the Tx carrier spectrum) - - if (mode == MODE_NORMAL) - ph_process(); // packet handler processing - - if (mode == MODE_STREAM_TX || mode == MODE_STREAM_RX) - stream_process(); // continuous data stream processing - - if (mode == MODE_PPM_TX || mode == MODE_PPM_RX) - ppm_process(); // ppm processing - - if (!API_Mode) - trans_process(); // tranparent local communication processing (serial port and usb port) - else -// api_process(); // API local communication processing (serial port and usb port) - apiconfig_process(); // API local communication processing (serial port and usb port) - - - - - - - - - - - - - - - - - - - - - // ****************** - // TEST ONLY ... get/put data over the radio link .. speed testing .. comment out trans_process() and api_process() if testing with this -/* - int connection_index = 0; - - if (ph_connected(connection_index)) - { // we have a connection to a remote modem - - uint8_t buffer[128]; - - uint16_t num = ph_getData_used(connection_index); // number of bytes waiting for us to get - if (num > 0) - { // their is data in the received buffer - fetch it - if (num > sizeof(buffer)) num = sizeof(buffer); - num = ph_getData(connection_index, buffer, num); // fetch the received data - } - - // keep the tx buffer topped up - num = ph_putData_free(connection_index); - if (num > 0) - { // their is space available in the transmit buffer - top it up - if (num > sizeof(buffer)) num = sizeof(buffer); - for (int16_t i = 0; i < num; i++) buffer[i] = i; - num = ph_putData(connection_index, buffer, num); - } - } -*/ - // ****************** - - - - - - - - - - - - - - - - - #if defined(USE_WATCHDOG) - processWatchdog(); // process the watchdog - #endif - } - - // ************* - // we should never arrive here - - // disable all interrupts - PIOS_IRQ_Disable(); - - // turn off all leds - USB_LED_OFF; - LINK_LED_OFF; - RX_LED_OFF; - TX_LED_OFF; - - PIOS_SYS_Reset(); - - while (1); - - return 0; -} - -// ***************************************************************************** diff --git a/flight/PipXtreme/packet_handler.c b/flight/PipXtreme/packet_handler.c deleted file mode 100644 index 787a732b7..000000000 --- a/flight/PipXtreme/packet_handler.c +++ /dev/null @@ -1,1724 +0,0 @@ -/****************************************************************************** - * - * @file packet_handler.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Modem packet handling routines - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -// ******** - -// We use 128-bit AES CBC encryption if encryption is enabled - - -// encrypted packet format -// 16-byte CBC .. 1st byte must not be zero -// 4-byte source id -// 4-byte destination id -// 1-byte packet type -// 1-byte tx sequence value -// 1-byte rx sequence value -// 1-byte data size -// 4-byte crc of entire packet not including CBC bytes - - -// unencrypted packet format -// 1-byte null byte .. set to zero to indicate packet is not encrypted -// 4-byte source id -// 4-byte destination id -// 1-byte packet type -// 1-byte tx sequence value -// 1-byte rx sequence value -// 1-byte data size -// 4-byte crc of entire packet not including the null byte - -// ******** - -#include // memmove - -#include "main.h" -#include "rfm22b.h" -#include "fifo_buffer.h" -#include "aes.h" -#include "crc.h" -#include "saved_settings.h" -#include "packet_handler.h" - -#if defined(PIOS_COM_DEBUG) -// #define PACKET_DEBUG -#endif - -// ***************************************************************************** - -#define PH_FIFO_BUFFER_SIZE 2048 // FIFO buffer size - -// ***************************************************************************** - -#define AES_BLOCK_SIZE 16 // AES encryption does it in 16-byte blocks ONLY - -// default aes 128-bit encryption key -const uint8_t default_aes_key[AES_BLOCK_SIZE] = {0x65, 0x3b, 0x71, 0x89, 0x4a, 0xf4, 0xc8, 0xcb, 0x18, 0xd4, 0x9b, 0x4d, 0x4a, 0xbe, 0xc8, 0x37}; - -// ***************************************************************************** - -#define RETRY_RECONNECT_COUNT 60 // if transmission retries this many times then reset the link to the remote modem - -#define PACKET_TYPE_DATA_COMP_BIT 0x80 // data compressed bit. if set then the data in the packet is compressed -#define PACKET_TYPE_MASK 0x7f // packet type mask - -enum { - PACKET_TYPE_NONE = 0, - - PACKET_TYPE_CONNECT, // for requesting a connection - PACKET_TYPE_CONNECT_ACK, // ack - - PACKET_TYPE_DISCONNECT, // to tell the other modem they cannot connect to us - - PACKET_TYPE_DATA, // data packet (packet contains user data) - PACKET_TYPE_DATA_ACK, // ack - - PACKET_TYPE_READY, // tells the other modem we are ready to accept more data - PACKET_TYPE_READY_ACK, // ack - - PACKET_TYPE_NOTREADY, // tells the other modem we're not ready to accept more data - we can also send user data in this packet type - PACKET_TYPE_NOTREADY_ACK, // ack - - PACKET_TYPE_DATARATE, // for changing the RF data rate - PACKET_TYPE_DATARATE_ACK, // ack - - PACKET_TYPE_PING, // used to check link is still up - PACKET_TYPE_PONG, // ack - - PACKET_TYPE_ADJUST_TX_PWR, // used to ask the other modem to adjust it's tx power - PACKET_TYPE_ADJUST_TX_PWR_ACK // ack -}; - -#define BROADCAST_ADDR 0xffffffff - -//#pragma pack(push) -//#pragma pack(1) - -typedef struct -{ - uint32_t source_id; - uint32_t destination_id; - uint8_t type; - uint8_t tx_seq; - uint8_t rx_seq; - uint8_t data_size; - uint32_t crc; -} __attribute__((__packed__)) t_packet_header; - -// this structure must be a multiple of 'AES_BLOCK_SIZE' bytes in size and no more than 255 bytes in size -typedef struct -{ - uint8_t cbc[AES_BLOCK_SIZE]; // AES encryption Cipher-Block-Chaining key .. 1st byte must not be zero - to indicate the packet is encrypted - t_packet_header header; - uint8_t data[240 - sizeof(t_packet_header) - AES_BLOCK_SIZE]; -} __attribute__((__packed__)) t_encrypted_packet; - -// this structure must be no more than 255 bytes in size (255 = the maximum packet size) -typedef struct -{ - uint8_t null_byte; // this must be set to zero - to indicate the packet is unencrypted - t_packet_header header; - uint8_t data[255 - sizeof(t_packet_header) - 1]; -} __attribute__((__packed__)) t_unencrypted_packet; - -//#pragma pack(pop) - -// ***************************************************************************** -// link state for each remote connection - -enum { - LINK_DISCONNECTED = 0, - LINK_CONNECTING, - LINK_CONNECTED -}; - -typedef struct -{ - uint32_t serial_number; // their serial number - - uint8_t tx_buffer[PH_FIFO_BUFFER_SIZE] __attribute__ ((aligned(4))); - t_fifo_buffer tx_fifo_buffer; // holds the data to be transmitted to the other modem - - uint8_t rx_buffer[PH_FIFO_BUFFER_SIZE] __attribute__ ((aligned(4))); - t_fifo_buffer rx_fifo_buffer; // holds the data received from the other modem - - uint8_t link_state; // holds our current RF link state - - uint8_t tx_sequence; // incremented with each data packet transmitted, sent in every packet transmitted - uint8_t tx_sequence_data_size; // the size of data we sent in our last packet - - uint8_t rx_sequence; // incremented with each data packet received contain data, sent in every packet transmitted - - volatile uint16_t tx_packet_timer; // ms .. used for packet timing - - uint16_t tx_retry_time_slots; // add's some random packet transmission timing - to try to prevent transmission collisions - uint16_t tx_retry_time_slot_len; // ms .. " " " - uint16_t tx_retry_time; // ms .. " " " - uint16_t tx_retry_counter; // incremented on each transmission, reset back to '0' when we receive an ack to our transmission - - volatile uint16_t data_speed_timer; // used for calculating the transmit/receive data rate - volatile uint32_t tx_data_speed_count; // incremented with the number of data bits we send in our transmit packets - volatile uint32_t tx_data_speed; // holds the number of data bits we have sent each second - volatile uint32_t rx_data_speed_count; // incremented with the number of data bits we send in our transmit packets - volatile uint32_t rx_data_speed; // holds the number of data bits we have received each second - - uint16_t ping_time; // ping timer - uint16_t fast_ping_time; // ping timer - bool pinging; // TRUE if we are doing a ping test with the other modem - to check if it is still present - - bool rx_not_ready_mode; // TRUE if we have told the other modem we cannot receive data (due to buffer filling up). - // we set it back to FALSE when our received buffer starts to empty - - volatile int16_t ready_to_send_timer; // ms .. used to hold off packet transmission to wait a bit for data to mount up for transmission (improves data thru-put speed) - - volatile int32_t not_ready_timer; // ms .. >= 0 while we have been asked not to send anymore data to the other modem, -1 when we are allowed to send data - - bool send_encrypted; // TRUE if we are to AES encrypt in every packet we transmit - - int16_t rx_rssi_dBm; // the strength of the received packet - int32_t rx_afc_Hz; // the frequency offset of the received packet - -} t_connection; - -// ***************************************************************************** - -uint32_t our_serial_number = 0; // our serial number - -t_connection connection[PH_MAX_CONNECTIONS]; // holds each connection state - -uint8_t aes_key[AES_BLOCK_SIZE] __attribute__ ((aligned(4))); // holds the aes encryption key - the same for ALL connections -uint8_t dec_aes_key[AES_BLOCK_SIZE] __attribute__ ((aligned(4))); // holds the pre-calculated decryption key -uint8_t enc_cbc[AES_BLOCK_SIZE] __attribute__ ((aligned(4))); // holds the tx aes cbc bytes - -uint8_t ph_tx_buffer[256] __attribute__ ((aligned(4))); // holds the transmit packet - -uint8_t ph_rx_buffer[256] __attribute__ ((aligned(4))); // holds the received packet - -int16_t rx_rssi_dBm; -int32_t rx_afc_Hz; - -bool fast_ping; - -// ***************************************************************************** -// return TRUE if we are connected to the remote modem - -bool ph_connected(const int connection_index) -{ - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return FALSE; - - t_connection *conn = &connection[connection_index]; - - return (conn->link_state == LINK_CONNECTED); -} - -// ***************************************************************************** -// public tx buffer functions - -uint16_t ph_putData_free(const int connection_index) -{ // return the free space size - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return 0; - - return fifoBuf_getFree(&connection[connection_index].tx_fifo_buffer); -} - -uint16_t ph_putData(const int connection_index, const void *data, uint16_t len) -{ // add data to our tx buffer to be sent - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return 0; - - return fifoBuf_putData(&connection[connection_index].tx_fifo_buffer, data, len); -} - -// ***************************************************************************** -// public rx buffer functions - -uint16_t ph_getData_used(const int connection_index) -{ // return the number of bytes available in the rx buffer - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return 0; - - return fifoBuf_getUsed(&connection[connection_index].rx_fifo_buffer); -} - -uint16_t ph_getData(const int connection_index, void *data, uint16_t len) -{ // get data from our rx buffer - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return 0; - - return fifoBuf_getData(&connection[connection_index].rx_fifo_buffer, data, len); -} - -// ***************************************************************************** -// start a connection to another modem - -int ph_startConnect(int connection_index, uint32_t sn) -{ - random32 = updateCRC32(random32, 0xff); - - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return -1; - - t_connection *conn = &connection[connection_index]; - - conn->link_state = LINK_DISCONNECTED; - - LINK_LED_OFF; - - conn->serial_number = sn; - - conn->tx_sequence = 0; - conn->tx_sequence_data_size = 0; - conn->rx_sequence = 0; - -// fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE); -// fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE); - - conn->tx_packet_timer = 0; - - conn->tx_retry_time_slots = 5; - - uint32_t ms = 1280000ul / rfm22_getDatarate(); - if (ms < 10) ms = 10; - else - if (ms > 32000) ms = 32000; - conn->tx_retry_time_slot_len = ms; - - conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4; - - conn->tx_retry_counter = 0; - - conn->data_speed_timer = 0; - conn->tx_data_speed_count = 0; - conn->tx_data_speed = 0; - conn->rx_data_speed_count = 0; - conn->rx_data_speed = 0; - - conn->ping_time = 8000 + (random32 % 100) * 10; - conn->fast_ping_time = 600 + (random32 % 50) * 10; - conn->pinging = false; - - conn->rx_not_ready_mode = false; - - conn->ready_to_send_timer = -1; - - conn->not_ready_timer = -1; - -// conn->send_encrypted = true; -// conn->send_encrypted = false; - - conn->rx_rssi_dBm = -200; - conn->rx_afc_Hz = 0; - - if (sn != 0 && sn == our_serial_number) - return -2; // same as our own - - if (sn == BROADCAST_ADDR) - { - - return -3; - } - - if (conn->serial_number != 0) - conn->link_state = LINK_CONNECTING; - - return connection_index; -} - -// ***************************************************************************** -// return a byte for the tx packet transmission. -// -// return value < 0 if no more bytes available, otherwise return byte to be sent - -int16_t ph_TxDataByteCallback(void) -{ - return -1; -} - -// ************************************************************* -// we are being given a block of received bytes -// -// return TRUE to continue current packet receive, otherwise return FALSE to halt current packet reception - -bool ph_RxDataCallback(void *data, uint8_t len) -{ - return true; -} - -// ***************************************************************************** -// transmit a packet - -bool ph_sendPacket(int connection_index, bool encrypt, uint8_t packet_type, bool send_immediately) -{ - uint8_t key[AES_BLOCK_SIZE]; - - t_connection *conn = NULL; - - // *********** - - t_encrypted_packet *encrypted_packet = (t_encrypted_packet*)&ph_tx_buffer; // point to the tx buffer - t_unencrypted_packet *unencrypted_packet = (t_unencrypted_packet*)&ph_tx_buffer; // point to the tx buffer - - t_packet_header *header; - uint8_t *data; - uint16_t max_data_size; - - if (encrypt) - { - header = (t_packet_header *)&encrypted_packet->header; - data = (uint8_t *)&encrypted_packet->data; - max_data_size = sizeof(encrypted_packet->data); - } - else - { - header = (t_packet_header *)&unencrypted_packet->header; - data = (uint8_t *)&unencrypted_packet->data; - max_data_size = sizeof(unencrypted_packet->data); - } - - // *********** - - if (!rfm22_txReady()) - return false; - - if ((packet_type & PACKET_TYPE_MASK) == PACKET_TYPE_NONE) - return false; - - if (connection_index >= PH_MAX_CONNECTIONS) - return false; - - if (connection_index >= 0) - conn = (t_connection *)&connection[connection_index]; - else - return false; - - // ****************** - // stuff - - uint8_t pack_type = packet_type & PACKET_TYPE_MASK; - - bool data_packet = (pack_type == PACKET_TYPE_DATA || pack_type == PACKET_TYPE_NOTREADY); - - // ****************** - // calculate how many user data bytes we are going to add to the packet - - uint16_t data_size = 0; - - if (data_packet && conn) - { // we're adding user data to the packet - data_size = fifoBuf_getUsed(&connection[connection_index].tx_fifo_buffer); // the number of data bytes waiting to be sent - - if (data_size > max_data_size) - data_size = max_data_size; - - if (conn->tx_sequence_data_size > 0) - { // we are re-sending data the same data - if (data_size > conn->tx_sequence_data_size) - data_size = conn->tx_sequence_data_size; - } - } - - // ****************** - // calculate the total packet size (including null data bytes if we have to add null data byte in AES encrypted packets) - - uint32_t packet_size; - - if (encrypt) - { - packet_size = AES_BLOCK_SIZE + sizeof(t_packet_header) + data_size; - - // total packet size must be a multiple of 'AES_BLOCK_SIZE' bytes - aes encryption works on 16-byte blocks - packet_size = (packet_size + (AES_BLOCK_SIZE - 1)) & ~(AES_BLOCK_SIZE - 1); - } - else - { - packet_size = 1 + sizeof(t_packet_header) + data_size; - } - - // ****************** - // construct the packets entire header - - if (encrypt) - { - memmove(key, aes_key, sizeof(key)); // fetch the encryption key - aes_encrypt_cbc_128(enc_cbc, key, NULL); // help randomize the CBC bytes - - // ensure the 1st byte is not zero - to indicate this packet is encrypted - while (enc_cbc[0] == 0) - { - random32 = updateCRC32(random32, 0xff); - enc_cbc[0] ^= random32; - } - - memmove(encrypted_packet->cbc, enc_cbc, AES_BLOCK_SIZE); // copy the AES CBC bytes into the packet - } - else - unencrypted_packet->null_byte = 0; // packet is not encrypted - - header->source_id = our_serial_number; // our serial number -// header->destination_id = BROADCAST_ADDR; // broadcast packet - header->destination_id = conn->serial_number; // the other modems serial number - header->type = packet_type; // packet type - header->tx_seq = conn->tx_sequence; // our TX sequence number - header->rx_seq = conn->rx_sequence; // our RX sequence number - header->data_size = data_size; // the number of user data bytes in the packet - header->crc = 0; // the CRC of the header and user data bytes - - // ****************** - // add the user data to the packet - - if (data_packet) - { // we're adding user data to the packet - fifoBuf_getDataPeek(&connection[connection_index].tx_fifo_buffer, data, data_size); - - if (encrypt) - { // zero unused bytes - if (data_size < max_data_size) - memset(data + data_size, 0, max_data_size - data_size); - } - - conn->tx_sequence_data_size = data_size; // remember how much data we are sending in this packet - } - - // ****************** - // complete the packet header by adding the CRC - - if (encrypt) - header->crc = updateCRC32Data(0xffffffff, header, packet_size - AES_BLOCK_SIZE); - else - header->crc = updateCRC32Data(0xffffffff, header, packet_size - 1); - - // ****************** - // encrypt the packet - - if (encrypt) - { // encrypt the packet .. 'AES_BLOCK_SIZE' bytes at a time - uint8_t *p = (uint8_t *)encrypted_packet; - - // encrypt the cbc - memmove(key, aes_key, sizeof(key)); // fetch the encryption key - aes_encrypt_cbc_128(p, key, NULL); // encrypt block of data (the CBC bytes) - p += AES_BLOCK_SIZE; - - // encrypt the rest of the packet - for (uint16_t i = AES_BLOCK_SIZE; i < packet_size; i += AES_BLOCK_SIZE) - { - memmove(key, aes_key, sizeof(key)); // fetch the encryption key - aes_encrypt_cbc_128(p, key, enc_cbc); // encrypt block of data - p += AES_BLOCK_SIZE; - } - } - - // ****************** - // send the packet - - int32_t res = rfm22_sendData(&ph_tx_buffer, packet_size, send_immediately); - - // ****************** - - if (data_size > 0 && conn->tx_retry_counter == 0) - conn->tx_data_speed_count += data_size * 8; // + the number of data bits we just sent .. used for calculating the transmit data rate - - // ****************** - // debug stuff - -#if defined(PACKET_DEBUG) - - DEBUG_PRINTF("T-PACK "); - switch (pack_type) - { - case PACKET_TYPE_NONE: DEBUG_PRINTF("none"); break; - case PACKET_TYPE_CONNECT: DEBUG_PRINTF("connect"); break; - case PACKET_TYPE_CONNECT_ACK: DEBUG_PRINTF("connect_ack"); break; - case PACKET_TYPE_DISCONNECT: DEBUG_PRINTF("disconnect"); break; - case PACKET_TYPE_DATA: DEBUG_PRINTF("data"); break; - case PACKET_TYPE_DATA_ACK: DEBUG_PRINTF("data_ack"); break; - case PACKET_TYPE_READY: DEBUG_PRINTF("ready"); break; - case PACKET_TYPE_READY_ACK: DEBUG_PRINTF("ready_ack"); break; - case PACKET_TYPE_NOTREADY: DEBUG_PRINTF("notready"); break; - case PACKET_TYPE_NOTREADY_ACK: DEBUG_PRINTF("notready_ack"); break; - case PACKET_TYPE_DATARATE: DEBUG_PRINTF("datarate"); break; - case PACKET_TYPE_DATARATE_ACK: DEBUG_PRINTF("datarate_ack"); break; - case PACKET_TYPE_PING: DEBUG_PRINTF("ping"); break; - case PACKET_TYPE_PONG: DEBUG_PRINTF("pong"); break; - case PACKET_TYPE_ADJUST_TX_PWR: DEBUG_PRINTF("PACKET_TYPE_ADJUST_TX_PWR"); break; - case PACKET_TYPE_ADJUST_TX_PWR_ACK: DEBUG_PRINTF("PACKET_TYPE_ADJUST_TX_PWR_ACK"); break; - default: DEBUG_PRINTF("UNKNOWN [%d]", pack_type); break; - } - DEBUG_PRINTF(" tseq:%d rseq:%d", conn->tx_sequence, conn->rx_sequence); - DEBUG_PRINTF(" drate:%dbps", conn->tx_data_speed); - if (data_size > 0) DEBUG_PRINTF(" data_size:%d", data_size); - if (conn->tx_retry_counter > 0) DEBUG_PRINTF(" retry:%d", conn->tx_retry_counter); - DEBUG_PRINTF("\r\n"); -#endif - - // ****************** - - switch (pack_type) - { - case PACKET_TYPE_CONNECT: - case PACKET_TYPE_DISCONNECT: - case PACKET_TYPE_DATA: - case PACKET_TYPE_READY: - case PACKET_TYPE_NOTREADY: - case PACKET_TYPE_DATARATE: - case PACKET_TYPE_PING: - case PACKET_TYPE_ADJUST_TX_PWR: - if (conn->tx_retry_counter < 0xffff) - conn->tx_retry_counter++; - break; - - case PACKET_TYPE_CONNECT_ACK: - case PACKET_TYPE_DATA_ACK: - case PACKET_TYPE_READY_ACK: - case PACKET_TYPE_NOTREADY_ACK: - case PACKET_TYPE_DATARATE_ACK: - case PACKET_TYPE_PONG: - case PACKET_TYPE_ADJUST_TX_PWR_ACK: - break; - - case PACKET_TYPE_NONE: - break; - } - - return (res >= packet_size); -} - -// ***************************************************************************** - -void ph_processPacket2(bool was_encrypted, t_packet_header *header, uint8_t *data) -{ // process the received decrypted error-free packet - - USB_LED_TOGGLE; // TEST ONLY - - // *********** - - // fetch the data compressed bit - bool compressed_data = (header->type & PACKET_TYPE_DATA_COMP_BIT) != 0; - - // fetch the packet type - uint8_t packet_type = header->type & PACKET_TYPE_MASK; - - // fetch the number of data bytes in the packet - uint16_t data_size = header->data_size; - - // update the ramdon number - random32 = updateCRC32(random32, 0xff); - - // ********************* - // debug stuff -/* -#if defined(PACKET_DEBUG) - if (data_size > 0) - { - DEBUG_PRINTF("rx packet:"); - for (uint16_t i = 0; i < data_size; i++) - DEBUG_PRINTF(" %u", data[i]); - DEBUG_PRINTF("\r\n"); - } -#endif -*/ - // *********** - // debug stuff - -#if defined(PACKET_DEBUG) - DEBUG_PRINTF("R-PACK "); - switch (packet_type) - { - case PACKET_TYPE_NONE: DEBUG_PRINTF("none"); break; - case PACKET_TYPE_CONNECT: DEBUG_PRINTF("connect"); break; - case PACKET_TYPE_CONNECT_ACK: DEBUG_PRINTF("connect_ack"); break; - case PACKET_TYPE_DISCONNECT: DEBUG_PRINTF("disconnect"); break; - case PACKET_TYPE_DATA: DEBUG_PRINTF("data"); break; - case PACKET_TYPE_DATA_ACK: DEBUG_PRINTF("data_ack"); break; - case PACKET_TYPE_READY: DEBUG_PRINTF("ready"); break; - case PACKET_TYPE_READY_ACK: DEBUG_PRINTF("ready_ack"); break; - case PACKET_TYPE_NOTREADY: DEBUG_PRINTF("notready"); break; - case PACKET_TYPE_NOTREADY_ACK: DEBUG_PRINTF("notready_ack"); break; - case PACKET_TYPE_DATARATE: DEBUG_PRINTF("datarate"); break; - case PACKET_TYPE_DATARATE_ACK: DEBUG_PRINTF("datarate_ack"); break; - case PACKET_TYPE_PING: DEBUG_PRINTF("ping"); break; - case PACKET_TYPE_PONG: DEBUG_PRINTF("pong"); break; - case PACKET_TYPE_ADJUST_TX_PWR: DEBUG_PRINTF("PACKET_TYPE_ADJUST_TX_PWR"); break; - case PACKET_TYPE_ADJUST_TX_PWR_ACK: DEBUG_PRINTF("PACKET_TYPE_ADJUST_TX_PWR_ACK"); break; - default: DEBUG_PRINTF("UNKNOWN [%d]", packet_type); break; - } - DEBUG_PRINTF(" tseq-%d rseq-%d", header->tx_seq, header->rx_seq); -// DEBUG_PRINTF(" drate:%dbps", conn->rx_data_speed); - if (data_size > 0) DEBUG_PRINTF(" data_size:%d", data_size); - DEBUG_PRINTF(" %ddBm", rx_rssi_dBm); - DEBUG_PRINTF(" %dHz", rx_afc_Hz); - DEBUG_PRINTF("\r\n"); -#endif - - // ********************* - - if (header->source_id == our_serial_number) - return; // it's our own packet .. ignore it - - if (header->destination_id == BROADCAST_ADDR) - { // it's a broadcast packet - - - - // todo: - - - - - return; - } - - if (header->destination_id != our_serial_number) - return; // the packet is not meant for us - - // ********************* - // find out which remote connection this packet is from - - int connection_index = 0; - while (connection_index < PH_MAX_CONNECTIONS) - { - uint32_t sn = connection[connection_index].serial_number; - if (sn != 0) - { // connection used - if (header->source_id == sn) - break; // found it - } - connection_index++; - } - - if (connection_index >= PH_MAX_CONNECTIONS) - { // the packet is from an unknown source ID (unknown modem) - - if (packet_type != PACKET_TYPE_NONE) - { // send a disconnect packet back to them -// ph_sendPacket(-1, was_encrypted, PACKET_TYPE_DISCONNECT, true); - } - - return; - } - - t_connection *conn = &connection[connection_index]; - - // *********** - - conn->rx_rssi_dBm = rx_rssi_dBm; // remember the packets signal strength - conn->rx_afc_Hz = rx_afc_Hz; // remember the packets frequency offset - - // *********** - // decompress the data - - if (compressed_data && data_size > 0) - { - - - // todo: - - - } - - // *********** - - if (packet_type == PACKET_TYPE_NONE) - return; - - if (packet_type == PACKET_TYPE_DISCONNECT) - { - conn->link_state = LINK_DISCONNECTED; - LINK_LED_OFF; - return; - } - - if (packet_type == PACKET_TYPE_CONNECT) - { - LINK_LED_ON; - -// fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE); -// fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE); - - conn->tx_packet_timer = 0; - - conn->tx_retry_counter = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len; - - conn->rx_sequence = header->tx_seq; - conn->tx_sequence = 0; - conn->tx_sequence_data_size = 0; - - conn->data_speed_timer = 0; - conn->tx_data_speed_count = 0; - conn->tx_data_speed = 0; - conn->rx_data_speed_count = 0; - conn->rx_data_speed = 0; - - conn->ping_time = 8000 + (random32 % 100) * 10; - conn->fast_ping_time = 600 + (random32 % 50) * 10; - conn->pinging = false; - - conn->rx_not_ready_mode = false; - - conn->ready_to_send_timer = -1; - - conn->not_ready_timer = -1; - - conn->link_state = LINK_CONNECTED; - - // send an ack back - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_CONNECT_ACK, true)) - { - conn->tx_packet_timer = 0; - } - - return; - } - - if (packet_type == PACKET_TYPE_CONNECT_ACK) - { - LINK_LED_ON; - - if (conn->link_state != LINK_CONNECTING) - { // reset the link - ph_set_remote_serial_number(connection_index, conn->serial_number); - return; - } - - conn->tx_packet_timer = 0; - - conn->tx_retry_counter = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len; - - conn->rx_sequence = header->tx_seq; - conn->tx_sequence = 0; - conn->tx_sequence_data_size = 0; - - conn->data_speed_timer = 0; - conn->tx_data_speed_count = 0; - conn->tx_data_speed = 0; - conn->rx_data_speed_count = 0; - conn->rx_data_speed = 0; - - conn->ping_time = 8000 + (random32 % 100) * 10; - conn->fast_ping_time = 600 + (random32 % 50) * 10; - conn->pinging = false; - - conn->rx_not_ready_mode = false; - - conn->ready_to_send_timer = -1; - - conn->not_ready_timer = -1; - - conn->link_state = LINK_CONNECTED; - - return; - } - - - - - if (conn->link_state == LINK_CONNECTING) - { // we are trying to connect to them .. reply with a connect request packet - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_CONNECT, true)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4; - } - return; - } - - if (conn->link_state != LINK_CONNECTED) - { // they have sent us a packet when we are not in a connected state - start a connection - ph_startConnect(connection_index, conn->serial_number); - return; - } - - - - - // check to make sure it's a wanted packet type - switch (packet_type) - { - case PACKET_TYPE_DATA: - case PACKET_TYPE_DATA_ACK: - case PACKET_TYPE_READY: - case PACKET_TYPE_READY_ACK: - case PACKET_TYPE_NOTREADY: - case PACKET_TYPE_NOTREADY_ACK: - case PACKET_TYPE_DATARATE: - case PACKET_TYPE_DATARATE_ACK: - case PACKET_TYPE_PING: - case PACKET_TYPE_PONG: - case PACKET_TYPE_ADJUST_TX_PWR: - case PACKET_TYPE_ADJUST_TX_PWR_ACK: - break; - default: - return; - } - - - - - - if ((conn->tx_sequence_data_size > 0) && (header->rx_seq == (uint8_t)(conn->tx_sequence + 1))) - { // they received our last data packet - - // remove the data we have sent and they have acked - fifoBuf_removeData(&conn->tx_fifo_buffer, conn->tx_sequence_data_size); - - conn->tx_sequence++; - conn->tx_retry_counter = 0; - conn->tx_sequence_data_size = 0; - conn->not_ready_timer = -1; // stop timer - } - - uint16_t size = fifoBuf_getUsed(&conn->tx_fifo_buffer); // the size of data waiting to be sent - - - - - if (packet_type == PACKET_TYPE_DATA || packet_type == PACKET_TYPE_DATA_ACK) - { - if (packet_type == PACKET_TYPE_DATA && header->tx_seq == conn->rx_sequence) - { // the packet number is what we expected - - if (data_size > 0) - { // save the data - - conn->rx_data_speed_count += data_size * 8; // + the number of data bits we just received - - uint16_t num = fifoBuf_getFree(&conn->rx_fifo_buffer); - if (num < data_size) - { // error .. we don't have enough space left in our fifo buffer to save the data .. discard it and tell them to hold off a sec -// conn->rx_not_ready_mode = true; - } - else - { // save the received data into our fifo buffer - fifoBuf_putData(&conn->rx_fifo_buffer, data, data_size); - conn->rx_sequence++; - conn->rx_not_ready_mode = false; - } - } - } - - if (size >= 200 || (conn->ready_to_send_timer >= 10 && size > 0) || (conn->tx_sequence_data_size > 0 && size > 0)) - { // send data - uint8_t pack_type = PACKET_TYPE_DATA; - if (conn->rx_not_ready_mode) - pack_type = PACKET_TYPE_NOTREADY; - - if (ph_sendPacket(connection_index, conn->send_encrypted, pack_type, true)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len; - return; - } - } - - if (packet_type == PACKET_TYPE_DATA) - { // send an ack back - uint8_t pack_type = PACKET_TYPE_DATA_ACK; - if (conn->rx_not_ready_mode) - pack_type = PACKET_TYPE_NOTREADY_ACK; - - if (ph_sendPacket(connection_index, conn->send_encrypted, pack_type, true)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len; - return; - } - } - - return; - } - - if (packet_type == PACKET_TYPE_READY) - { - conn->not_ready_timer = -1; // stop timer - - // send an ack back - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_READY_ACK, true)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4; - return; - } - - return; - } - - if (packet_type == PACKET_TYPE_READY_ACK) - { - conn->rx_not_ready_mode = false; - return; - } - - if (packet_type == PACKET_TYPE_NOTREADY) - { -// conn->not_ready_timer = 0; // start timer - - if (header->tx_seq == conn->rx_sequence) - { // the packet number is what we expected - - if (data_size > 0) - { // save the data - - conn->rx_data_speed_count += data_size * 8; // + the number of data bits we just received - - uint16_t num = fifoBuf_getFree(&conn->rx_fifo_buffer); - if (num < data_size) - { // error .. we don't have enough space left in our fifo buffer to save the data .. discard it and tell them to hold off a sec -// conn->rx_not_ready_mode = true; - } - else - { // save the received data into our fifo buffer - fifoBuf_putData(&conn->rx_fifo_buffer, data, data_size); - conn->rx_sequence++; - conn->rx_not_ready_mode = false; - } - } - } - - // send an ack back - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_NOTREADY_ACK, true)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4; - return; - } - - return; - } - - if (packet_type == PACKET_TYPE_NOTREADY_ACK) - { - return; - } - - if (packet_type == PACKET_TYPE_PING) - { // send a pong back - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_PONG, true)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len; - } - return; - } - - if (packet_type == PACKET_TYPE_PONG) - { - if (conn->pinging) - { - conn->pinging = false; - conn->tx_retry_counter = 0; - } - return; - } - - if (packet_type == PACKET_TYPE_DATARATE) - { - // send an ack back - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_DATARATE_ACK, true)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len; - } - return; - } - - if (packet_type == PACKET_TYPE_DATARATE_ACK) - { - return; - } - - if (packet_type == PACKET_TYPE_ADJUST_TX_PWR) - { - // send an ack back - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_ADJUST_TX_PWR_ACK, true)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len; - } - return; - } - - if (packet_type == PACKET_TYPE_ADJUST_TX_PWR_ACK) - { - return; - } - - // ********************* -} - -void ph_processRxPacket(void) -{ - uint32_t crc1, crc2; - uint8_t key[AES_BLOCK_SIZE]; - register uint8_t *p; - - // *********** - // fetch the received packet - - uint16_t packet_size = rfm22_receivedLength(); - if (packet_size == 0) - return; // nothing received - - if (packet_size > sizeof(ph_rx_buffer)) - { // packet too big .. discard it - rfm22_receivedDone(); - return; - } - - rx_rssi_dBm = rfm22_receivedRSSI(); // fetch the packets signal stength - rx_afc_Hz = rfm22_receivedAFCHz(); // fetch the packets frequency offset - - // copy the received packet into our own buffer - memmove(ph_rx_buffer, rfm22_receivedPointer(), packet_size); - - rfm22_receivedDone(); // the received packet has been saved - - // ********************* - // if the 1st byte in the packet is not zero, then the packet is encrypted - - bool encrypted = (ph_rx_buffer[0] != 0); - - // *********** - - t_encrypted_packet *encrypted_packet = (t_encrypted_packet *)&ph_rx_buffer; // point to the rx buffer - t_unencrypted_packet *unencrypted_packet = (t_unencrypted_packet *)&ph_rx_buffer; // point to the rx buffer - - t_packet_header *header; - uint8_t *data; - uint16_t min_packet_size; - uint16_t max_data_size; - - if (encrypted) - { - header = (t_packet_header *)&encrypted_packet->header; - data = (uint8_t *)&encrypted_packet->data; - min_packet_size = AES_BLOCK_SIZE + sizeof(t_packet_header); - max_data_size = sizeof(encrypted_packet->data); - } - else - { - header = (t_packet_header *)&unencrypted_packet->header; - data = (uint8_t *)&unencrypted_packet->data; - min_packet_size = 1 + sizeof(t_packet_header); - max_data_size = sizeof(unencrypted_packet->data); - } - - if (packet_size < min_packet_size) - { // packet too small .. discard it - return; - } - - random32 = updateCRC32(random32 ^ header->crc, 0xff); // help randomize the random number - - // ********************* - // help to randomize the tx aes cbc bytes by using the received packet - - p = (uint8_t *)&ph_rx_buffer; - for (uint16_t i = 0; i < packet_size; i += AES_BLOCK_SIZE) - { - for (int j = AES_BLOCK_SIZE - 1; j >= 0; j--) - enc_cbc[j] ^= *p++; - } - - // ********************* - // check the packet size - - if (encrypted) - { - if ((packet_size & (AES_BLOCK_SIZE - 1)) != 0) - return; // packet must be a multiple of 'AES_BLOCK_SIZE' bytes in length - for the aes decryption - } - - // ********************* - // decrypt the packet - - if (encrypted) - { - p = (uint8_t *)encrypted_packet; // point to the received packet - - // decrypt the cbc - memmove(key, (void *)dec_aes_key, sizeof(key)); // fetch the decryption key - aes_decrypt_cbc_128(p, key, NULL); // decrypt the cbc bytes - p += AES_BLOCK_SIZE; - - // decrypt the rest of the packet - for (uint16_t i = AES_BLOCK_SIZE; i < packet_size; i += AES_BLOCK_SIZE) - { - memmove(key, (void *)dec_aes_key, sizeof(key)); // fetch the decryption key - aes_decrypt_cbc_128(p, key, (void *)encrypted_packet->cbc); - p += AES_BLOCK_SIZE; - } - } - - // ********************* - -#if defined(PACKET_DEBUG) - DEBUG_PRINTF("rx packet: "); - DEBUG_PRINTF("%s", encrypted ? "encrypted " : "unencrypted"); - if (encrypted) - { - for (int i = 0; i < AES_BLOCK_SIZE; i++) - DEBUG_PRINTF("%02X", encrypted_packet->cbc[i]); - } - DEBUG_PRINTF(" %08X %08X %u %u %u %u %08X\r\n", - header->source_id, - header->destination_id, - header->type, - header->tx_seq, - header->rx_seq, - header->data_size, - header->crc); - - if (header->data_size > 0) - { - DEBUG_PRINTF("rx packet [%u]: ", header->data_size); - for (int i = 0; i < header->data_size; i++) - DEBUG_PRINTF("%02X", data[i]); - DEBUG_PRINTF("\r\n"); - } -#endif - - // ********************* - - uint32_t data_size = header->data_size; - - if (packet_size < (min_packet_size + data_size)) - return; // packet too small - -#if defined(PACKET_DEBUG) -// DEBUG_PRINTF("rx packet size: %d\r\n", packet_size); -#endif - - // ********************* - // check the packet is error free - - crc1 = header->crc; - header->crc = 0; - if (encrypted) - crc2 = updateCRC32Data(0xffffffff, header, packet_size - AES_BLOCK_SIZE); - else - crc2 = updateCRC32Data(0xffffffff, header, packet_size - 1); - if (crc1 != crc2) - { // corrupt packet - #if defined(PACKET_DEBUG) - if (encrypted) - DEBUG_PRINTF("ENC-R-PACK corrupt %08X %08X\r\n", crc1, crc2); - else - DEBUG_PRINTF("R-PACK corrupt %08X %08X\r\n", crc1, crc2); - #endif - return; - } - - // ********************* - // process the data - - ph_processPacket2(encrypted, header, data); - - // ********************* -} - -// ***************************************************************************** -// do all the link/packet handling stuff - request connection/disconnection, send data, acks etc - -void ph_processLinks(int connection_index) -{ - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return; - - random32 = updateCRC32(random32, 0xff); - - t_connection *conn = &connection[connection_index]; - - bool canTx = (!rfm22_transmitting() && rfm22_channelIsClear());// TRUE is we can transmit - - bool timeToRetry = (rfm22_txReady() && conn->tx_packet_timer >= conn->tx_retry_time); - - bool tomanyRetries = (conn->tx_retry_counter >= RETRY_RECONNECT_COUNT); - - if (conn->tx_retry_counter > 3) - conn->rx_rssi_dBm = -200; - - switch (conn->link_state) - { - case LINK_DISCONNECTED: - if (!canTx) - { - conn->tx_packet_timer = 0; - break; - } - - if (!rfm22_txReady() || conn->tx_packet_timer < 60000) - break; - - if (our_serial_number != 0 && conn->serial_number != 0) - { // try to reconnect with the remote modem - ph_startConnect(connection_index, conn->serial_number); - break; - } - - break; - - case LINK_CONNECTING: - if (!canTx) - { - conn->tx_packet_timer = 0; - break; - } - - if (!timeToRetry) - break; - - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_CONNECT, false)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4; - break; - } - - break; - - case LINK_CONNECTED: - if (!canTx) - { - conn->tx_packet_timer = 0; - break; - } - - if (!timeToRetry) - break; - - if (tomanyRetries) - { // reset the link if we have sent tomany retries - ph_startConnect(connection_index, conn->serial_number); - break; - } - - if (conn->pinging) - { // we are trying to ping them - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_PING, false)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4; - } - break; - } - - uint16_t ping_time = conn->ping_time; - if (fast_ping) ping_time = conn->fast_ping_time; - if (conn->tx_packet_timer >= ping_time) - { // start pinging - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_PING, false)) - { - conn->ping_time = 8000 + (random32 % 100) * 10; - conn->fast_ping_time = 600 + (random32 % 50) * 10; - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4; - conn->pinging = true; - } - break; - } - - // *********** - // exit rx not ready mode if we have space in our rx buffer for more data -/* - if (conn->rx_not_ready_mode) - { - uint16_t size = fifoBuf_getFree(&conn->rx_fifo_buffer); - if (size >= conn->rx_fifo_buffer.buf_size / 6) - { // leave 'rx not ready' mode - if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_READY, false)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len; - break; - } - } - } -*/ - // *********** - // send data packets - -// if (conn->not_ready_timer < 0) - { - uint16_t size = fifoBuf_getUsed(&conn->tx_fifo_buffer); - - if (size == 0) - conn->ready_to_send_timer = -1; // no data to send - else - if (conn->ready_to_send_timer < 0) - conn->ready_to_send_timer = 0; // start timer - - if (size >= 200 || (conn->ready_to_send_timer >= saved_settings.rts_time && size > 0) || (conn->tx_sequence_data_size > 0 && size > 0)) - { // send data - - uint8_t pack_type = PACKET_TYPE_DATA; - if (conn->rx_not_ready_mode) - pack_type = PACKET_TYPE_NOTREADY; - - if (ph_sendPacket(connection_index, conn->send_encrypted, pack_type, false)) - { - conn->tx_packet_timer = 0; - conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len; - } - break; - } - } - - // *********** - - break; - - default: // we should never end up here - maybe we should do a reboot? - conn->link_state = LINK_DISCONNECTED; -/* - // disable all interrupts - PIOS_IRQ_Disable(); - - // turn off all leds - USB_LED_OFF; - LINK_LED_OFF; - RX_LED_OFF; - TX_LED_OFF; - - PIOS_SYS_Reset(); - - while (1); -*/ - break; - } -} - -// ***************************************************************************** - -void ph_setFastPing(bool fast) -{ - fast_ping = fast; -} - -// ***************************************************************************** - -uint8_t ph_getCurrentLinkState(const int connection_index) -{ - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return 0; - - return connection[connection_index].link_state; -} - -// ***************************************************************************** - -uint16_t ph_getRetries(const int connection_index) -{ - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return 0; - - return connection[connection_index].tx_retry_counter; -} - -// ***************************************************************************** - -int16_t ph_getLastRSSI(const int connection_index) -{ - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return 0; - - return connection[connection_index].rx_rssi_dBm; -} - -int32_t ph_getLastAFC(const int connection_index) -{ - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return 0; - - return connection[connection_index].rx_afc_Hz; -} - -// ***************************************************************************** -// set/get the carrier frequency - -void ph_setNominalCarrierFrequency(uint32_t frequency_hz) -{ - rfm22_setNominalCarrierFrequency(frequency_hz); -} - -uint32_t ph_getNominalCarrierFrequency(void) -{ - return rfm22_getNominalCarrierFrequency(); -} - -// ***************************************************************************** -// set/get the RF datarate - -void ph_setDatarate(uint32_t datarate_bps) -{ - rfm22_setDatarate(datarate_bps, TRUE); - - uint32_t ms = 1280000ul / rfm22_getDatarate(); - if (ms < 10) ms = 10; - else - if (ms > 32000) ms = 32000; - - for (int i = 0; i < PH_MAX_CONNECTIONS; i++) - connection[i].tx_retry_time_slot_len = ms; -} - -uint32_t ph_getDatarate(void) -{ - return rfm22_getDatarate(); -} - -// ***************************************************************************** - -void ph_setTxPower(uint8_t tx_power) -{ - rfm22_setTxPower(tx_power); -} - -uint8_t ph_getTxPower(void) -{ - return rfm22_getTxPower(); -} - -// ***************************************************************************** -// set the AES encryption key - -void ph_set_AES128_key(const void *key) -{ - if (!key) - return; - - memmove(aes_key, key, sizeof(aes_key)); - - // create the AES decryption key - aes_decrypt_key_128_create(aes_key, (void *)&dec_aes_key); -} - -// ***************************************************************************** - -int ph_set_remote_serial_number(int connection_index, uint32_t sn) -{ - random32 = updateCRC32(random32, 0xff); - - if (ph_startConnect(connection_index, sn) >= 0) - { - t_connection *conn = &connection[connection_index]; - - // wipe any user data present in the buffers - fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE); - fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE); - - return connection_index; - } - - return -4; -} - -void ph_set_remote_encryption(int connection_index, bool enabled, const void *key) -{ - if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS) - return; - - ph_set_AES128_key(key); - - connection[connection_index].send_encrypted = enabled; -} - -// ***************************************************************************** -// can be called from an interrupt if you wish. -// call this once every ms - -void ph_1ms_tick(void) -{ - if (booting) return; - - if (saved_settings.mode == MODE_NORMAL) - { - // help randomize the encryptor cbc bytes - register uint32_t *cbc = (uint32_t *)&enc_cbc; - for (int i = 0; i < sizeof(enc_cbc) / 4; i++) - { - random32 = updateCRC32(random32, 0xff); - *cbc++ ^= random32; - } - - for (int i = 0; i < PH_MAX_CONNECTIONS; i++) - { - t_connection *conn = &connection[i]; - - if (conn->tx_packet_timer < 0xffff) - conn->tx_packet_timer++; - - if (conn->link_state == LINK_CONNECTED) - { // we are connected - - if (conn->ready_to_send_timer >= 0 && conn->ready_to_send_timer < 0x7fff) - conn->ready_to_send_timer++; - - if (conn->not_ready_timer >= 0 && conn->not_ready_timer < 0x7fffffff) - conn->not_ready_timer++; - - if (conn->data_speed_timer < 0xffff) - { - if (++conn->data_speed_timer >= 1000) - { // 1 second gone by - conn->data_speed_timer = 0; - conn->tx_data_speed = (conn->tx_data_speed + conn->tx_data_speed_count) >> 1; - conn->tx_data_speed_count = 0; - conn->rx_data_speed = (conn->rx_data_speed + conn->rx_data_speed_count) >> 1; - conn->rx_data_speed_count = 0; - } - } - } - else - { // we are not connected - if (conn->data_speed_timer) conn->data_speed_timer = 0; - if (conn->tx_data_speed_count) conn->tx_data_speed_count = 0; - if (conn->tx_data_speed) conn->tx_data_speed = 0; - if (conn->rx_data_speed_count) conn->rx_data_speed_count = 0; - if (conn->rx_data_speed) conn->rx_data_speed = 0; - } - } - } -} - -// ***************************************************************************** -// call this as often as possible - not from an interrupt - -void ph_process(void) -{ - if (booting) return; - - if (saved_settings.mode == MODE_NORMAL) - { - ph_processRxPacket(); - - for (int i = 0; i < PH_MAX_CONNECTIONS; i++) - ph_processLinks(i); - } - else - { - - } -} - -// ***************************************************************************** - -void ph_disconnectAll(void) -{ - for (int i = 0; i < PH_MAX_CONNECTIONS; i++) - { - random32 = updateCRC32(random32, 0xff); - - t_connection *conn = &connection[i]; - - conn->serial_number = 0; - - conn->tx_sequence = 0; - conn->tx_sequence_data_size = 0; - - conn->rx_sequence = 0; - - fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE); - fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE); - - conn->link_state = LINK_DISCONNECTED; - - conn->tx_packet_timer = 0; - - conn->tx_retry_time_slots = 5; - conn->tx_retry_time_slot_len = 40; - conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4; - conn->tx_retry_counter = 0; - - conn->data_speed_timer = 0; - conn->tx_data_speed_count = 0; - conn->tx_data_speed = 0; - conn->rx_data_speed_count = 0; - conn->rx_data_speed = 0; - - conn->ping_time = 8000 + (random32 % 100) * 10; - conn->fast_ping_time = 600 + (random32 % 50) * 10; - conn->pinging = false; - - conn->rx_not_ready_mode = false; - - conn->ready_to_send_timer = -1; - - conn->not_ready_timer = -1; - - conn->send_encrypted = false; - - conn->rx_rssi_dBm = -200; - conn->rx_afc_Hz = 0; - } -} - -// ***************************************************************************** - -void ph_deinit(void) -{ - ph_disconnectAll(); -} - -void ph_init(uint32_t our_sn) -{ - our_serial_number = our_sn; // remember our own serial number - - fast_ping = false; - - ph_disconnectAll(); - - // set the AES encryption key using the default AES key - ph_set_AES128_key(default_aes_key); - - // try too randomise the tx AES CBC bytes - for (uint32_t j = 0, k = 0; j < 123 + (random32 & 1023); j++) - { - random32 = updateCRC32(random32, 0xff); - enc_cbc[k] ^= random32 >> 3; - if (++k >= sizeof(enc_cbc)) k = 0; - } - - // ****** - - rfm22_init_normal(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz, rfm22_freqHopSize()); - - rfm22_TxDataByte_SetCallback(ph_TxDataByteCallback); - rfm22_RxData_SetCallback(ph_RxDataCallback); - - rfm22_setFreqCalibration(saved_settings.rf_xtal_cap); - ph_setNominalCarrierFrequency(saved_settings.frequency_Hz); - ph_setDatarate(saved_settings.max_rf_bandwidth); - ph_setTxPower(saved_settings.max_tx_power); - - ph_set_remote_encryption(0, saved_settings.aes_enable, (const void *)saved_settings.aes_key); - ph_set_remote_serial_number(0, saved_settings.destination_id); - - // ****** -} - -// ***************************************************************************** diff --git a/flight/PipXtreme/pios_board.c b/flight/PipXtreme/pios_board.c deleted file mode 100644 index a5536db2b..000000000 --- a/flight/PipXtreme/pios_board.c +++ /dev/null @@ -1,112 +0,0 @@ -/** - ****************************************************************************** - * - * @file pios_board.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board specific static initializers for hardware for the PipBee board. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Pull in the board-specific static HW definitions. - * Including .c files is a bit ugly but this allows all of - * the HW definitions to be const and static to limit their - * scope. - * - * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE - */ -#include "board_hw_defs.c" - -#include - -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192 - -static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN]; -static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN]; - -#define PIOS_COM_SERIAL_RX_BUF_LEN 192 -#define PIOS_COM_SERIAL_TX_BUF_LEN 192 - -static uint8_t pios_com_serial_rx_buffer[PIOS_COM_SERIAL_RX_BUF_LEN]; -static uint8_t pios_com_serial_tx_buffer[PIOS_COM_SERIAL_TX_BUF_LEN]; - -uint32_t pios_com_serial_id; -uint32_t pios_com_telem_usb_id; - -/** - * PIOS_Board_Init() - * initializes all the core subsystems on this specific hardware - * called from System/openpilot.c - */ -void PIOS_Board_Init(void) { - // Bring up System using CMSIS functions, enables the LEDs. - PIOS_SYS_Init(); - - // turn all the leds on - USB_LED_ON; - LINK_LED_ON; - RX_LED_ON; - TX_LED_ON; - - // Delay system - PIOS_DELAY_Init(); - - uint32_t pios_usart_serial_id; - if (PIOS_USART_Init(&pios_usart_serial_id, &pios_usart_serial_cfg)) { - PIOS_DEBUG_Assert(0); - } - if (PIOS_COM_Init(&pios_com_serial_id, &pios_usart_com_driver, pios_usart_serial_id, - pios_com_serial_rx_buffer, sizeof(pios_com_serial_rx_buffer), - pios_com_serial_tx_buffer, sizeof(pios_com_serial_tx_buffer))) { - PIOS_DEBUG_Assert(0); - } - -#if defined(PIOS_INCLUDE_USB) - /* Initialize board specific USB data */ - PIOS_USB_BOARD_DATA_Init(); - - if (PIOS_USB_DESC_HID_ONLY_Init()) { - PIOS_Assert(0); - } - - uint32_t pios_usb_id; - PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); - -#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM) - uint32_t pios_usb_hid_id; - if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, - pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer), - pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) { - PIOS_Assert(0); - } -#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM */ - -#endif /* PIOS_INCLUDE_USB_HID */ - - // ADC system - // PIOS_ADC_Init(); - - // SPI link to master - if (PIOS_SPI_Init(&pios_spi_port_id, &pios_spi_port_cfg)) { - PIOS_DEBUG_Assert(0); - } -} diff --git a/flight/PipXtreme/ppm.c b/flight/PipXtreme/ppm.c deleted file mode 100644 index e67ea231d..000000000 --- a/flight/PipXtreme/ppm.c +++ /dev/null @@ -1,631 +0,0 @@ -/** - ****************************************************************************** - * - * @file ppm.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sends or Receives the ppm values to/from the remote unit - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include // memmove - -#include "main.h" -#include "rfm22b.h" -#include "saved_settings.h" -#include "ppm.h" - -#if defined(PIOS_COM_DEBUG) - #define PPM_DEBUG -#endif - -// ************************************************************* - -#define PPM_OUT_FRAME_PERIOD_US 20000 // microseconds -#define PPM_OUT_HIGH_PULSE_US 480 // microseconds -#define PPM_OUT_MIN_CHANNEL_PULSE_US 850 // microseconds -#define PPM_OUT_MAX_CHANNEL_PULSE_US 2200 // microseconds - -#define PPM_IN_MIN_SYNC_PULSE_US 7000 // microseconds .. Pip's 6-chan TX goes down to 8.8ms -#define PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds -#define PPM_IN_MAX_CHANNEL_PULSE_US 2400 // microseconds - -// ************************************************************* - -uint8_t ppm_mode; - -volatile bool ppm_initialising = true; - -volatile uint32_t ppm_In_PrevFrames = 0; -volatile uint32_t ppm_In_LastValidFrameTimer = 0; -volatile uint32_t ppm_In_Frames = 0; -volatile uint32_t ppm_In_ErrorFrames = 0; -volatile uint8_t ppm_In_NoisyChannelCounter = 0; -volatile int8_t ppm_In_ChannelsDetected = 0; -volatile int8_t ppm_In_ChannelPulseIndex = -1; -volatile int32_t ppm_In_PreviousValue = -1; -volatile uint32_t ppm_In_PulseWidth = 0; -volatile uint32_t ppm_In_ChannelPulseWidthNew[PIOS_PPM_MAX_CHANNELS]; -volatile uint32_t ppm_In_ChannelPulseWidth[PIOS_PPM_MAX_CHANNELS]; - -volatile uint16_t ppm_Out_ChannelPulseWidth[PIOS_PPM_MAX_CHANNELS]; -volatile uint32_t ppm_Out_SyncPulseWidth = PPM_OUT_FRAME_PERIOD_US; -volatile int8_t ppm_Out_ChannelPulseIndex = -1; -volatile uint8_t ppm_Out_ChannelsUsed = 0; - -// ************************************************************* - -// Initialise the PPM INPUT -void ppm_In_Init(void) -{ - TIM_ICInitTypeDef TIM_ICInitStructure; - - // disable the timer - TIM_Cmd(PIOS_PPM_TIM, DISABLE); - - ppm_In_PrevFrames = 0; - ppm_In_NoisyChannelCounter = 0; - ppm_In_LastValidFrameTimer = 0; - ppm_In_Frames = 0; - ppm_In_ErrorFrames = 0; - ppm_In_ChannelsDetected = 0; - ppm_In_ChannelPulseIndex = -1; - ppm_In_PreviousValue = -1; - ppm_In_PulseWidth = 0; - - for (int i = 0; i < PIOS_PPM_MAX_CHANNELS; i++) - { - ppm_In_ChannelPulseWidthNew[i] = 0; - ppm_In_ChannelPulseWidth[i] = 0; - } - - // Enable timer clock - PIOS_PPM_TIMER_EN_RCC_FUNC; - - // Enable timer interrupts - NVIC_InitTypeDef NVIC_InitStructure; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_InitStructure.NVIC_IRQChannel = PIOS_PPM_TIM_IRQ; - NVIC_Init(&NVIC_InitStructure); - - // Init PPM IN pin - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = PPM_IN_PIN; - GPIO_InitStructure.GPIO_Mode = PPM_IN_MODE; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; - GPIO_Init(PPM_IN_PORT, &GPIO_InitStructure); - - // remap the pin to switch it to timer mode - if (PIOS_PPM_TIM == TIM2) - { -// GPIO_PinRemapConfig(GPIO_PartialRemap1_TIM2, ENABLE); - GPIO_PinRemapConfig(GPIO_PartialRemap2_TIM2, ENABLE); -// GPIO_PinRemapConfig(GPIO_FullRemap_TIM2, ENABLE); - } - - // Configure timer for input capture - TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; - TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; - TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; - TIM_ICInitStructure.TIM_ICFilter = 15; // 0 to 15 - TIM_ICInitStructure.TIM_Channel = PIOS_PPM_IN_TIM_CHANNEL; - TIM_ICInit(PIOS_PPM_TIM_PORT, &TIM_ICInitStructure); - - // Configure timer clocks - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); - TIM_TimeBaseStructure.TIM_Period = 25000 - 1; // 25ms - can be anything you like now really - up to 65536us - TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1; - TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_InternalClockConfig(PIOS_PPM_TIM_PORT); - TIM_TimeBaseInit(PIOS_PPM_TIM_PORT, &TIM_TimeBaseStructure); - - // Enable the Capture Compare and Update Interrupts - TIM_ITConfig(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR | TIM_IT_Update, ENABLE); - - // Clear TIMER Capture compare and update interrupt pending bits - TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR | TIM_IT_Update); - - // Enable timer - TIM_Cmd(PIOS_PPM_TIM, ENABLE); - - // Setup local variable which stays in this scope - // Doing this here and using a local variable saves doing it in the ISR - TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; - TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; - TIM_ICInitStructure.TIM_ICFilter = 0x0; - -#ifdef PPM_DEBUG - DEBUG_PRINTF("ppm_in: initialised\r\n"); -#endif -} - -// TIMER capture/compare/update interrupt -void PIOS_PPM_IN_CC_IRQ(void) -{ - uint16_t new_value = 0; - uint32_t period = (uint32_t)PIOS_PPM_TIM->ARR + 1; - - if (booting || ppm_initialising) - { // clear the interrupts - TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR | TIM_IT_Update); - return; - } - - // determine the interrupt source(s) - bool update_int = TIM_GetITStatus(PIOS_PPM_TIM_PORT, TIM_IT_Update) == SET; // timer/counter overflow occured - bool capture_int = TIM_GetITStatus(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR) == SET; // PPM input capture - - if (capture_int) - new_value = PIOS_PPM_IN_TIM_GETCAP_FUNC(PIOS_PPM_TIM_PORT); - - // clear the interrupts - TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR | TIM_IT_Update); - - // ******** - - uint32_t ticks = 0; - if (update_int) - { // timer/counter overflowed - - if (ppm_In_PreviousValue >= 0) - ticks = (period - ppm_In_PreviousValue) + new_value; - else - { - ticks = period; - if (capture_int) ticks += new_value; - } - ppm_In_PreviousValue = -1; - } - else - if (capture_int) - { - if (ppm_In_PreviousValue >= 0) - ticks = new_value - ppm_In_PreviousValue; - else - ticks += new_value; - } - - ppm_In_PulseWidth += ticks; - if (ppm_In_PulseWidth > 0x7fffffff) - ppm_In_PulseWidth = 0x7fffffff; // prevent overflows - - ppm_In_LastValidFrameTimer += ticks; - if (ppm_In_LastValidFrameTimer > 0x7fffffff) - ppm_In_LastValidFrameTimer = 0x7fffffff; // prevent overflows - - if (capture_int) - ppm_In_PreviousValue = new_value; - - // ******** - -#ifdef PPM_DEBUG -// DEBUG_PRINTF("ppm_in:"); -// if (update_int) DEBUG_PRINTF(" update"); -// if (capture_int) DEBUG_PRINTF(" capture"); -// DEBUG_PRINTF(" %u %u\r\n", ppm_In_LastValidFrameTimer, ppm_In_PulseWidth); -#endif - - if (ppm_In_LastValidFrameTimer >= 200000 && ppm_In_Frames > 0) - { // we haven't seen a valid PPM frame for at least 200ms - for (int i = 0; i < PIOS_PPM_MAX_CHANNELS; i++) - ppm_In_ChannelPulseWidth[i] = 0; - ppm_In_Frames = 0; - ppm_In_ErrorFrames = 0; - } - - if (ppm_In_ChannelPulseIndex < 0 || ppm_In_PulseWidth > PPM_IN_MAX_CHANNEL_PULSE_US) - { // we are looking for a SYNC pulse, or we are receiving one - - if (ppm_In_ChannelPulseIndex >= 0) - { // it's either the start of a sync pulse or a noisy channel .. assume it's the end of a PPM frame - - if (ppm_In_ChannelPulseIndex > 0) - { - if (ppm_In_Frames < 0xffffffff) - ppm_In_Frames++; // update frame counter - - #ifdef PPM_DEBUG -// DEBUG_PRINTF("ppm_in: %u %u\r\n", ppm_In_ChannelsDetected, ppm_In_ChannelPulseIndex); - #endif - - if (ppm_In_ChannelsDetected > 0 && - ppm_In_ChannelsDetected == ppm_In_ChannelPulseIndex && - ppm_In_NoisyChannelCounter <= 2) - { // detected same number of channels as in previous PPM frame .. save the new channel PWM values - #ifdef PPM_DEBUG -// DEBUG_PRINTF("ppm_in: %u channels detected\r\n", ppm_In_ChannelPulseIndex); - #endif - - for (int i = 0; i < PIOS_PPM_MAX_CHANNELS; i++) - ppm_In_ChannelPulseWidth[i] = ppm_In_ChannelPulseWidthNew[i]; - - ppm_In_LastValidFrameTimer = 0; // reset timer - } - else - { - if ((ppm_In_ChannelsDetected > 0 && ppm_In_ChannelsDetected != ppm_In_ChannelPulseIndex) || - ppm_In_NoisyChannelCounter >= 2) - { - if (ppm_In_ErrorFrames < 0xffffffff) - ppm_In_ErrorFrames++; - } - } - ppm_In_ChannelsDetected = ppm_In_ChannelPulseIndex; // the number of channels we found in this frame - } - - ppm_In_ChannelPulseIndex = -1; // back to looking for a SYNC pulse - } - - if (ppm_In_PulseWidth >= PPM_IN_MIN_SYNC_PULSE_US) - { // SYNC pulse found - ppm_In_NoisyChannelCounter = 0; // reset noisy channel detector - ppm_In_ChannelPulseIndex = 0; // start of PPM frame - } - } - else - if (capture_int) - { // CHANNEL pulse - - if (ppm_In_PulseWidth < PPM_IN_MIN_CHANNEL_PULSE_US) - { // bad/noisy channel pulse .. reset state to wait for next SYNC pulse - ppm_In_ChannelPulseIndex = -1; - - if (ppm_In_ErrorFrames < 0xffffffff) - ppm_In_ErrorFrames++; - } - else - { // pulse width is within the accepted tolerance range for a channel - if (ppm_In_ChannelPulseIndex < PIOS_PPM_MAX_CHANNELS) - { - if (ppm_In_ChannelPulseWidthNew[ppm_In_ChannelPulseIndex] > 0) - { - int32_t difference = (int32_t)ppm_In_PulseWidth - ppm_In_ChannelPulseWidthNew[ppm_In_ChannelPulseIndex]; - if (abs(difference) >= 600) - ppm_In_NoisyChannelCounter++; // possibly a noisy channel - or an RC switch was moved - } - - ppm_In_ChannelPulseWidthNew[ppm_In_ChannelPulseIndex] = ppm_In_PulseWidth; // save it - } - - if (ppm_In_ChannelPulseIndex < 127) - ppm_In_ChannelPulseIndex++; // next channel - } - } - - if (capture_int) - ppm_In_PulseWidth = 0; - - // ******** -} - -uint32_t ppm_In_NewFrame(void) -{ - if (booting || ppm_initialising) - return 0; - - if (ppm_In_Frames >= 2 && ppm_In_Frames != ppm_In_PrevFrames) - { // we have a new PPM frame - ppm_In_PrevFrames = ppm_In_Frames; - return ppm_In_PrevFrames; - } - - return 0; -} - -int32_t ppm_In_GetChannelPulseWidth(uint8_t channel) -{ - if (booting || ppm_initialising) - return -1; - - // Return error if channel not available - if (channel >= PIOS_PPM_MAX_CHANNELS || channel >= ppm_In_ChannelsDetected) - return -2; - - return ppm_In_ChannelPulseWidth[channel]; // return channel pulse width -} - -// ************************************************************* - -// Initialise the PPM INPUT -void ppm_Out_Init(void) -{ - // disable the timer - TIM_Cmd(PIOS_PPM_TIM, DISABLE); - - ppm_Out_SyncPulseWidth = PPM_OUT_FRAME_PERIOD_US; - ppm_Out_ChannelPulseIndex = -1; - ppm_Out_ChannelsUsed = 0; - for (int i = 0; i < PIOS_PPM_MAX_CHANNELS; i++) - ppm_Out_ChannelPulseWidth[i] = 1000; -// ppm_Out_ChannelPulseWidth[i] = 1000 + i * 100; // TEST ONLY - -// ppm_Out_ChannelsUsed = 5; // TEST ONLY - - // Enable timer clock - PIOS_PPM_TIMER_EN_RCC_FUNC; - - // Init PPM OUT pin - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = PPM_OUT_PIN; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz; - GPIO_Init(PPM_OUT_PORT, &GPIO_InitStructure); - - // remap the pin to switch it to timer mode -// GPIO_PinRemapConfig(GPIO_PartialRemap1_TIM2, ENABLE); -// GPIO_PinRemapConfig(GPIO_PartialRemap2_TIM2, ENABLE); - GPIO_PinRemapConfig(GPIO_FullRemap_TIM2, ENABLE); - - // Enable timer interrupt - NVIC_InitTypeDef NVIC_InitStructure; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_InitStructure.NVIC_IRQChannel = PIOS_PPM_TIM_IRQ; - NVIC_Init(&NVIC_InitStructure); - - // Time base configuration - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); - TIM_TimeBaseStructure.TIM_Period = ppm_Out_SyncPulseWidth - 1; - TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1; - TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_InternalClockConfig(PIOS_PPM_TIM_PORT); - TIM_TimeBaseInit(PIOS_PPM_TIM_PORT, &TIM_TimeBaseStructure); - - // Set up for output compare function - TIM_OCInitTypeDef TIM_OCInitStructure; - TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; - TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; - TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; - TIM_OCInitStructure.TIM_Pulse = PPM_OUT_HIGH_PULSE_US; - TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; - TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCPolarity_High; - TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Reset; - TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset; - TIM_OC3Init(PIOS_PPM_TIM, &TIM_OCInitStructure); - TIM_OC3PreloadConfig(PIOS_PPM_TIM, TIM_OCPreload_Enable); - - TIM_ARRPreloadConfig(PIOS_PPM_TIM, ENABLE); - - // TIMER Main Output Enable - TIM_CtrlPWMOutputs(PIOS_PPM_TIM, ENABLE); - - // TIM IT enable - TIM_ITConfig(PIOS_PPM_TIM, PIOS_PPM_OUT_TIM_CCR, ENABLE); - - // Clear TIMER Capture compare interrupt pending bit - TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR); - - // Enable timer - TIM_Cmd(PIOS_PPM_TIM, ENABLE); - -#ifdef PPM_DEBUG - DEBUG_PRINTF("ppm_out: initialised\r\n"); -#endif -} - -// TIMER capture/compare interrupt -void PIOS_PPM_OUT_CC_IRQ(void) -{ - // clear the interrupt - TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_OUT_TIM_CCR); - - if (booting || ppm_initialising) - return; - - // ************************* - // update the TIMER period (channel pulse width) - - if (ppm_Out_ChannelPulseIndex < 0) - { // SYNC PULSE - TIM_SetAutoreload(PIOS_PPM_TIM, ppm_Out_SyncPulseWidth - 1); // sync pulse length - ppm_Out_SyncPulseWidth = PPM_OUT_FRAME_PERIOD_US; // reset sync period - - if (ppm_Out_ChannelsUsed > 0) - ppm_Out_ChannelPulseIndex = 0; // onto channel-1 - } - else - { // CHANNEL PULSE - uint16_t pulse_width = ppm_Out_ChannelPulseWidth[ppm_Out_ChannelPulseIndex]; - if (pulse_width < PPM_OUT_MIN_CHANNEL_PULSE_US) pulse_width = PPM_OUT_MIN_CHANNEL_PULSE_US; - else - if (pulse_width > PPM_OUT_MAX_CHANNEL_PULSE_US) pulse_width = PPM_OUT_MAX_CHANNEL_PULSE_US; - - TIM_SetAutoreload(PIOS_PPM_TIM, pulse_width - 1); // channel pulse width - ppm_Out_SyncPulseWidth -= pulse_width; // maintain constant PPM frame period - - // TEST ONLY -// pulse_width += 4; -// if (pulse_width > 2000) pulse_width = 1000; -// ppm_Out_ChannelPulseWidth[ppm_Out_ChannelPulseIndex] = pulse_width; - - ppm_Out_ChannelPulseIndex++; - if (ppm_Out_ChannelPulseIndex >= ppm_Out_ChannelsUsed || ppm_Out_ChannelPulseIndex >= PIOS_PPM_MAX_CHANNELS) - ppm_Out_ChannelPulseIndex = -1; // back to SYNC pulse - } - - // ************************* -} - -// ************************************************************* -// TIMER capture/compare interrupt - -void PIOS_PPM_CC_IRQ_FUNC(void) -{ - if (ppm_mode == MODE_PPM_TX) - PIOS_PPM_IN_CC_IRQ(); - else - if (ppm_mode == MODE_PPM_RX) - PIOS_PPM_OUT_CC_IRQ(); - else - TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR | TIM_IT_Update); // clear the interrupts -} - -// ************************************************************* -// can be called from an interrupt if you wish -// call this once every ms - -void ppm_1ms_tick(void) -{ - if (booting || ppm_initialising) - return; - - -} - -// ************************************************************* -// return a byte for the tx packet transmission. -// -// return value < 0 if no more bytes available, otherwise return byte to be sent - -int16_t ppm_TxDataByteCallback(void) -{ - return -1; -} - -// ************************************************************* -// we are being given a block of received bytes -// -// return TRUE to continue current packet receive, otherwise return FALSE to halt current packet reception - -bool ppm_RxDataCallback(void *data, uint8_t len) -{ - return true; -} - -// ************************************************************* -// call this from the main loop (not interrupt) as often as possible - -void ppm_process(void) -{ - if (booting || ppm_initialising) - return; - - if (ppm_mode == MODE_PPM_TX) - { - if (ppm_In_NewFrame() > 0) - { // we have a new PPM frame to send - - #ifdef PPM_DEBUG - DEBUG_PRINTF("ppm_in: %5u %5u ..", ppm_In_Frames, ppm_In_ErrorFrames); - #endif - - for (int i = 0; i < PIOS_PPM_MAX_CHANNELS && i < ppm_In_ChannelsDetected; i++) - { -// int32_t pwm = ppm_In_GetChannelPulseWidth(i); - - #ifdef PPM_DEBUG - DEBUG_PRINTF(" %4u", ppm_In_GetChannelPulseWidth(i)); - #endif - - // TODO: - } - - #ifdef PPM_DEBUG - DEBUG_PRINTF("\r\n"); - #endif - } - } - else - if (ppm_mode == MODE_PPM_RX) - { - // TODO: - } -} - -// ************************************************************* - -void ppm_deinit(void) -{ - ppm_initialising = true; - - ppm_mode = 0; - - // disable timer - TIM_Cmd(PIOS_PPM_TIM, DISABLE); - - // Disable timer clock - PIOS_PPM_TIMER_DIS_RCC_FUNC; - - // TIM IT disable - TIM_ITConfig(PIOS_PPM_TIM, PIOS_PPM_IN_TIM_CCR | PIOS_PPM_OUT_TIM_CCR, DISABLE); - - // TIMER Main Output Disable - TIM_CtrlPWMOutputs(PIOS_PPM_TIM, DISABLE); - - // un-remap the PPM pins - GPIO_PinRemapConfig(GPIO_FullRemap_TIM2, DISABLE); - - // Disable timer interrupt - NVIC_InitTypeDef NVIC_InitStructure; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = DISABLE; - NVIC_InitStructure.NVIC_IRQChannel = PIOS_PPM_TIM_IRQ; - NVIC_Init(&NVIC_InitStructure); - - ppm_initialising = false; -} - -void ppm_init(uint32_t our_sn) -{ - ppm_deinit(); - - ppm_initialising = true; - - ppm_mode = saved_settings.mode; - - #if defined(PPM_DEBUG) - DEBUG_PRINTF("\r\nPPM init\r\n"); - #endif - - if (ppm_mode == MODE_PPM_TX) - { - ppm_In_Init(); - rfm22_init_tx_stream(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz); - } - else - if (ppm_mode == MODE_PPM_RX) - { - ppm_Out_Init(); - rfm22_init_rx_stream(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz); - } - - rfm22_TxDataByte_SetCallback(ppm_TxDataByteCallback); - rfm22_RxData_SetCallback(ppm_RxDataCallback); - - rfm22_setFreqCalibration(saved_settings.rf_xtal_cap); - rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz); - rfm22_setDatarate(saved_settings.max_rf_bandwidth, FALSE); - rfm22_setTxPower(saved_settings.max_tx_power); - - if (ppm_mode == MODE_PPM_TX) - rfm22_setTxStream(); - - ppm_initialising = false; -} - -// ************************************************************* diff --git a/flight/PipXtreme/reserved/api_comms.c b/flight/PipXtreme/reserved/api_comms.c deleted file mode 100644 index 0f7d27708..000000000 --- a/flight/PipXtreme/reserved/api_comms.c +++ /dev/null @@ -1,500 +0,0 @@ -/** - ****************************************************************************** - * - * @file api_comms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RF Module hardware layer - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - - - -// see http://newwiki.openpilot.org/display/Doc/UAVTalk .. for UAVTalk protocol description -// -// This module scans for OP UAVTalk packets in the comm-port or RF data streams. -// It will discard any corrupt/invalid packets and only pass valid ones. - - - -#include - -#include "stm32f10x.h" -#include "gpio_in.h" -#include "api_comms.h" -#include "packet_handler.h" -#include "main.h" - -#if defined(PIOS_COM_DEBUG) - #define API_DEBUG -#endif - -// ***************************************************************************** -// modem configuration packets - -typedef struct -{ - uint32_t marker; - uint32_t serial_number; - uint8_t type; - uint8_t spare; - uint16_t data_size; - uint32_t header_crc; - uint32_t data_crc; -// uint8_t data[0]; -} __attribute__((__packed__)) t_pipx_config_header; - -typedef struct -{ - uint8_t mode; - uint8_t state; -} __attribute__((__packed__)) t_pipx_config_data_mode_state; - -typedef struct -{ - uint32_t serial_baudrate; // serial uart baudrate - - uint32_t destination_id; - - uint32_t min_frequency_Hz; - uint32_t max_frequency_Hz; - uint32_t frequency_Hz; - - uint32_t max_rf_bandwidth; - - uint8_t max_tx_power; - - uint8_t frequency_band; - - uint8_t rf_xtal_cap; - - bool aes_enable; - uint8_t aes_key[16]; - - uint16_t frequency_step_size; -} __attribute__((__packed__)) t_pipx_config_data_settings; - -typedef struct -{ - uint32_t start_frequency; - uint16_t frequency_step_size; - uint16_t magnitudes; -// int8_t magnitude[0]; -} __attribute__((__packed__)) t_pipx_config_data_spectrum; - -// ***************************************************************************** - -typedef struct -{ - uint8_t sync_byte; - uint8_t message_type; - uint16_t packet_size; // not including CRC byte - uint32_t object_id; -} __attribute__((__packed__)) t_uav_header1; - -typedef struct -{ - uint8_t sync_byte; - uint8_t message_type; - uint16_t packet_size; // not including CRC byte - uint32_t object_id; - uint16_t instance_id; -} __attribute__((__packed__)) t_uav_header2; - -#define SYNC_VAL 0x3C -#define TYPE_MASK 0xFC -#define TYPE_VER 0x20 -#define TYPE_OBJ (TYPE_VER | 0x00) -#define TYPE_OBJ_REQ (TYPE_VER | 0x01) -#define TYPE_OBJ_ACK (TYPE_VER | 0x02) -#define TYPE_ACK (TYPE_VER | 0x03) - -#define MIN_HEADER_LENGTH sizeof(t_uav_header1) -#define MAX_HEADER_LENGTH sizeof(t_uav_header2) -#define MAX_PAYLOAD_LENGTH 256 -#define CHECKSUM_LENGTH 1 - -#define MAX_PACKET_LENGTH (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH) - -// CRC lookup table -static const uint8_t crc_table[256] = { - 0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d, - 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, - 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, - 0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd, - 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, - 0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a, - 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, - 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, - 0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, - 0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, 0xd4, - 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, - 0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, - 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63, - 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, - 0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83, - 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 -}; - -// ***************************************************************************** -// local variables - -uint32_t api_previous_com_port = 0; - -volatile uint16_t api_rx_timer = 0; -volatile uint16_t api_tx_timer = 0; - -uint8_t api_rx_buffer[MAX_PACKET_LENGTH] __attribute__ ((aligned(4))); -uint16_t api_rx_buffer_wr; - -uint8_t api_tx_buffer[MAX_PACKET_LENGTH] __attribute__ ((aligned(4))); -uint16_t api_tx_buffer_wr; - -// ***************************************************************************** -// 8-bit CRC updating - -uint8_t api_updateCRC_byte(uint8_t crc, uint8_t b) -{ - return crc_table[crc ^ b]; -} - -uint8_t api_updateCRC_buffer(uint8_t crc, const void *data, int32_t length) -{ - // use registers for speed - register uint8_t crc8 = crc; - register const uint8_t *p = (uint8_t *)data; - - for (register int32_t i = length; i > 0; i--) - crc8 = crc_table[crc8 ^ *p++]; - - return crc8; -} - -// returned value < 0 if no valid packet detected. -// otherwise returned value is the total size of the valid UAVTalk packet found in the buffer. -// -// any corrupt/invalid UAVTalk packets/data are deleted from the buffer and we scan for the next valid packet. -int16_t api_scanForUAVTalkPacket(void *buf, uint16_t *len) -{ - uint8_t *buffer = (uint8_t *)buf; - - t_uav_header1 *header1 = (t_uav_header1 *)buf; -// t_uav_header2 *header2 = (t_uav_header2 *)buf; - - register uint16_t num_bytes = *len; - - if (num_bytes < MIN_HEADER_LENGTH + CHECKSUM_LENGTH) - return -1; // not yet enough bytes for a complete packet - - while (TRUE) - { - // scan the buffer for the start of a UAVTalk packet - for (uint16_t i = 0; i < num_bytes; i++) - { - if (api_rx_buffer[i] != SYNC_VAL) - continue; // not the start of a packet - move on to the next byte in the buffer - - // possible start of packet found - we found a SYNC byte - - if (i > 0) - { // remove/delete leading bytes before the SYNC byte - num_bytes -= i; - if (num_bytes > 0) - memmove(buffer, buffer + i, num_bytes); - *len = num_bytes; - } - break; - } - - if (num_bytes < MIN_HEADER_LENGTH + CHECKSUM_LENGTH) - return -2; // not yet enough bytes for a complete packet - - if (header1->sync_byte != SYNC_VAL) - { // SYNC byte was not found - start of UAVTalk packet not found in any of the data in the buffer - *len = 0; // empty the entire buffer - return -3; - } - - if (header1->packet_size < MIN_HEADER_LENGTH || header1->packet_size > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) - { // the packet size value is too small or too big - assume either a corrupt UAVTalk packet or we are at the start of a packet -// if (--num_bytes > 0) -// memmove(buffer, buffer + 1, num_bytes); // remove 1st byte -// *len = num_bytes; - buffer[0] ^= 0xaa; // corrupt the sync byte - we'll move the buffer bytes down further up in the code - continue; // continue scanning for a valid packet in the buffer - } - - if (num_bytes < header1->packet_size + CHECKSUM_LENGTH) - { // not yet enough bytes for a complete packet - return -4; - } - - // check the packet CRC - uint8_t crc1 = api_updateCRC_buffer(0, buffer, header1->packet_size); - uint8_t crc2 = buffer[header1->packet_size]; - if (crc1 != crc2) - { // faulty CRC -// if (--num_bytes > 0) -// memmove(buffer, buffer + 1, num_bytes); // remove 1st byte -// *len = num_bytes; - buffer[0] ^= 0xaa; // corrupt the sync byte - we'll move the buffer bytes down further up in the code - - #if defined(API_DEBUG) - DEBUG_PRINTF("UAVTalk packet corrupt %d\r\n", header1->packet_size + 1); - #endif - - continue; // continue scanning for a valid packet in the buffer - } - - #if defined(API_DEBUG) - DEBUG_PRINTF("UAVTalk packet found %d\r\n", header1->packet_size + 1); - #endif - - return (header1->packet_size + CHECKSUM_LENGTH); // return the size of the UAVTalk packet - } - - return -5; -} - -// ***************************************************************************** - -int16_t api_scanForConfigPacket(void *buf, uint16_t *len) -{ - return -1; -} - -// ***************************************************************************** -// can be called from an interrupt if you wish - -void api_1ms_tick(void) -{ // call this once every 1ms - - if (api_rx_timer < 0xffff) api_rx_timer++; - if (api_tx_timer < 0xffff) api_tx_timer++; -} - -// ***************************************************************************** -// call this as often as possible - not from an interrupt - -void api_process(void) -{ // copy data from comm-port RX buffer to RF packet handler TX buffer, and from RF packet handler RX buffer to comm-port TX buffer - - // ******************** - // decide which comm-port we are using (usart or usb) - - bool usb_comms = false; // TRUE if we are using the usb port for comms. - uint32_t comm_port = PIOS_COM_SERIAL; // default to using the usart comm-port - - #if defined(PIOS_INCLUDE_USB_HID) - if (PIOS_USB_HID_CheckAvailable(0)) - { // USB comms is up, use the USB comm-port instead of the USART comm-port - usb_comms = true; - comm_port = PIOS_COM_TELEM_USB; - } - #endif - - // ******************** - // check to see if the local communication port has changed (usart/usb) - - if (api_previous_com_port == 0 && api_previous_com_port != comm_port) - { // the local communications port has changed .. remove any data in the buffers - api_rx_buffer_wr = 0; - api_tx_buffer_wr = 0; - } - else - if (usb_comms) - { // we're using the USB for comms - keep the USART rx buffer empty - int32_t bytes = PIOS_COM_ReceiveBufferUsed(PIOS_COM_SERIAL); - while (bytes > 0) - { - PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL); - bytes--; - } - } - - api_previous_com_port = comm_port; // remember the current comm-port we are using - - // ******************** - - uint16_t connection_index = 0; // the RF connection we are using - - // ******************** - // send the data received from the local comm-port to the RF packet handler TX buffer - - while (TRUE) - { - int16_t packet_size; - - // free space size in the RF packet handler tx buffer - uint16_t ph_num = ph_putData_free(connection_index); - - // get the number of data bytes received down the comm-port - int32_t com_num = PIOS_COM_ReceiveBufferUsed(comm_port); - - // set the USART RTS handshaking line - if (!usb_comms && ph_connected(connection_index)) - { - if (ph_num < 32) - SERIAL_RTS_CLEAR; // lower the USART RTS line - we don't have space in the buffer for anymore bytes - else - SERIAL_RTS_SET; // release the USART RTS line - we have space in the buffer for now bytes - } - else - SERIAL_RTS_SET; // release the USART RTS line - - // limit number of bytes we will get to how much space we have in our RX buffer - if (com_num > sizeof(api_rx_buffer) - api_rx_buffer_wr) - com_num = sizeof(api_rx_buffer) - api_rx_buffer_wr; - - while (com_num > 0) - { // fetch a byte from the comm-port RX buffer and save it into our RX buffer - api_rx_buffer[api_rx_buffer_wr++] = PIOS_COM_ReceiveBuffer(comm_port); - com_num--; - } - -// packet_size = api_scanForConfigPacket(api_rx_buffer, &api_rx_buffer_wr); - - packet_size = api_scanForUAVTalkPacket(api_rx_buffer, &api_rx_buffer_wr); - if (packet_size < 0) - break; // no UAVTalk packet in our RX buffer - - api_rx_timer = 0; - - if (!ph_connected(connection_index)) - { // we don't have a link to a remote modem .. remove the UAVTalk packet from our RX buffer - if (api_rx_buffer_wr > packet_size) - { - api_rx_buffer_wr -= packet_size; - memmove(api_rx_buffer, api_rx_buffer + packet_size, api_rx_buffer_wr); - } - else - api_rx_buffer_wr = 0; - continue; - } - - if (ph_num < packet_size) - break; // not enough room in the RF packet handler TX buffer for the UAVTalk packet - - // copy the rx'ed UAVTalk packet into the RF packet handler TX buffer for sending over the RF link - ph_putData(connection_index, api_rx_buffer, packet_size); - - // remove the UAVTalk packet from our RX buffer - if (api_rx_buffer_wr > packet_size) - { - api_rx_buffer_wr -= packet_size; - memmove(api_rx_buffer, api_rx_buffer + packet_size, api_rx_buffer_wr); - } - else - api_rx_buffer_wr = 0; - } - - // ******************** - // send the data received via the RF link out the comm-port - - while (TRUE) - { - // get number of data bytes received via the RF link - uint16_t ph_num = ph_getData_used(connection_index); - - // limit to how much space we have in the temp TX buffer - if (ph_num > sizeof(api_tx_buffer) - api_tx_buffer_wr) - ph_num = sizeof(api_tx_buffer) - api_tx_buffer_wr; - - if (ph_num > 0) - { // fetch the data bytes received via the RF link and save into our temp buffer - ph_num = ph_getData(connection_index, api_tx_buffer + api_tx_buffer_wr, ph_num); - api_tx_buffer_wr += ph_num; - } - - int16_t packet_size = api_scanForUAVTalkPacket(api_tx_buffer, &api_tx_buffer_wr); - - if (packet_size <= 0) - break; // no UAV Talk packet found - - // we have a UAVTalk packet to send down the comm-port -/* - #if (defined(PIOS_COM_DEBUG) && (PIOS_COM_DEBUG == PIOS_COM_SERIAL)) - if (!usb_comms) - { // the serial-port is being used for debugging - don't send data down it - api_tx_buffer_wr = 0; - api_tx_timer = 0; - continue; - } - #endif -*/ - if (!usb_comms && !GPIO_IN(SERIAL_CTS_PIN)) - break; // we can't yet send data down the comm-port - - // send the data out the comm-port - int32_t res; -// if (usb_comms) -// res = PIOS_COM_SendBuffer(comm_port, api_tx_buffer, packet_size); -// else - res = PIOS_COM_SendBufferNonBlocking(comm_port, api_tx_buffer, packet_size); // this one doesn't work properly with USB :( - if (res < 0) - { // failed to send the data out the comm-port - #if defined(API_DEBUG) - DEBUG_PRINTF("PIOS_COM_SendBuffer %d %d\r\n", packet_size, res); - #endif - - if (api_tx_timer >= 5000) - { // seems we can't send our data for at least the last 5 seconds - delete it - if (api_tx_buffer_wr > packet_size) - { - api_tx_buffer_wr -= packet_size; - memmove(api_tx_buffer, api_tx_buffer + packet_size, api_tx_buffer_wr); - } - else - api_tx_buffer_wr = 0; - } - - break; - } - - // data was sent out the comm-port OK .. remove the sent data from our buffer - - if (api_tx_buffer_wr > packet_size) - { - api_tx_buffer_wr -= packet_size; - memmove(api_tx_buffer, api_tx_buffer + packet_size, api_tx_buffer_wr); - } - else - api_tx_buffer_wr = 0; - - api_tx_timer = 0; - } - - // ******************** -} - -// ***************************************************************************** - -void api_init(void) -{ - api_previous_com_port = 0; - - api_rx_buffer_wr = 0; - - api_tx_buffer_wr = 0; - - api_rx_timer = 0; - api_tx_timer = 0; -} - -// ***************************************************************************** diff --git a/flight/PipXtreme/rfm22b.c b/flight/PipXtreme/rfm22b.c deleted file mode 100644 index 57be9a493..000000000 --- a/flight/PipXtreme/rfm22b.c +++ /dev/null @@ -1,2491 +0,0 @@ -/** - ****************************************************************************** - * - * @file rfm22b.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RF Module hardware layer - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -// ***************************************************************** -// RFM22B hardware layer -// -// This module uses the RFM22B's internal packet handling hardware to encapsulate our own packet data. -// -// The RFM22B internal hardware packet handler configuration is as follows .. -// -// 4-byte (32-bit) preamble .. alternating 0's & 1's -// 4-byte (32-bit) sync -// 1-byte packet length (number of data bytes to follow) -// 0 to 255 user data bytes -// -// Our own packet data will also contain it's own header and 32-bit CRC as a single 16-bit CRC is not sufficient for wireless comms. -// -// ***************************************************************** - -#include // memmove - -#include "stm32f10x.h" -#include "main.h" -#include "stopwatch.h" -#include "gpio_in.h" -#include "rfm22b.h" - -#if defined(PIOS_COM_DEBUG) -// #define RFM22_DEBUG -// #define RFM22_INT_TIMEOUT_DEBUG -#endif - -// ***************************************************************** -// forward delarations - -#if defined(RFM22_EXT_INT_USE) - void rfm22_processInt(void); -#endif - -// ************************************ -// this is too adjust the RF module so that it is on frequency - -#define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default - -#define OSC_LOAD_CAP_1 0x7D // board 1 -#define OSC_LOAD_CAP_2 0x7B // board 2 -#define OSC_LOAD_CAP_3 0x7E // board 3 -#define OSC_LOAD_CAP_4 0x7F // board 4 - -// ************************************ - -#define TX_TEST_MODE_TIMELIMIT_MS 30000 // TX test modes time limit (in ms) - -//#define TX_PREAMBLE_NIBBLES 8 // 7 to 511 (number of nibbles) -//#define RX_PREAMBLE_NIBBLES 5 // 5 to 31 (number of nibbles) -#define TX_PREAMBLE_NIBBLES 12 // 7 to 511 (number of nibbles) -#define RX_PREAMBLE_NIBBLES 6 // 5 to 31 (number of nibbles) - -#define FIFO_SIZE 64 // the size of the rf modules internal FIFO buffers - -#define TX_FIFO_HI_WATERMARK 62 // 0-63 -#define TX_FIFO_LO_WATERMARK 32 // 0-63 - -#define RX_FIFO_HI_WATERMARK 32 // 0-63 - -#define PREAMBLE_BYTE 0x55 // preamble byte (preceeds SYNC_BYTE's) - -#define SYNC_BYTE_1 0x2D // RF sync bytes (32-bit in all) -#define SYNC_BYTE_2 0xD4 // -#define SYNC_BYTE_3 0x4B // -#define SYNC_BYTE_4 0x59 // - -// ************************************ -// the default TX power level - -#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_0 // +1dBm ... 1.25mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_1 // +2dBm ... 1.6mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_2 // +5dBm ... 3.16mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_3 // +8dBm ... 6.3mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_4 // +11dBm .. 12.6mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_5 // +14dBm .. 25mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_6 // +17dBm .. 50mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_7 // +20dBm .. 100mW - -// ************************************ -// the default RF datarate - -//#define RFM22_DEFAULT_RF_DATARATE 500 // 500 bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 1000 // 1k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 2000 // 2k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 4000 // 4k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 8000 // 8k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 9600 // 9.6k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 16000 // 16k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 19200 // 19k2 bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 24000 // 24k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 32000 // 32k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 64000 // 64k bits per sec -#define RFM22_DEFAULT_RF_DATARATE 128000 // 128k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 192000 // 192k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 256000 // 256k bits per sec .. NOT YET WORKING - -// ************************************ - -#define RFM22_DEFAULT_SS_RF_DATARATE 125 // 128bps - -// ************************************ -// Normal data streaming -// GFSK modulation -// no manchester encoding -// data whitening -// FIFO mode -// 5-nibble rx preamble length detection -// 10-nibble tx preamble length -// AFC enabled - -#define LOOKUP_SIZE 14 - -// xtal 10 ppm, 434MHz -const uint32_t data_rate[LOOKUP_SIZE] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 64000, 128000, 192000, 256000}; -const uint8_t modulation_index[LOOKUP_SIZE] = { 16, 8, 4, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}; -const uint32_t freq_deviation[LOOKUP_SIZE] = { 4000, 4000, 4000, 4000, 4000, 4800, 8000, 9600, 12000, 16000, 32000, 64000, 96000, 128000}; -const uint32_t rx_bandwidth[LOOKUP_SIZE] = { 17500, 17500, 17500, 17500, 17500, 19400, 32200, 38600, 51200, 64100, 137900, 269300, 420200, 518800}; -const int8_t est_rx_sens_dBm[LOOKUP_SIZE] = { -118, -118, -117, -116, -115, -115, -112, -112, -110, -109, -106, -103, -101, -100}; // estimated receiver sensitivity for BER = 1E-3 - -const uint8_t reg_1C[LOOKUP_SIZE] = { 0x37, 0x37, 0x37, 0x37, 0x3A, 0x3B, 0x26, 0x28, 0x2E, 0x16, 0x07, 0x83, 0x8A, 0x8C}; // rfm22_if_filter_bandwidth - -const uint8_t reg_1D[LOOKUP_SIZE] = { 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44}; // rfm22_afc_loop_gearshift_override -const uint8_t reg_1E[LOOKUP_SIZE] = { 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x02}; // rfm22_afc_timing_control - -const uint8_t reg_1F[LOOKUP_SIZE] = { 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03}; // rfm22_clk_recovery_gearshift_override -const uint8_t reg_20[LOOKUP_SIZE] = { 0xE8, 0xF4, 0xFA, 0x70, 0x3F, 0x34, 0x3F, 0x34, 0x2A, 0x3F, 0x3F, 0x5E, 0x3F, 0x2F}; // rfm22_clk_recovery_oversampling_ratio -const uint8_t reg_21[LOOKUP_SIZE] = { 0x60, 0x20, 0x00, 0x01, 0x02, 0x02, 0x02, 0x02, 0x03, 0x02, 0x02, 0x01, 0x02, 0x02}; // rfm22_clk_recovery_offset2 -const uint8_t reg_22[LOOKUP_SIZE] = { 0x20, 0x41, 0x83, 0x06, 0x0C, 0x75, 0x0C, 0x75, 0x12, 0x0C, 0x0C, 0x5D, 0x0C, 0xBB}; // rfm22_clk_recovery_offset1 -const uint8_t reg_23[LOOKUP_SIZE] = { 0xC5, 0x89, 0x12, 0x25, 0x4A, 0x25, 0x4A, 0x25, 0x6F, 0x4A, 0x4A, 0x86, 0x4A, 0x0D}; // rfm22_clk_recovery_offset0 -const uint8_t reg_24[LOOKUP_SIZE] = { 0x00, 0x00, 0x00, 0x02, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x05, 0x07, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 -const uint8_t reg_25[LOOKUP_SIZE] = { 0x0A, 0x23, 0x85, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x74, 0xFF, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 - -const uint8_t reg_2A[LOOKUP_SIZE] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 0x17, 0x31, 0x50, 0x50, 0x50}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz - -const uint8_t reg_6E[LOOKUP_SIZE] = { 0x04, 0x08, 0x10, 0x20, 0x41, 0x4E, 0x83, 0x9D, 0xC4, 0x08, 0x10, 0x20, 0x31, 0x41}; // rfm22_tx_data_rate1 -const uint8_t reg_6F[LOOKUP_SIZE] = { 0x19, 0x31, 0x62, 0xC5, 0x89, 0xA5, 0x12, 0x49, 0x9C, 0x31, 0x62, 0xC5, 0x27, 0x89}; // rfm22_tx_data_rate0 - -const uint8_t reg_70[LOOKUP_SIZE] = { 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x0D, 0x0D, 0x0D, 0x0D, 0x0D}; // rfm22_modulation_mode_control1 -const uint8_t reg_71[LOOKUP_SIZE] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23}; // rfm22_modulation_mode_control2 - -const uint8_t reg_72[LOOKUP_SIZE] = { 0x06, 0x06, 0x06, 0x06, 0x06, 0x08, 0x0D, 0x0F, 0x13, 0x1A, 0x33, 0x66, 0x9A, 0xCD}; // rfm22_frequency_deviation - -// ************************************ -// Scan Spectrum settings -// GFSK modulation -// no manchester encoding -// data whitening -// FIFO mode -// 5-nibble rx preamble length detection -// 10-nibble tx preamble length -// AFC disabled - -#define SS_LOOKUP_SIZE 2 - -// xtal 1 ppm, 434MHz -const uint32_t ss_rx_bandwidth[SS_LOOKUP_SIZE] = { 2600, 10600}; - -const uint8_t ss_reg_1C[SS_LOOKUP_SIZE] = { 0x51, 0x32}; // rfm22_if_filter_bandwidth -const uint8_t ss_reg_1D[SS_LOOKUP_SIZE] = { 0x00, 0x00}; // rfm22_afc_loop_gearshift_override - -const uint8_t ss_reg_20[SS_LOOKUP_SIZE] = { 0xE8, 0x38}; // rfm22_clk_recovery_oversampling_ratio -const uint8_t ss_reg_21[SS_LOOKUP_SIZE] = { 0x60, 0x02}; // rfm22_clk_recovery_offset2 -const uint8_t ss_reg_22[SS_LOOKUP_SIZE] = { 0x20, 0x4D}; // rfm22_clk_recovery_offset1 -const uint8_t ss_reg_23[SS_LOOKUP_SIZE] = { 0xC5, 0xD3}; // rfm22_clk_recovery_offset0 -const uint8_t ss_reg_24[SS_LOOKUP_SIZE] = { 0x00, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 -const uint8_t ss_reg_25[SS_LOOKUP_SIZE] = { 0x0F, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 - -const uint8_t ss_reg_2A[SS_LOOKUP_SIZE] = { 0xFF, 0xFF}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz - -const uint8_t ss_reg_70[SS_LOOKUP_SIZE] = { 0x24, 0x2D}; // rfm22_modulation_mode_control1 -const uint8_t ss_reg_71[SS_LOOKUP_SIZE] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2 - -// ************************************ - -volatile bool initialized = false; - -#if defined(RFM22_EXT_INT_USE) - volatile bool exec_using_spi; // set this if you want to access the SPI bus outside of the interrupt - volatile bool inside_ext_int; // this is set whenever we are inside the interrupt -#endif - -uint8_t device_type; // the RF chips device ID number -uint8_t device_version; // the RF chips revision number - -volatile uint8_t rf_mode; // holds our current RF mode - -uint32_t lower_carrier_frequency_limit_Hz; // the minimum RF frequency we can use -uint32_t upper_carrier_frequency_limit_Hz; // the maximum RF frequency we can use -uint32_t carrier_frequency_hz; // the current RF frequency we are on - -uint32_t carrier_datarate_bps; // the RF data rate we are using - -uint32_t rf_bandwidth_used; // the RF bandwidth currently used -uint32_t ss_rf_bandwidth_used; // the RF bandwidth currently used - -uint8_t hbsel; // holds the hbsel (1 or 2) -float frequency_step_size; // holds the minimum frequency step size - -uint8_t frequency_hop_channel; // current frequency hop channel - -uint8_t frequency_hop_step_size_reg; // - -uint8_t adc_config; // holds the adc config reg value - -volatile uint8_t device_status; // device status register -volatile uint8_t int_status1; // interrupt status register 1 -volatile uint8_t int_status2; // interrupt status register 2 -volatile uint8_t ezmac_status; // ezmac status register - -volatile int16_t afc_correction; // afc correction reading -volatile int32_t afc_correction_Hz; // afc correction reading (in Hz) - -volatile int16_t temperature_reg; // the temperature sensor reading - -#if defined(RFM22_DEBUG) - volatile uint8_t prev_device_status; // just for debugging - volatile uint8_t prev_int_status1; // " " - volatile uint8_t prev_int_status2; // " " - volatile uint8_t prev_ezmac_status; // " " - - bool debug_outputted; -#endif - -volatile uint8_t osc_load_cap; // xtal frequency calibration value - -volatile uint8_t rssi; // the current RSSI (register value) -volatile int16_t rssi_dBm; // dBm value - -uint8_t tx_power; // the transmit power to use for data transmissions -volatile uint8_t tx_pwr; // the tx power register read back - -volatile uint8_t rx_buffer_current; // the current receive buffer in use (double buffer) -volatile uint8_t rx_buffer[256] __attribute__ ((aligned(4))); // the receive buffer .. received packet data is saved here -volatile uint16_t rx_buffer_wr; // the receive buffer write index - -volatile uint8_t rx_packet_buf[256] __attribute__ ((aligned(4))); // the received packet -volatile uint16_t rx_packet_wr; // the receive packet write index -volatile int16_t rx_packet_start_rssi_dBm; // -volatile int32_t rx_packet_start_afc_Hz; // -volatile int16_t rx_packet_rssi_dBm; // the received packet signal strength -volatile int32_t rx_packet_afc_Hz; // the receive packet frequency offset - -volatile uint8_t *tx_data_addr; // the address of the data we send in the transmitted packets -volatile uint16_t tx_data_rd; // the tx data read index -volatile uint16_t tx_data_wr; // the tx data write index - -//volatile uint8_t tx_fifo[FIFO_SIZE]; // - -volatile uint8_t rx_fifo[FIFO_SIZE]; // -volatile uint8_t rx_fifo_wr; // - -int lookup_index; -int ss_lookup_index; - -volatile bool power_on_reset; // set if the RF module has reset itself - -volatile uint16_t rfm22_int_timer; // used to detect if the RF module stops responding. thus act accordingly if it does stop responding. -volatile uint16_t rfm22_int_time_outs; // counter -volatile uint16_t prev_rfm22_int_time_outs; // - -uint32_t clear_channel_count = (TX_PREAMBLE_NIBBLES + 4) * 2; // minimum clear channel time before allowing transmit - -uint16_t timeout_ms = 20000; // -uint16_t timeout_sync_ms = 3; // -uint16_t timeout_data_ms = 20; // - -t_rfm22_TxDataByteCallback tx_data_byte_callback_function = NULL; -t_rfm22_RxDataCallback rx_data_callback_function = NULL; - -// ************************************ -// SPI read/write - -void rfm22_startBurstWrite(uint8_t addr) -{ - // wait 1us .. so we don't toggle the CS line to quickly - PIOS_DELAY_WaituS(1); - - // chip select line LOW - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0); - - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr); -} - -inline void rfm22_burstWrite(uint8_t data) -{ - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data); -} - -void rfm22_endBurstWrite(void) -{ - // chip select line HIGH - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1); -} - -void rfm22_write(uint8_t addr, uint8_t data) -{ - // wait 1us .. so we don't toggle the CS line to quickly - PIOS_DELAY_WaituS(1); - - // chip select line LOW - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0); - - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr); - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data); - - // chip select line HIGH - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1); -} - -void rfm22_startBurstRead(uint8_t addr) -{ - // wait 1us .. so we don't toggle the CS line to quickly - PIOS_DELAY_WaituS(1); - - // chip select line LOW - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0); - - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f); -} - -inline uint8_t rfm22_burstRead(void) -{ - return PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff); -} - -void rfm22_endBurstRead(void) -{ - // chip select line HIGH - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1); -} - -uint8_t rfm22_read(uint8_t addr) -{ - uint8_t rdata; - - // wait 1us .. so we don't toggle the CS line to quickly - PIOS_DELAY_WaituS(1); - - // chip select line LOW - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0); - - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f); - rdata = PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff); - - // chip select line HIGH - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1); - - return rdata; -} - -// ************************************ -// external interrupt - -#if defined(RFM22_EXT_INT_USE) - - void RFM22_EXT_INT_FUNC(void) - { - inside_ext_int = TRUE; - - if (EXTI_GetITStatus(RFM22_EXT_INT_LINE) != RESET) - { - // Clear the EXTI line pending bit - EXTI_ClearITPendingBit(RFM22_EXT_INT_LINE); - -// USB_LED_TOGGLE; // TEST ONLY - - if (!booting && !exec_using_spi) - { -// while (!GPIO_IN(RF_INT_PIN) && !exec_using_spi) - { // stay here until the interrupt line returns HIGH - rfm22_processInt(); - } - } - } - - inside_ext_int = FALSE; - } - - void rfm22_disableExtInt(void) - { - // Configure the external interrupt - GPIO_EXTILineConfig(RFM22_EXT_INT_PORT_SOURCE, RFM22_EXT_INT_PIN_SOURCE); - EXTI_InitTypeDef EXTI_InitStructure; - EXTI_InitStructure.EXTI_Line = RFM22_EXT_INT_LINE; - EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; - EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling; - EXTI_InitStructure.EXTI_LineCmd = DISABLE; - EXTI_Init(&EXTI_InitStructure); - - EXTI_ClearFlag(RFM22_EXT_INT_LINE); - } - - void rfm22_enableExtInt(void) - { - // Configure the external interrupt - GPIO_EXTILineConfig(RFM22_EXT_INT_PORT_SOURCE, RFM22_EXT_INT_PIN_SOURCE); - EXTI_InitTypeDef EXTI_InitStructure; - EXTI_InitStructure.EXTI_Line = RFM22_EXT_INT_LINE; - EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; - EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling; - EXTI_InitStructure.EXTI_LineCmd = ENABLE; - EXTI_Init(&EXTI_InitStructure); - - EXTI_ClearFlag(RFM22_EXT_INT_LINE); - - // Enable and set the external interrupt - NVIC_InitTypeDef NVIC_InitStructure; - NVIC_InitStructure.NVIC_IRQChannel = RFM22_EXT_INT_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = RFM22_EXT_INT_PRIORITY; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); - } - -#endif - -// ************************************ -// set/get the current tx power setting - -void rfm22_setTxPower(uint8_t tx_pwr) -{ - switch (tx_pwr) - { - case 0: tx_power = RFM22_tx_pwr_txpow_0; break; // +1dBm ... 1.25mW - case 1: tx_power = RFM22_tx_pwr_txpow_1; break; // +2dBm ... 1.6mW - case 2: tx_power = RFM22_tx_pwr_txpow_2; break; // +5dBm ... 3.16mW - case 3: tx_power = RFM22_tx_pwr_txpow_3; break; // +8dBm ... 6.3mW - case 4: tx_power = RFM22_tx_pwr_txpow_4; break; // +11dBm .. 12.6mW - case 5: tx_power = RFM22_tx_pwr_txpow_5; break; // +14dBm .. 25mW - case 6: tx_power = RFM22_tx_pwr_txpow_6; break; // +17dBm .. 50mW - case 7: tx_power = RFM22_tx_pwr_txpow_7; break; // +20dBm .. 100mW - default: break; - } -} - -uint8_t rfm22_getTxPower(void) -{ - return tx_power; -} - -// ************************************ - -uint32_t rfm22_minFrequency(void) -{ - return lower_carrier_frequency_limit_Hz; -} -uint32_t rfm22_maxFrequency(void) -{ - return upper_carrier_frequency_limit_Hz; -} - -void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz) -{ - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = TRUE; -#endif - - // ******* - - if (frequency_hz < lower_carrier_frequency_limit_Hz) frequency_hz = lower_carrier_frequency_limit_Hz; - else - if (frequency_hz > upper_carrier_frequency_limit_Hz) frequency_hz = upper_carrier_frequency_limit_Hz; - - if (frequency_hz < 480000000) - hbsel = 1; - else - hbsel = 2; - uint8_t fb = (uint8_t)(frequency_hz / (10000000 * hbsel)); - - uint32_t fc = (uint32_t)(frequency_hz - (10000000 * hbsel * fb)); - - fc = (fc * 64u) / (10000ul * hbsel); - fb -= 24; - -// carrier_frequency_hz = frequency_hz; - carrier_frequency_hz = ((uint32_t)fb + 24 + ((float)fc / 64000)) * 10000000 * hbsel; - - if (hbsel > 1) - fb |= RFM22_fbs_hbsel; - - fb |= RFM22_fbs_sbse; // is this the RX LO polarity? - - frequency_step_size = 156.25f * hbsel; - - rfm22_write(RFM22_frequency_hopping_channel_select, frequency_hop_channel); // frequency hopping channel (0-255) - - rfm22_write(RFM22_frequency_offset1, 0); // no frequency offset - rfm22_write(RFM22_frequency_offset2, 0); // no frequency offset - - rfm22_write(RFM22_frequency_band_select, fb); // set the carrier frequency - rfm22_write(RFM22_nominal_carrier_frequency1, fc >> 8); // " " - rfm22_write(RFM22_nominal_carrier_frequency0, fc & 0xff); // " " - - // ******* - -#if defined(RFM22_DEBUG) - DEBUG_PRINTF("rf setFreq: %u\r\n", carrier_frequency_hz); -// DEBUG_PRINTF("rf setFreq frequency_step_size: %0.2f\r\n", frequency_step_size); -#endif - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = FALSE; -#endif -} - -uint32_t rfm22_getNominalCarrierFrequency(void) -{ - return carrier_frequency_hz; -} - -float rfm22_getFrequencyStepSize(void) -{ - return frequency_step_size; -} - -void rfm22_setFreqHopChannel(uint8_t channel) -{ // set the frequency hopping channel - frequency_hop_channel = channel; - rfm22_write(RFM22_frequency_hopping_channel_select, frequency_hop_channel); -} - -uint8_t rfm22_freqHopChannel(void) -{ // return the current frequency hopping channel - return frequency_hop_channel; -} - -uint32_t rfm22_freqHopSize(void) -{ // return the frequency hopping step size - return ((uint32_t)frequency_hop_step_size_reg * 10000); -} - -// ************************************ -// radio datarate about 19200 Baud -// radio frequency deviation 45kHz -// radio receiver bandwidth 67kHz. -// -// Carson's rule: -// The signal bandwidth is about 2(Delta-f + fm) .. -// -// Delta-f = frequency deviation -// fm = maximum frequency of the signal -// -// This gives 2(45 + 9.6) = 109.2kHz. - -void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) -{ - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = TRUE; -#endif - // ******* - - lookup_index = 0; - while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps) - lookup_index++; - - carrier_datarate_bps = datarate_bps = data_rate[lookup_index]; - - rf_bandwidth_used = rx_bandwidth[lookup_index]; - - // ******************************** - -#if defined(RFM22_DEBUG) - uint32_t frequency_deviation = freq_deviation[lookup_index]; // Hz - uint32_t modulation_bandwidth = datarate_bps + (2 * frequency_deviation); -#endif - - - - - - - rfm22_write(0x1C, reg_1C[lookup_index]); // rfm22_if_filter_bandwidth - - rfm22_write(0x1D, reg_1D[lookup_index]); // rfm22_afc_loop_gearshift_override - rfm22_write(0x1E, reg_1E[lookup_index]); // RFM22_afc_timing_control - - rfm22_write(0x1F, reg_1F[lookup_index]); // RFM22_clk_recovery_gearshift_override - rfm22_write(0x20, reg_20[lookup_index]); // rfm22_clk_recovery_oversampling_ratio - rfm22_write(0x21, reg_21[lookup_index]); // rfm22_clk_recovery_offset2 - rfm22_write(0x22, reg_22[lookup_index]); // rfm22_clk_recovery_offset1 - rfm22_write(0x23, reg_23[lookup_index]); // rfm22_clk_recovery_offset0 - rfm22_write(0x24, reg_24[lookup_index]); // rfm22_clk_recovery_timing_loop_gain1 - rfm22_write(0x25, reg_25[lookup_index]); // rfm22_clk_recovery_timing_loop_gain0 - - rfm22_write(0x2A, reg_2A[lookup_index]); // rfm22_afc_limiter - - if (carrier_datarate_bps < 100000) - rfm22_write(0x58, 0x80); // rfm22_chargepump_current_trimming_override - else - rfm22_write(0x58, 0xC0); // rfm22_chargepump_current_trimming_override - - rfm22_write(0x6E, reg_6E[lookup_index]); // rfm22_tx_data_rate1 - rfm22_write(0x6F, reg_6F[lookup_index]); // rfm22_tx_data_rate0 - - // Enable data whitening -// uint8_t txdtrtscale_bit = rfm22_read(RFM22_modulation_mode_control1) & RFM22_mmc1_txdtrtscale; -// rfm22_write(RFM22_modulation_mode_control1, txdtrtscale_bit | RFM22_mmc1_enwhite); - - if (!data_whitening) - rfm22_write(0x70, reg_70[lookup_index] & ~RFM22_mmc1_enwhite); // rfm22_modulation_mode_control1 - else - rfm22_write(0x70, reg_70[lookup_index] | RFM22_mmc1_enwhite); // rfm22_modulation_mode_control1 - - rfm22_write(0x71, reg_71[lookup_index]); // rfm22_modulation_mode_control2 - - rfm22_write(0x72, reg_72[lookup_index]); // rfm22_frequency_deviation - - rfm22_write(RFM22_ook_counter_value1, 0x00); - rfm22_write(RFM22_ook_counter_value2, 0x00); - - // ******************************** - // calculate the TX register values -/* - uint16_t fd = frequency_deviation / 625; - - uint8_t mmc1 = RFM22_mmc1_enphpwdn | RFM22_mmc1_manppol; - uint16_t txdr; - if (datarate_bps < 30000) - { - txdr = (datarate_bps * 20972) / 10000; - mmc1 |= RFM22_mmc1_txdtrtscale; - } - else - txdr = (datarate_bps * 6553) / 100000; - - uint8_t mmc2 = RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk; // FIFO mode, GFSK -// uint8_t mmc2 = RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_gfsk; // PN9 mode, GFSK .. TX TEST MODE - if (fd & 0x100) mmc2 |= RFM22_mmc2_fd; - - rfm22_write(RFM22_frequency_deviation, fd); // set the TX peak frequency deviation - - rfm22_write(RFM22_modulation_mode_control1, mmc1); - rfm22_write(RFM22_modulation_mode_control2, mmc2); - - rfm22_write(RFM22_tx_data_rate1, txdr >> 8); // set the TX data rate - rfm22_write(RFM22_tx_data_rate0, txdr); // " " -*/ - // ******************************** - // determine a clear channel time - - // initialise the stopwatch with a suitable resolution for the datarate - STOPWATCH_init(4000000ul / carrier_datarate_bps); // set resolution to the time for 1 nibble (4-bits) at rf datarate - - // ******************************** - // determine suitable time-out periods - - timeout_sync_ms = (8000ul * 16) / carrier_datarate_bps; // milliseconds - if (timeout_sync_ms < 3) - timeout_sync_ms = 3; // because out timer resolution is only 1ms - - timeout_data_ms = (8000ul * 100) / carrier_datarate_bps; // milliseconds - if (timeout_data_ms < 3) - timeout_data_ms = 3; // because out timer resolution is only 1ms - - // ******************************** - -#if defined(RFM22_DEBUG) - DEBUG_PRINTF("rf datarate_bps: %d\r\n", datarate_bps); - DEBUG_PRINTF("rf frequency_deviation: %d\r\n", frequency_deviation); - DEBUG_PRINTF("rf modulation_bandwidth: %u\r\n", modulation_bandwidth); - DEBUG_PRINTF("rf_rx_bandwidth[%u]: %u\r\n", lookup_index, rx_bandwidth[lookup_index]); - DEBUG_PRINTF("rf est rx sensitivity[%u]: %ddBm\r\n", lookup_index, est_rx_sens_dBm[lookup_index]); -#endif - - // ******* - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = FALSE; -#endif -} - -uint32_t rfm22_getDatarate(void) -{ - return carrier_datarate_bps; -} - -// ************************************ - -void rfm22_setSSBandwidth(uint32_t bandwidth_index) -{ - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = TRUE; -#endif - // ******* - - ss_lookup_index = bandwidth_index; - - ss_rf_bandwidth_used = ss_rx_bandwidth[lookup_index]; - - // ******************************** - - rfm22_write(0x1C, ss_reg_1C[ss_lookup_index]); // rfm22_if_filter_bandwidth - rfm22_write(0x1D, ss_reg_1D[ss_lookup_index]); // rfm22_afc_loop_gearshift_override - - rfm22_write(0x20, ss_reg_20[ss_lookup_index]); // rfm22_clk_recovery_oversampling_ratio - rfm22_write(0x21, ss_reg_21[ss_lookup_index]); // rfm22_clk_recovery_offset2 - rfm22_write(0x22, ss_reg_22[ss_lookup_index]); // rfm22_clk_recovery_offset1 - rfm22_write(0x23, ss_reg_23[ss_lookup_index]); // rfm22_clk_recovery_offset0 - rfm22_write(0x24, ss_reg_24[ss_lookup_index]); // rfm22_clk_recovery_timing_loop_gain1 - rfm22_write(0x25, ss_reg_25[ss_lookup_index]); // rfm22_clk_recovery_timing_loop_gain0 - - rfm22_write(0x2A, ss_reg_2A[ss_lookup_index]); // rfm22_afc_limiter - - rfm22_write(0x58, 0x80); // rfm22_chargepump_current_trimming_override - - rfm22_write(0x70, ss_reg_70[ss_lookup_index]); // rfm22_modulation_mode_control1 - rfm22_write(0x71, ss_reg_71[ss_lookup_index]); // rfm22_modulation_mode_control2 - - rfm22_write(RFM22_ook_counter_value1, 0x00); - rfm22_write(RFM22_ook_counter_value2, 0x00); - - // ******************************** - -#if defined(RFM22_DEBUG) - DEBUG_PRINTF("ss_rf_rx_bandwidth[%u]: %u\r\n", ss_lookup_index, ss_rx_bandwidth[ss_lookup_index]); -#endif - - // ******* - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = FALSE; -#endif -} - -// ************************************ - -void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode) -{ -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = TRUE; -#endif - - // disable interrupts - rfm22_write(RFM22_interrupt_enable1, 0x00); - rfm22_write(RFM22_interrupt_enable2, 0x00); - - // disable the receiver and transmitter -// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode - - RX_LED_OFF; - TX_LED_OFF; - -// rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); // RX FIFO Almost Full Threshold (0 - 63) - - if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE) - { // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk); - } - - rx_buffer_wr = 0; // empty the rx buffer - - rfm22_int_timer = 0; // reset the timer - - rf_mode = mode; - - if (mode != RX_SCAN_SPECTRUM) - { - STOPWATCH_reset(); // reset clear channel detect timer - - // enable RX interrupts - rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_encrcerror | RFM22_ie1_enpkvalid | RFM22_ie1_enrxffafull | RFM22_ie1_enfferr); - rfm22_write(RFM22_interrupt_enable2, RFM22_ie2_enpreainval | RFM22_ie2_enpreaval | RFM22_ie2_enswdet); - } - - // read interrupt status - clear interrupts - rfm22_read(RFM22_interrupt_status1); - rfm22_read(RFM22_interrupt_status2); - - // clear FIFOs - if (!multi_packet_mode) - { - rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); - rfm22_write(RFM22_op_and_func_ctrl2, 0x00); - } - else - { - rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_rxmpk | RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); - rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_rxmpk); - } - - // enable the receiver -// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_rxon); - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_rxon); - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = FALSE; -#endif - -#if defined(RFM22_DEBUG) - DEBUG_PRINTF(" RX Mode\r\n"); -#endif -} - -// ************************************ - -uint16_t rfm22_addHeader(uint8_t mode) -{ - uint16_t i = 0; - - if (mode == TX_STREAM_MODE) - { // add header - for (uint16_t j = (TX_PREAMBLE_NIBBLES + 1) / 2; j > 0; j--) - { - rfm22_burstWrite(PREAMBLE_BYTE); - i++; - } - rfm22_burstWrite(SYNC_BYTE_1); i++; - rfm22_burstWrite(SYNC_BYTE_2); i++; - } - - return i; -} - -// ************************************ - -void rfm22_setTxMode(uint8_t mode) -{ - if (mode != TX_DATA_MODE && mode != TX_STREAM_MODE && mode != TX_CARRIER_MODE && mode != TX_PN_MODE) - return; // invalid mode - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = TRUE; -#endif - - // ******************* - - // disable interrupts - rfm22_write(RFM22_interrupt_enable1, 0x00); - rfm22_write(RFM22_interrupt_enable2, 0x00); - -// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode - - RX_LED_OFF; - - // set the tx power -// rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | tx_power); -// rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); - rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); - - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - if (mode == TX_CARRIER_MODE) - { // blank carrier mode - for testing - rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_none); // FIFO mode, Blank carrier - } - else - if (mode == TX_PN_MODE) - { // psuedo random data carrier mode - for testing - rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_gfsk); // FIFO mode, PN9 carrier - } - else - { // data transmission - rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk); // FIFO mode, GFSK modulation - } - -// rfm22_write(0x72, reg_72[lookup_index]); // rfm22_frequency_deviation - - // clear FIFOs - rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); - rfm22_write(RFM22_op_and_func_ctrl2, 0x00); - - // ******************* - // add some data to the chips TX FIFO before enabling the transmitter - - { - uint16_t rd = 0; - uint16_t wr = tx_data_wr; - if (!tx_data_addr) wr = 0; - - if (mode == TX_DATA_MODE) - rfm22_write(RFM22_transmit_packet_length, wr); // set the total number of data bytes we are going to transmit - - uint16_t max_bytes = FIFO_SIZE - 1; - - uint16_t i = 0; - - rfm22_startBurstWrite(RFM22_fifo_access); - - if (mode == TX_STREAM_MODE) - { - if (rd >= wr) - { // no data to send - yet .. just send preamble pattern - while (true) - { - rfm22_burstWrite(PREAMBLE_BYTE); - if (++i >= max_bytes) break; - } - } - else - { // add the RF heaader - i += rfm22_addHeader(mode); - } - } - - // add some data - for (uint16_t j = wr - rd; j > 0; j--) - { -// int16_t b = -1; -// if (tx_data_byte_callback_function) -// b = tx_data_byte_callback_function(); - - rfm22_burstWrite(tx_data_addr[rd++]); - if (++i >= max_bytes) break; - } - - rfm22_endBurstWrite(); - - tx_data_rd = rd; - } - - // ******************* - - rfm22_int_timer = 0; // reset the timer - - rf_mode = mode; - - // enable TX interrupts -// rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem | RFM22_ie1_enfferr); - rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); - - // read interrupt status - clear interrupts - rfm22_read(RFM22_interrupt_status1); - rfm22_read(RFM22_interrupt_status2); - - // enable the transmitter -// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_txon); - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); - - TX_LED_ON; - - // ******************* - // create new slightly random clear channel detector count value - - uint32_t ccc = (TX_PREAMBLE_NIBBLES + 8) + 4; // minimum clear channel time before allowing transmit - clear_channel_count = ccc + (random32 % (ccc * 2)); // plus a some randomness - - // ******************* - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = FALSE; -#endif - -#if defined(RFM22_DEBUG) - if (rf_mode == TX_DATA_MODE) DEBUG_PRINTF(" TX_Data_Mode\r\n"); - else - if (rf_mode == TX_STREAM_MODE) DEBUG_PRINTF(" TX_Stream_Mode\r\n"); - else - if (rf_mode == TX_CARRIER_MODE) DEBUG_PRINTF(" TX_Carrier_Mode\r\n"); - else - if (rf_mode == TX_PN_MODE) DEBUG_PRINTF(" TX_PN_Mode\r\n"); -#endif -} - -// ************************************ -// external interrupt line triggered (or polled) from the rf chip - -void rfm22_processRxInt(void) -{ - register uint8_t int_stat1 = int_status1; - register uint8_t int_stat2 = int_status2; - - if (int_stat2 & RFM22_is2_ipreaval) - { // Valid preamble detected - - if (rf_mode == RX_WAIT_PREAMBLE_MODE) - { - rfm22_int_timer = 0; // reset the timer - rf_mode = RX_WAIT_SYNC_MODE; - RX_LED_ON; - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" pream_det"); - debug_outputted = true; - #endif - } - } -/* else - if (int_stat2 & RFM22_is2_ipreainval) - { // Invalid preamble detected - - if (rf_mode == RX_WAIT_SYNC_MODE) - { - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" invalid_preamble"); - debug_outputted = true; - #endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - return; - } - else - { - } - } -*/ - if (int_stat2 & RFM22_is2_iswdet) - { // Sync word detected - - STOPWATCH_reset(); // reset timer - - if (rf_mode == RX_WAIT_PREAMBLE_MODE || rf_mode == RX_WAIT_SYNC_MODE) - { - rfm22_int_timer = 0; // reset the timer - rf_mode = RX_DATA_MODE; - RX_LED_ON; - - // read the 10-bit signed afc correction value - afc_correction = (uint16_t)rfm22_read(RFM22_afc_correction_read) << 8; // bits 9 to 2 - afc_correction |= (uint16_t)rfm22_read(RFM22_ook_counter_value1) & 0x00c0; // bits 1 & 0 - afc_correction >>= 6; - afc_correction_Hz = (int32_t)(frequency_step_size * afc_correction + 0.5f); // convert the afc value to Hz - - rx_packet_start_rssi_dBm = rssi_dBm; // remember the rssi for this packet - rx_packet_start_afc_Hz = afc_correction_Hz; // remember the afc value for this packet - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" sync_det"); - DEBUG_PRINTF(" AFC_%d_%dHz", afc_correction, afc_correction_Hz); - debug_outputted = true; - #endif - } - } - - if (int_stat1 & RFM22_is1_irxffafull) - { // RX FIFO almost full, it needs emptying - - if (rf_mode == RX_DATA_MODE) - { // read data from the rf chips FIFO buffer - rfm22_int_timer = 0; // reset the timer - - register uint16_t len = rfm22_read(RFM22_received_packet_length); // read the total length of the packet data - - register uint16_t wr = rx_buffer_wr; - - if ((wr + RX_FIFO_HI_WATERMARK) > len) - { // some kind of error in the RF module - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" r_size_error1"); - debug_outputted = true; - #endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - return; - } - - if (((wr + RX_FIFO_HI_WATERMARK) >= len) && !(int_stat1 & RFM22_is1_ipkvalid)) - { // some kind of error in the RF module - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" r_size_error2"); - debug_outputted = true; - #endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - return; - } - - // fetch the rx'ed data from the rf chips RX FIFO - rfm22_startBurstRead(RFM22_fifo_access); - rx_fifo_wr = 0; - for (register uint8_t i = RX_FIFO_HI_WATERMARK; i > 0; i--) - rx_fifo[rx_fifo_wr++] = rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer - rfm22_endBurstRead(); - - uint16_t i = rx_fifo_wr; - if (wr + i > sizeof(rx_buffer)) i = sizeof(rx_buffer) - wr; - memcpy((void *)(rx_buffer + wr), (void *)rx_fifo, i); // save the new bytes into our rx buffer - wr += i; - - rx_buffer_wr = wr; - - if (rx_data_callback_function) - { // pass the new data onto whoever wanted it - if (!rx_data_callback_function((void *)rx_fifo, rx_fifo_wr)) - { - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - return; - } - } - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) -// DEBUG_PRINTF(" r_data_%u/%u", rx_buffer_wr, len); -// debug_outputted = true; - #endif - } - else - { // just clear the RX FIFO - rfm22_startBurstRead(RFM22_fifo_access); - for (register uint16_t i = RX_FIFO_HI_WATERMARK; i > 0; i--) - rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer - rfm22_endBurstRead(); - } - } - - if (int_stat1 & RFM22_is1_icrerror) - { // CRC error .. discard the received data - - if (rf_mode == RX_DATA_MODE) - { - rfm22_int_timer = 0; // reset the timer - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" CRC_ERR"); - debug_outputted = true; - #endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver - return; - } - } - -// if (int_stat2 & RFM22_is2_irssi) -// { // RSSI level is >= the set threshold -// } - -// if (device_status & RFM22_ds_rxffem) -// { // RX FIFO empty -// } - -// if (device_status & RFM22_ds_headerr) -// { // Header check error -// } - - if (int_stat1 & RFM22_is1_ipkvalid) - { // Valid packet received - - if (rf_mode == RX_DATA_MODE) - { - rfm22_int_timer = 0; // reset the timer - - // disable the receiver -// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode - - register uint16_t len = rfm22_read(RFM22_received_packet_length); // read the total length of the packet data - - register uint16_t wr = rx_buffer_wr; - - if (wr < len) - { // their must still be data in the RX FIFO we need to get - - // fetch the rx'ed data from the rf chips RX FIFO - rfm22_startBurstRead(RFM22_fifo_access); - rx_fifo_wr = 0; - for (register uint8_t i = len - wr; i > 0; i--) - rx_fifo[rx_fifo_wr++] = rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer - rfm22_endBurstRead(); - - uint16_t i = rx_fifo_wr; - if (wr + i > sizeof(rx_buffer)) i = sizeof(rx_buffer) - wr; - memcpy((void *)(rx_buffer + wr), (void *)rx_fifo, i); // save the new bytes into our rx buffer - wr += i; - - rx_buffer_wr = wr; - - if (rx_data_callback_function) - { // pass the new data onto whoever wanted it - if (!rx_data_callback_function((void *)rx_fifo, rx_fifo_wr)) - { -// rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); -// return; - } - } - } - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver - - if (wr != len) - { // we have a packet length error .. discard the packet - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" r_pack_len_error_%u_%u", len, wr); - debug_outputted = true; - #endif - - return; - } - - // we have a valid received packet - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" VALID_R_PACKET_%u", wr); - debug_outputted = true; - #endif - - if (rx_packet_wr == 0) - { // save the received packet for further processing - rx_packet_rssi_dBm = rx_packet_start_rssi_dBm; // remember the rssi for this packet - rx_packet_afc_Hz = rx_packet_start_afc_Hz; // remember the afc offset for this packet - memmove((void *)rx_packet_buf, (void *)rx_buffer, wr); // copy the packet data - rx_packet_wr = wr; // save the length of the data - } - else - { // the save buffer is still in use .. nothing we can do but to drop the packet - } - -// return; - } - else - { -// rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver -// return; - } - } -} - -uint8_t rfm22_topUpRFTxFIFO(void) -{ - rfm22_int_timer = 0; // reset the timer - - uint16_t rd = tx_data_rd; - uint16_t wr = tx_data_wr; - - if (rf_mode == TX_DATA_MODE && (!tx_data_addr || rd >= wr)) - return 0; // no more data to send - - uint16_t max_bytes = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1; - - uint16_t i = 0; - - // top-up the rf chips TX FIFO buffer - rfm22_startBurstWrite(RFM22_fifo_access); - - // add some data - for (uint16_t j = wr - rd; j > 0; j--) - { -// int16_t b = -1; -// if (tx_data_byte_callback_function) -// b = tx_data_byte_callback_function(); - - rfm22_burstWrite(tx_data_addr[rd++]); - if (++i >= max_bytes) break; - } - tx_data_rd = rd; - - if (rf_mode == TX_STREAM_MODE && rd >= wr) - { // all data sent .. need to start sending RF header again - - tx_data_addr = NULL; - tx_data_rd = tx_data_wr = 0; - - while (i < max_bytes) - { - rfm22_burstWrite(PREAMBLE_BYTE); // preamble byte - i++; - } - - // todo: - - // add the RF heaader - // i += rfm22_addHeader(rf_mode); - } - - rfm22_endBurstWrite(); - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) -// DEBUG_PRINTF(" added_%d_bytes", i); -// debug_outputted = true; - #endif - - return i; -} - -void rfm22_processTxInt(void) -{ - register uint8_t int_stat1 = int_status1; -// register uint8_t int_stat2 = int_status2; - - /* - if (int_stat1 & RFM22_is1_ifferr) - { // FIFO underflow/overflow error - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - tx_data_addr = NULL; - tx_data_rd = tx_data_wr = 0; - return; - } - */ - - if (int_stat1 & RFM22_is1_ixtffaem) - { // TX FIFO almost empty, it needs filling up - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) -// DEBUG_PRINTF(" T_FIFO_AE"); -// debug_outputted = true; - #endif - -// uint8_t bytes_added = rfm22_topUpRFTxFIFO(); - rfm22_topUpRFTxFIFO(); - } - - if (int_stat1 & RFM22_is1_ipksent) - { // Packet has been sent - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" T_Sent"); - debug_outputted = true; - #endif - - if (rf_mode == TX_DATA_MODE) - { - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to receive mode - - tx_data_addr = NULL; - tx_data_rd = tx_data_wr = 0; - return; - } - else - if (rf_mode == TX_STREAM_MODE) - { - tx_data_addr = NULL; - tx_data_rd = tx_data_wr = 0; - - rfm22_setTxMode(TX_STREAM_MODE); - return; - } - } - -// if (int_stat1 & RFM22_is1_itxffafull) -// { // TX FIFO almost full, it needs to be transmitted -// } -} - -void rfm22_processInt(void) -{ // this is called from the external interrupt handler - - #if !defined(RFM22_EXT_INT_USE) - if (GPIO_IN(RF_INT_PIN)) - return; // the external int line is high (no signalled interrupt) - #endif - - if (!initialized || power_on_reset) - return; // we haven't yet been initialized - - #if defined(RFM22_DEBUG) - debug_outputted = false; - #endif - - // ******************************** - // read the RF modules current status registers - - // read device status register - device_status = rfm22_read(RFM22_device_status); - - // read ezmac status register - ezmac_status = rfm22_read(RFM22_ezmac_status); - - // read interrupt status registers - clears the interrupt line - int_status1 = rfm22_read(RFM22_interrupt_status1); - int_status2 = rfm22_read(RFM22_interrupt_status2); - - if (rf_mode != TX_DATA_MODE && rf_mode != TX_STREAM_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE) - { - rssi = rfm22_read(RFM22_rssi); // read rx signal strength .. 45 = -100dBm, 205 = -20dBm - rssi_dBm = ((int16_t)rssi / 2) - 122; // convert to dBm - - // calibrate the RSSI value (rf bandwidth appears to affect it) -// if (rf_bandwidth_used > 0) -// rssi_dBm -= 10000 / rf_bandwidth_used; - } - else - { - tx_pwr = rfm22_read(RFM22_tx_power); // read the tx power register - } - - if (int_status2 & RFM22_is2_ipor) - { // the RF module has gone and done a reset - we need to re-initialize the rf module - initialized = FALSE; - power_on_reset = TRUE; - return; - } - - // ******************************** - // debug stuff - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - if (prev_device_status != device_status || prev_int_status1 != int_status1 || prev_int_status2 != int_status2 || prev_ezmac_status != ezmac_status) - { - DEBUG_PRINTF("%02x %02x %02x %02x %dC", device_status, int_status1, int_status2, ezmac_status, temperature_reg); - - if ((device_status & RFM22_ds_cps_mask) == RFM22_ds_cps_rx) - DEBUG_PRINTF(" %ddBm", rssi_dBm); // rx mode - else - if ((device_status & RFM22_ds_cps_mask) == RFM22_ds_cps_tx) - DEBUG_PRINTF(" %s", (tx_pwr & RFM22_tx_pwr_papeakval) ? "ANT_MISMATCH" : "ant_ok"); // tx mode - - debug_outputted = true; - - prev_device_status = device_status; - prev_int_status1 = int_status1; - prev_int_status2 = int_status2; - prev_ezmac_status = ezmac_status; - } - #endif - - // ******************************** - // read the ADC - temperature sensor .. this can only be used in IDLE mode -/* - if (!(rfm22_read(RFM22_adc_config) & RFM22_ac_adcstartbusy)) - { // the ADC has completed it's conversion - - // read the ADC sample - temperature_reg = (int16_t)rfm22_read(RFM22_adc_value) * 0.5f - 64; - - // start a new ADC conversion - rfm22_write(RFM22_adc_config, adc_config | RFM22_ac_adcstartbusy); - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(", %dC", temperature_reg); - debug_outputted = true; - #endif - } -*/ - // ******************************** - - register uint16_t timer_ms = rfm22_int_timer; - - switch (rf_mode) - { - case RX_SCAN_SPECTRUM: - break; - - case RX_WAIT_PREAMBLE_MODE: - case RX_WAIT_SYNC_MODE: - case RX_DATA_MODE: - - if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) - { // FIFO under/over flow error - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" R_UNDER/OVERRUN"); - debug_outputted = true; - #endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - - if (rf_mode == RX_WAIT_SYNC_MODE && timer_ms >= timeout_sync_ms) - { - rfm22_int_time_outs++; - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" R_SYNC_TIMEOUT"); - debug_outputted = true; - #endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - - if (rf_mode == RX_DATA_MODE && timer_ms >= timeout_data_ms) - { // missing interrupts - rfm22_int_time_outs++; - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - - if ((device_status & RFM22_ds_cps_mask) != RFM22_ds_cps_rx) - { // the rf module is not in rx mode - if (timer_ms >= 100) - { - rfm22_int_time_outs++; - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" R_TIMEOUT"); - debug_outputted = true; - #endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - } - - rfm22_processRxInt(); // process the interrupt - break; - - case TX_DATA_MODE: - - if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) - { // FIFO under/over flow error - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" T_UNDER/OVERRUN"); - debug_outputted = true; - #endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - - if (timer_ms >= timeout_data_ms) - { - rfm22_int_time_outs++; - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - - if ((device_status & RFM22_ds_cps_mask) != RFM22_ds_cps_tx) - { // the rf module is not in tx mode - if (timer_ms >= 100) - { - rfm22_int_time_outs++; - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - DEBUG_PRINTF(" T_TIMEOUT"); - debug_outputted = true; - #endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - } - - rfm22_processTxInt(); // process the interrupt - break; - - case TX_STREAM_MODE: - - // todo: - rfm22_processTxInt(); // process the interrupt - - break; - - case TX_CARRIER_MODE: - case TX_PN_MODE: - -// if (timer_ms >= TX_TEST_MODE_TIMELIMIT_MS) // 'nn'ms limit -// { -// rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode -// tx_data_rd = tx_data_wr = 0; // wipe TX buffer -// break; -// } - - break; - - default: // unknown mode - this should NEVER happen, maybe we should do a complete CPU reset here - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // to rx mode - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - - // ******************************** - - #if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE) - if (debug_outputted) - { - switch (rf_mode) - { - case RX_SCAN_SPECTRUM: - DEBUG_PRINTF(" R_SCAN_SPECTRUM\r\n"); - break; - case RX_WAIT_PREAMBLE_MODE: - DEBUG_PRINTF(" R_WAIT_PREAMBLE\r\n"); - break; - case RX_WAIT_SYNC_MODE: - DEBUG_PRINTF(" R_WAIT_SYNC\r\n"); - break; - case RX_DATA_MODE: - DEBUG_PRINTF(" R_DATA\r\n"); - break; - case TX_DATA_MODE: - DEBUG_PRINTF(" T_DATA\r\n"); - break; - case TX_STREAM_MODE: - DEBUG_PRINTF(" T_STREAM\r\n"); - break; - case TX_CARRIER_MODE: - DEBUG_PRINTF(" T_CARRIER\r\n"); - break; - case TX_PN_MODE: - DEBUG_PRINTF(" T_PN\r\n"); - break; - default: - DEBUG_PRINTF(" UNKNOWN_MODE\r\n"); - break; - } - } - #endif - - // ******************************** -} - -// ************************************ - -int16_t rfm22_getRSSI(void) -{ - #if defined(RFM22_EXT_INT_USE) - exec_using_spi = TRUE; - #endif - - rssi = rfm22_read(RFM22_rssi); // read rx signal strength .. 45 = -100dBm, 205 = -20dBm - rssi_dBm = ((int16_t)rssi / 2) - 122; // convert to dBm - - #if defined(RFM22_EXT_INT_USE) - exec_using_spi = FALSE; - #endif - - return rssi_dBm; -} - -int16_t rfm22_receivedRSSI(void) -{ // return the packets signal strength - if (!initialized) - return -200; - else - return rx_packet_rssi_dBm; -} - -int32_t rfm22_receivedAFCHz(void) -{ // return the packets offset frequency - if (!initialized) - return 0; - else - return rx_packet_afc_Hz; -} - -uint16_t rfm22_receivedLength(void) -{ // return the size of the data received - if (!initialized) - return 0; - else - return rx_packet_wr; -} - -uint8_t * rfm22_receivedPointer(void) -{ // return the address of the data - return (uint8_t *)&rx_packet_buf; -} - -void rfm22_receivedDone(void) -{ // empty the rx packet buffer - rx_packet_wr = 0; -} - -// ************************************ - -int32_t rfm22_sendData(void *data, uint16_t length, bool send_immediately) -{ - if (!initialized) - return -1; // we are not yet initialized - - if (length == 0) - return -2; // no data to send - - if (!data || length > 255) - return -3; // no data or too much data to send - - if (tx_data_wr > 0) - return -4; // already have data to be sent - - if (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE || rf_mode == RX_SCAN_SPECTRUM) - return -5; // we are currently transmitting or scanning the spectrum - - tx_data_addr = data; - tx_data_rd = 0; - tx_data_wr = length; - - #if defined(RFM22_DEBUG) - DEBUG_PRINTF("rf sendData(0x%08x %u)\r\n", (uint32_t)tx_data_addr, tx_data_wr); - #endif - - if (send_immediately || rfm22_channelIsClear()) // is the channel clear to transmit on? - rfm22_setTxMode(TX_DATA_MODE); // transmit NOW - - return tx_data_wr; -} - -// ************************************ - -void rfm22_setTxStream(void) // TEST ONLY -{ - if (!initialized) - return; - - tx_data_rd = tx_data_wr = 0; - - rfm22_setTxMode(TX_STREAM_MODE); -} - -// ************************************ - -void rfm22_setTxNormal(void) -{ - if (!initialized) - return; - -// if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE) - if (rf_mode != RX_SCAN_SPECTRUM) - { - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - tx_data_rd = tx_data_wr = 0; - - rx_packet_wr = 0; - rx_packet_start_rssi_dBm = 0; - rx_packet_start_afc_Hz = 0; - rx_packet_rssi_dBm = 0; - rx_packet_afc_Hz = 0; - } -} - -// enable a blank tx carrier (for frequency alignment) -void rfm22_setTxCarrierMode(void) -{ - if (!initialized) - return; - - if (rf_mode != TX_CARRIER_MODE && rf_mode != RX_SCAN_SPECTRUM) - rfm22_setTxMode(TX_CARRIER_MODE); -} - -// enable a psuedo random data tx carrier (for spectrum inspection) -void rfm22_setTxPNMode(void) -{ - if (!initialized) - return; - - if (rf_mode != TX_PN_MODE && rf_mode != RX_SCAN_SPECTRUM) - rfm22_setTxMode(TX_PN_MODE); -} - -// ************************************ - -// return the current mode -int8_t rfm22_currentMode(void) -{ - return rf_mode; -} - -// return TRUE if we are transmitting -bool rfm22_transmitting(void) -{ - return (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE); -} - -// return TRUE if the channel is clear to transmit on -bool rfm22_channelIsClear(void) -{ - if (!initialized) - return FALSE; // we haven't yet been initialized - - if (rf_mode != RX_WAIT_PREAMBLE_MODE && rf_mode != RX_WAIT_SYNC_MODE) - return FALSE; // we are receiving something or we are transmitting or we are scanning the spectrum - - return TRUE; -// return (STOPWATCH_get_count() > clear_channel_count); -} - -// return TRUE if the transmiter is ready for use -bool rfm22_txReady(void) -{ - if (!initialized) - return FALSE; // we haven't yet been initialized - - return (tx_data_rd == 0 && tx_data_wr == 0 && rf_mode != TX_DATA_MODE && rf_mode != TX_STREAM_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE && rf_mode != RX_SCAN_SPECTRUM); -} - -// ************************************ -// set/get the frequency calibration value - -void rfm22_setFreqCalibration(uint8_t value) -{ - osc_load_cap = value; - - if (!initialized || power_on_reset) - return; // we haven't yet been initialized - - uint8_t prev_rf_mode = rf_mode; - - if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE) - { - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - tx_data_rd = tx_data_wr = 0; - } - - #if defined(RFM22_EXT_INT_USE) - exec_using_spi = TRUE; - #endif - - rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap); - - #if defined(RFM22_EXT_INT_USE) - exec_using_spi = FALSE; - #endif - - if (prev_rf_mode == TX_CARRIER_MODE || prev_rf_mode == TX_PN_MODE) - rfm22_setTxMode(prev_rf_mode); -} - -uint8_t rfm22_getFreqCalibration(void) -{ - return osc_load_cap; -} - -// ************************************ -// can be called from an interrupt if you wish - -void rfm22_1ms_tick(void) -{ // call this once every ms - if (booting) return; - if (!initialized) return; // we haven't yet been initialized - - if (rf_mode != RX_SCAN_SPECTRUM) - { - if (rfm22_int_timer < 0xffff) rfm22_int_timer++; - } -} - -// ***************************************************************************** -// call this as often as possible - not from an interrupt - -void rfm22_process(void) -{ - if (booting) return; - if (!initialized) return; // we haven't yet been initialized - - #if !defined(RFM22_EXT_INT_USE) - if (rf_mode != RX_SCAN_SPECTRUM) - rfm22_processInt(); // manually poll the interrupt line routine - #endif - - if (power_on_reset) - { // we need to re-initialize the RF module - it told us it's reset itself - if (rf_mode != RX_SCAN_SPECTRUM) - { // normal data mode - uint32_t current_freq = carrier_frequency_hz; // fetch current rf nominal frequency - rfm22_init_normal(lower_carrier_frequency_limit_Hz, upper_carrier_frequency_limit_Hz, rfm22_freqHopSize()); - rfm22_setNominalCarrierFrequency(current_freq); // restore the nominal carrier frequency - } - else - { // we are scanning the spectrum - rfm22_init_scan_spectrum(lower_carrier_frequency_limit_Hz, upper_carrier_frequency_limit_Hz); - } - return; - } - - switch (rf_mode) - { - case RX_SCAN_SPECTRUM: // we are scanning the spectrum - - // read device status register - device_status = rfm22_read(RFM22_device_status); - - // read ezmac status register - ezmac_status = rfm22_read(RFM22_ezmac_status); - - // read interrupt status registers - clears the interrupt line - int_status1 = rfm22_read(RFM22_interrupt_status1); - int_status2 = rfm22_read(RFM22_interrupt_status2); - - if (int_status2 & RFM22_is2_ipor) - { // the RF module has gone and done a reset - we need to re-initialize the rf module - initialized = FALSE; - power_on_reset = TRUE; - return; - } - - break; - - case RX_WAIT_PREAMBLE_MODE: - - if (rfm22_int_timer >= timeout_ms) - { // assume somethings locked up - rfm22_int_time_outs++; - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the RF module to rx mode - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - - // go to transmit mode if we have data to send and the channel is clear to transmit on - if (tx_data_rd == 0 && tx_data_wr > 0 && rfm22_channelIsClear()) - { - rfm22_setTxMode(TX_DATA_MODE); // transmit packet NOW - break; - } - - break; - - case RX_WAIT_SYNC_MODE: - - if (rfm22_int_timer >= timeout_sync_ms) - { // assume somethings locked up - rfm22_int_time_outs++; - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the RF module to rx mode - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - - // go to transmit mode if we have data to send and the channel is clear to transmit on - if (tx_data_rd == 0 && tx_data_wr > 0 && rfm22_channelIsClear()) - { - rfm22_setTxMode(TX_DATA_MODE); // transmit packet NOW - break; - } - - break; - - case RX_DATA_MODE: - case TX_DATA_MODE: - - if (rfm22_int_timer >= timeout_data_ms) - { // assume somethings locked up - rfm22_int_time_outs++; - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the RF module to rx mode - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - - break; - - case TX_STREAM_MODE: - - // todo: - - break; - - case TX_CARRIER_MODE: - case TX_PN_MODE: - -// if (rfm22_int_timer >= TX_TEST_MODE_TIMELIMIT_MS) -// { -// rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode -// tx_data_rd = tx_data_wr = 0; // wipe TX buffer -// break; -// } - - break; - - default: - // unknown mode - this should never happen, maybe we should do a complete CPU reset here? - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // to rx mode - tx_data_rd = tx_data_wr = 0; // wipe TX buffer - break; - } - - #if defined(RFM22_INT_TIMEOUT_DEBUG) - if (prev_rfm22_int_time_outs != rfm22_int_time_outs) - { - prev_rfm22_int_time_outs = rfm22_int_time_outs; - DEBUG_PRINTF("rf int timeouts %d\r\n", rfm22_int_time_outs); - } - #endif -} - -// ************************************ - -void rfm22_TxDataByte_SetCallback(t_rfm22_TxDataByteCallback new_function) -{ - tx_data_byte_callback_function = new_function; -} - -void rfm22_RxData_SetCallback(t_rfm22_RxDataCallback new_function) -{ - rx_data_callback_function = new_function; -} - -// ************************************ -// reset the RF module - -int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_frequency_hz) -{ - initialized = false; - -#if defined(RFM22_EXT_INT_USE) - rfm22_disableExtInt(); -#endif - - power_on_reset = false; - - // **************** - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = TRUE; -#endif - - // **************** - // setup the SPI port - - // chip select line HIGH - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1); - - // set SPI port SCLK frequency .. 4.5MHz - PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_16); - // set SPI port SCLK frequency .. 2.25MHz -// PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_32); - - // set SPI port SCLK frequency .. 285kHz .. purely for hardware fault finding -// PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_256); - - // **************** - // software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B) - - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_swres); // software reset the radio - - PIOS_DELAY_WaitmS(26); // wait 26ms - - for (int i = 50; i > 0; i--) - { - PIOS_DELAY_WaitmS(1); // wait 1ms - - // read the status registers - int_status1 = rfm22_read(RFM22_interrupt_status1); - int_status2 = rfm22_read(RFM22_interrupt_status2); - if (int_status2 & RFM22_is2_ichiprdy) break; - } - - // **************** - - // read status - clears interrupt - device_status = rfm22_read(RFM22_device_status); - int_status1 = rfm22_read(RFM22_interrupt_status1); - int_status2 = rfm22_read(RFM22_interrupt_status2); - ezmac_status = rfm22_read(RFM22_ezmac_status); - - // disable all interrupts - rfm22_write(RFM22_interrupt_enable1, 0x00); - rfm22_write(RFM22_interrupt_enable2, 0x00); - - // **************** - -#if defined(RFM22_EXT_INT_USE) - exec_using_spi = FALSE; -#endif - - // **************** - -#if defined(RFM22_EXT_INT_USE) - inside_ext_int = FALSE; -#endif - - rf_mode = mode; - - device_status = int_status1 = int_status2 = ezmac_status = 0; - - rssi = 0; - rssi_dBm = -200; - - tx_data_byte_callback_function = NULL; - rx_data_callback_function = NULL; - - rx_buffer_current = 0; - rx_buffer_wr = 0; - rx_packet_wr = 0; - rx_packet_rssi_dBm = -200; - rx_packet_afc_Hz = 0; - - tx_data_addr = NULL; - tx_data_rd = tx_data_wr = 0; - - lookup_index = 0; - ss_lookup_index = 0; - - rf_bandwidth_used = 0; - ss_rf_bandwidth_used = 0; - - rfm22_int_timer = 0; - rfm22_int_time_outs = 0; - prev_rfm22_int_time_outs = 0; - - hbsel = 0; - frequency_step_size = 0.0f; - - frequency_hop_channel = 0; - - afc_correction = 0; - afc_correction_Hz = 0; - - temperature_reg = 0; - - // set the TX power - tx_power = RFM22_DEFAULT_RF_POWER; - - tx_pwr = 0; - - // **************** - // read the RF chip ID bytes - - device_type = rfm22_read(RFM22_DEVICE_TYPE) & RFM22_DT_MASK; // read the device type - device_version = rfm22_read(RFM22_DEVICE_VERSION) & RFM22_DV_MASK; // read the device version - - #if defined(RFM22_DEBUG) - DEBUG_PRINTF("rf device type: %d\r\n", device_type); - DEBUG_PRINTF("rf device version: %d\r\n", device_version); - #endif - - if (device_type != 0x08) - { - #if defined(RFM22_DEBUG) - DEBUG_PRINTF("rf device type: INCORRECT - should be 0x08\r\n"); - #endif - return -1; // incorrect RF module type - } - -// if (device_version != RFM22_DEVICE_VERSION_V2) // V2 -// return -2; // incorrect RF module version -// if (device_version != RFM22_DEVICE_VERSION_A0) // A0 -// return -2; // incorrect RF module version - if (device_version != RFM22_DEVICE_VERSION_B1) // B1 - { - #if defined(RFM22_DEBUG) - DEBUG_PRINTF("rf device version: INCORRECT\r\n"); - #endif - return -2; // incorrect RF module version - } - - // **************** - // set the minimum and maximum carrier frequency allowed - - if (min_frequency_hz < RFM22_MIN_CARRIER_FREQUENCY_HZ) min_frequency_hz = RFM22_MIN_CARRIER_FREQUENCY_HZ; - else - if (min_frequency_hz > RFM22_MAX_CARRIER_FREQUENCY_HZ) min_frequency_hz = RFM22_MAX_CARRIER_FREQUENCY_HZ; - - if (max_frequency_hz < RFM22_MIN_CARRIER_FREQUENCY_HZ) max_frequency_hz = RFM22_MIN_CARRIER_FREQUENCY_HZ; - else - if (max_frequency_hz > RFM22_MAX_CARRIER_FREQUENCY_HZ) max_frequency_hz = RFM22_MAX_CARRIER_FREQUENCY_HZ; - - if (min_frequency_hz > max_frequency_hz) - { // swap them over - uint32_t tmp = min_frequency_hz; - min_frequency_hz = max_frequency_hz; - max_frequency_hz = tmp; - } - - lower_carrier_frequency_limit_Hz = min_frequency_hz; - upper_carrier_frequency_limit_Hz = max_frequency_hz; - - // **************** - // calibrate our RF module to be exactly on frequency .. different for every module - - osc_load_cap = OSC_LOAD_CAP; // default - rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap); - - // **************** - - // disable Low Duty Cycle Mode - rfm22_write(RFM22_op_and_func_ctrl2, 0x00); - - rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); // 1MHz clock output - - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode -// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode - - // choose the 3 GPIO pin functions - rfm22_write(RFM22_io_port_config, RFM22_io_port_default); // GPIO port use default value - rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch) - rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch) - rfm22_write(RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca); // GPIO2 = Clear Channel Assessment - - // **************** - - return 0; // OK -} - -// ************************************ - -int rfm22_init_scan_spectrum(uint32_t min_frequency_hz, uint32_t max_frequency_hz) -{ - #if defined(RFM22_DEBUG) - DEBUG_PRINTF("\r\nRF init scan spectrum\r\n"); - #endif - - int res = rfm22_resetModule(RX_SCAN_SPECTRUM, min_frequency_hz, max_frequency_hz); - if (res < 0) - return res; - -// rfm22_setSSBandwidth(0); - rfm22_setSSBandwidth(1); - - // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); - - rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); // 1MHz clock output - - rfm22_write(RFM22_rssi_threshold_clear_chan_indicator, 0); - - rfm22_write(RFM22_preamble_detection_ctrl1, 31 << 3); // 31-nibbles rx preamble detection - - // avoid packet detection - rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_encrc); - rfm22_write(RFM22_header_control1, 0x0f); - rfm22_write(RFM22_header_control2, 0x77); - - rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); - rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); - rfm22_write(RFM22_sync_word1, SYNC_BYTE_3 ^ 0xff); - rfm22_write(RFM22_sync_word0, SYNC_BYTE_4 ^ 0xff); - - // all the bits to be checked - rfm22_write(RFM22_header_enable3, 0xff); - rfm22_write(RFM22_header_enable2, 0xff); - rfm22_write(RFM22_header_enable1, 0xff); - rfm22_write(RFM22_header_enable0, 0xff); - -// rfm22_write(RFM22_frequency_hopping_step_size, 0); // set frequency hopping channel step size (multiples of 10kHz) - - rfm22_setNominalCarrierFrequency(min_frequency_hz); // set our nominal carrier frequency - - rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | 0); // set minimum tx power - - rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen); - -// rfm22_write(RFM22_vco_current_trimming, 0x7f); -// rfm22_write(RFM22_vco_calibration_override, 0x40); -// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80); - -#if defined(RFM22_EXT_INT_USE) - // Enable RF module external interrupt - rfm22_enableExtInt(); -#endif - - rfm22_setRxMode(RX_SCAN_SPECTRUM, true); - - initialized = true; - - return 0; // OK -} - -// ************************************ - -int rfm22_init_tx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz) -{ - #if defined(RFM22_DEBUG) - DEBUG_PRINTF("\r\nRF init TX stream\r\n"); - #endif - - int res = rfm22_resetModule(TX_STREAM_MODE, min_frequency_hz, max_frequency_hz); - if (res < 0) - return res; - - frequency_hop_step_size_reg = 0; - - // set the RF datarate - rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, FALSE); - - // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); - - // disable the internal Tx & Rx packet handlers (without CRC) - rfm22_write(RFM22_data_access_control, 0); - - rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble - rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection - - rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header - rfm22_write(RFM22_header_control2, RFM22_header_cntl2_fixpklen | RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_32 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2 used, packet length not included in header (fixed packet length). - - rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word - rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); // - -// rfm22_write(RFM22_modem_test, 0x01); - - rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen); -// rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen); - - rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz) - - rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency - - rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); // set the tx power -// rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | tx_power); // set the tx power - -// rfm22_write(RFM22_vco_current_trimming, 0x7f); -// rfm22_write(RFM22_vco_calibration_override, 0x40); -// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80); - - rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); // TX FIFO Almost Full Threshold (0 - 63) - rfm22_write(RFM22_tx_fifo_control2, TX_FIFO_LO_WATERMARK); // TX FIFO Almost Empty Threshold (0 - 63) - - #if defined(RFM22_EXT_INT_USE) - // Enable RF module external interrupt - rfm22_enableExtInt(); - #endif - - initialized = true; - - return 0; // OK -} - -// ************************************ - -int rfm22_init_rx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz) -{ - #if defined(RFM22_DEBUG) - DEBUG_PRINTF("\r\nRF init RX stream\r\n"); - #endif - - int res = rfm22_resetModule(RX_WAIT_PREAMBLE_MODE, min_frequency_hz, max_frequency_hz); - if (res < 0) - return res; - - frequency_hop_step_size_reg = 0; - - // set the RF datarate - rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, FALSE); - - // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); - - // disable the internal Tx & Rx packet handlers (without CRC) - rfm22_write(RFM22_data_access_control, 0); - - rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble - rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection - - rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header - rfm22_write(RFM22_header_control2, RFM22_header_cntl2_fixpklen | RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_32 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2 used, packet length not included in header (fixed packet length). - - rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word - rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); // - - // no header bits to be checked - rfm22_write(RFM22_header_enable3, 0x00); - rfm22_write(RFM22_header_enable2, 0x00); - rfm22_write(RFM22_header_enable1, 0x00); - rfm22_write(RFM22_header_enable0, 0x00); - -// rfm22_write(RFM22_modem_test, 0x01); - - rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen); -// rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen); - - rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz) - - rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency - -// rfm22_write(RFM22_vco_current_trimming, 0x7f); -// rfm22_write(RFM22_vco_calibration_override, 0x40); -// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80); - - rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); // RX FIFO Almost Full Threshold (0 - 63) - - #if defined(RFM22_EXT_INT_USE) - // Enable RF module external interrupt - rfm22_enableExtInt(); - #endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - - initialized = true; - - return 0; // OK -} - -// ************************************ -// Initialise this hardware layer module and the rf module - -int rfm22_init_normal(uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size) -{ - #if defined(RFM22_DEBUG) - DEBUG_PRINTF("\r\nRF init normal\r\n"); - #endif - - int res = rfm22_resetModule(RX_WAIT_PREAMBLE_MODE, min_frequency_hz, max_frequency_hz); - if (res < 0) - return res; - - // **************** - - freq_hop_step_size /= 10000; // in 10kHz increments - if (freq_hop_step_size > 255) freq_hop_step_size = 255; - - frequency_hop_step_size_reg = freq_hop_step_size; - - // **************** - - // set the RF datarate - rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, TRUE); - - // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); - - // setup to read the internal temperature sensor - adc_config = RFM22_ac_adcsel_temp_sensor | RFM22_ac_adcref_bg; // ADC used to sample the temperature sensor - rfm22_write(RFM22_adc_config, adc_config); // - rfm22_write(RFM22_adc_sensor_amp_offset, 0); // adc offset - rfm22_write(RFM22_temp_sensor_calib, RFM22_tsc_tsrange0 | RFM22_tsc_entsoffs); // temp sensor calibration .. –40C to +64C 0.5C resolution - rfm22_write(RFM22_temp_value_offset, 0); // temp sensor offset - rfm22_write(RFM22_adc_config, adc_config | RFM22_ac_adcstartbusy); // start an ADC conversion - - rfm22_write(RFM22_rssi_threshold_clear_chan_indicator, (-90 + 122) * 2); // set the RSSI threshold interrupt to about -90dBm - - // enable the internal Tx & Rx packet handlers (with CRC) -// rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_enpactx | RFM22_dac_encrc | RFM22_dac_crc_crc16); - // enable the internal Tx & Rx packet handlers (without CRC) - rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_enpactx); - - rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble - rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection - - rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header - rfm22_write(RFM22_header_control2, RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_3210 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header. - - rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word - rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); // - rfm22_write(RFM22_sync_word1, SYNC_BYTE_3); // - rfm22_write(RFM22_sync_word0, SYNC_BYTE_4); // -/* - rfm22_write(RFM22_transmit_header3, 'p'); // set tx header - rfm22_write(RFM22_transmit_header2, 'i'); // - rfm22_write(RFM22_transmit_header1, 'p'); // - rfm22_write(RFM22_transmit_header0, ' '); // - - rfm22_write(RFM22_check_header3, 'p'); // set expected rx header - rfm22_write(RFM22_check_header2, 'i'); // - rfm22_write(RFM22_check_header1, 'p'); // - rfm22_write(RFM22_check_header0, ' '); // - - // all the bits to be checked - rfm22_write(RFM22_header_enable3, 0xff); - rfm22_write(RFM22_header_enable2, 0xff); - rfm22_write(RFM22_header_enable1, 0xff); - rfm22_write(RFM22_header_enable0, 0xff); -*/ // no bits to be checked - rfm22_write(RFM22_header_enable3, 0x00); - rfm22_write(RFM22_header_enable2, 0x00); - rfm22_write(RFM22_header_enable1, 0x00); - rfm22_write(RFM22_header_enable0, 0x00); - -// rfm22_write(RFM22_modem_test, 0x01); - - rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen); -// rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen); - - rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz) - - rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency - - rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); // set the tx power -// rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | tx_power); // set the tx power - -// rfm22_write(RFM22_vco_current_trimming, 0x7f); -// rfm22_write(RFM22_vco_calibration_override, 0x40); -// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80); - - rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); // TX FIFO Almost Full Threshold (0 - 63) - rfm22_write(RFM22_tx_fifo_control2, TX_FIFO_LO_WATERMARK); // TX FIFO Almost Empty Threshold (0 - 63) - - rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); // RX FIFO Almost Full Threshold (0 - 63) - -#if defined(RFM22_EXT_INT_USE) - // Enable RF module external interrupt - rfm22_enableExtInt(); -#endif - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - - initialized = true; - - return 0; // ok -} - -// ************************************ diff --git a/flight/PipXtreme/saved_settings.c b/flight/PipXtreme/saved_settings.c deleted file mode 100644 index badef5673..000000000 --- a/flight/PipXtreme/saved_settings.c +++ /dev/null @@ -1,326 +0,0 @@ -/** - ****************************************************************************** - * - * @file saved_settings.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RF Module hardware layer - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include // memmove, memset - -#include "crc.h" -#include "gpio_in.h" -#include "saved_settings.h" -#include "main.h" - -#if defined(PIOS_COM_DEBUG) - #define SAVED_SETTINGS_DEBUG -#endif - -// ***************************************************************** - -// default aes 128-bit encryption key -const uint8_t saved_settings_default_aes_key[16] = {0x65, 0x3b, 0x71, 0x89, 0x4a, 0xf4, 0xc8, 0xcb, 0x18, 0xd4, 0x9b, 0x4d, 0x4a, 0xbe, 0xc8, 0x37}; - -// ***************************************************************** - -#define pages 1 // number of flash pages to use - -uint32_t eeprom_addr; // the address of the emulated EEPROM area in program flash area -uint16_t eeprom_page_size; // flash page size - -volatile t_saved_settings saved_settings __attribute__ ((aligned(4))); // a RAM copy of the settings stored in EEPROM -t_saved_settings tmp_settings __attribute__ ((aligned(4))); - -// ***************************************************************** -// Private functions - -bool saved_settings_page_empty(int page) -{ // return TRUE if the flash page is emtpy (erased), otherwise return FALSE - - if (page < 0 || page >= pages) - return FALSE; - - __IO uint32_t *addr = (__IO uint32_t *)(eeprom_addr + eeprom_page_size * page); - int32_t len = eeprom_page_size / 4; - - for (int32_t i = len; i > 0; i--) - if (*addr++ != 0xffffffff) - return FALSE; // the page is not erased - - return TRUE; -} - -bool saved_settings_settings_empty(uint32_t addr) -{ // return TRUE if the settings flash area is emtpy (erased), otherwise return FALSE - - __IO uint8_t *p = (__IO uint8_t *)addr; - - for (int32_t i = sizeof(t_saved_settings); i > 0; i--) - if (*p++ != 0xff) - return FALSE; // the flash area is not empty/erased - - return TRUE; -} - -// ***************************************************************** - -int32_t saved_settings_read(void) -{ // look for the last valid settings saved in EEPROM - - uint32_t flash_addr; - __IO uint8_t *p1; - uint8_t *p2; - - flash_addr = eeprom_addr; - - if (saved_settings_settings_empty(flash_addr)) - { - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("settings Read, no settings found at %08X\r\n", flash_addr); - #endif - - return -1; // no settings found at the specified addr - } - - // copy the data from program flash area into temp settings area - p1 = (__IO uint8_t *)flash_addr; - p2 = (uint8_t *)&tmp_settings; - for (int32_t i = 0; i < sizeof(t_saved_settings); i++) - *p2++ = *p1++; - - // calculate and check the CRC - uint32_t crc1 = tmp_settings.crc; - tmp_settings.crc = 0; - uint32_t crc2 = updateCRC32Data(0xffffffff, (void *)&tmp_settings, sizeof(t_saved_settings)); - if (crc2 != crc1) - { - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("settings Read crc error: %08X %08X\r\n", crc1, crc2); - #endif - - return -2; // error - } - - memmove((void *)&saved_settings, (void *)&tmp_settings, sizeof(t_saved_settings)); - - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("settings Read OK!\r\n"); - #endif - - return 0; // OK -} - -// ***************************************************************** -// Public functions - -int32_t saved_settings_save(void) -{ // save the settings into EEPROM - - FLASH_Status fs; - uint32_t flash_addr; - uint8_t *p1; - __IO uint8_t *p2; - uint32_t *p3; - bool do_save; - - // size of the settings aligned to 4 bytes -// uint16_t settings_size = (uint16_t)(sizeof(t_saved_settings) + 3) & 0xfffc; - - // address of settings in FLASH area - flash_addr = eeprom_addr; - - // ***************************************** - // calculate and add the CRC - - saved_settings.crc = 0; - saved_settings.crc = updateCRC32Data(0xffffffff, (void *)&saved_settings, sizeof(t_saved_settings)); - - // ***************************************** - // first check to see if we need to save the settings - - p1 = (uint8_t *)&saved_settings; - p2 = (__IO uint8_t *)flash_addr; - do_save = FALSE; - - for (int32_t i = 0; i < sizeof(t_saved_settings); i++) - { - if (*p1++ != *p2++) - { // we need to save the settings - do_save = TRUE; - break; - } - } - - if (!do_save) - { - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("settings already saved OK\r\n"); - #endif - - return 0; // settings already saved .. all OK - } - - // ***************************************** - - // Unlock the Flash Program Erase controller - FLASH_Unlock(); - - if (!saved_settings_page_empty(0)) - { // erase the page - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("settings erasing page .. "); - #endif - - fs = FLASH_ErasePage(eeprom_addr); - if (fs != FLASH_COMPLETE) - { // error - FLASH_Lock(); - - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("error %d\r\n", fs); - #endif - - return -1; - } - - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("OK\r\n"); - #endif - } - else - { - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("settings page already erased\r\n"); - #endif - } - - // ***************************************** - // save the settings into flash area (emulated EEPROM area) - - p1 = (uint8_t *)&saved_settings; - p3 = (uint32_t *)flash_addr; - - // write 4 bytes at a time into program flash area (emulated EEPROM area) - for (int32_t i = 0; i < sizeof(t_saved_settings); p3++) - { - uint32_t value = 0; - if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 0; else value |= 0x000000ff; i++; - if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 8; else value |= 0x0000ff00; i++; - if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 16; else value |= 0x00ff0000; i++; - if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 24; else value |= 0xff000000; i++; - - fs = FLASH_ProgramWord((uint32_t)p3, value); // write a 32-bit value - if (fs != FLASH_COMPLETE) - { - FLASH_Lock(); - - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("settings FLASH_ProgramWord error: %d\r\n", fs); - #endif - - return -2; // error - } - } - - // Lock the Flash Program Erase controller - FLASH_Lock(); - - // ***************************************** - // now error check it by reading it back (simple compare) - - p1 = (uint8_t *)&saved_settings; - p2 = (__IO uint8_t *)flash_addr; - - for (int32_t i = 0; i < sizeof(t_saved_settings); i++) - { - if (*p1++ != *p2++) - { - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("settings WriteSettings compare error\r\n"); - #endif - - return -3; // error - } - } - - // ***************************************** - - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("settings Save OK!\r\n"); - #endif - - return 0; // OK -} - -void saved_settings_init(void) -{ - // ********** - // determine emulated EEPROM details - - if (flash_size < 256000) - eeprom_page_size = 1024; // 1 kByte - else - eeprom_page_size = 2048; // 2 kByte - - // place emulated eeprom at end of program flash area - eeprom_addr = (0x08000000 + flash_size) - (eeprom_page_size * pages); - - #if defined(SAVED_SETTINGS_DEBUG) - DEBUG_PRINTF("\r\n"); - DEBUG_PRINTF("settings eeprom addr: %08x\r\n", eeprom_addr); - DEBUG_PRINTF("settings eeprom page size: %u\r\n", eeprom_page_size); - DEBUG_PRINTF("settings eeprom pages: %u\r\n", pages); - #endif - - // ********** - // default settings - - memset((void *)&saved_settings, 0xff, sizeof(t_saved_settings)); - - saved_settings.mode = MODE_NORMAL; - - saved_settings.destination_id = 0; - - saved_settings.frequency_band = FREQBAND_UNKNOWN; - - saved_settings.rf_xtal_cap = 0x7f; - - saved_settings.aes_enable = FALSE; - memmove((void *)&saved_settings.aes_key, saved_settings_default_aes_key, sizeof(saved_settings.aes_key)); - - saved_settings.serial_baudrate = 57600; - - saved_settings.rts_time = 10; // ms - -// saved_settings.crc = 0; -// saved_settings.crc = updateCRC32Data(0xffffffff, (void *)&saved_settings, sizeof(t_saved_settings)); - - // ********** - - // Lock the Flash Program Erase controller - FLASH_Lock(); - - saved_settings_read(); - - // ********** -} - -// ***************************************************************** diff --git a/flight/PipXtreme/stopwatch.c b/flight/PipXtreme/stopwatch.c deleted file mode 100644 index c1e983e91..000000000 --- a/flight/PipXtreme/stopwatch.c +++ /dev/null @@ -1,156 +0,0 @@ -/** - ****************************************************************************** - * - * @file stopwatch.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Stop watch function - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "stopwatch.h" -#include "main.h" - -// ***************************************************************************** - -uint32_t resolution_us = 0; - -// ***************************************************************************** -// initialise the stopwatch - -void STOPWATCH_init(uint32_t resolution) -{ - resolution_us = resolution; - - if (resolution_us == 0) - return; - - // enable timer clock - switch ((uint32_t)STOPWATCH_TIMER) - { - case (uint32_t)TIM1: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); break; - case (uint32_t)TIM2: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); break; - case (uint32_t)TIM3: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); break; - case (uint32_t)TIM4: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); break; - #ifdef STM32F10X_HD - case (uint32_t)TIM5: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); break; - case (uint32_t)TIM6: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); break; - case (uint32_t)TIM7: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); break; - case (uint32_t)TIM8: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); break; - #endif - } - - // time base configuration - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - TIM_TimeBaseStructure.TIM_Period = 0xffff; // max period - TIM_TimeBaseStructure.TIM_Prescaler = ((PIOS_MASTER_CLOCK / 1000000) * resolution_us) - 1; // uS accuracy @ 72 MHz - TIM_TimeBaseStructure.TIM_ClockDivision = 0; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseInit(STOPWATCH_TIMER, &TIM_TimeBaseStructure); - - // enable interrupt request - TIM_ITConfig(STOPWATCH_TIMER, TIM_IT_Update, ENABLE); - - // start counter - TIM_Cmd(STOPWATCH_TIMER, ENABLE); -} - -// ***************************************************************************** -// timer interrupt -/* -#ifdef STM32F10X_MD - #if (STOPWATCH_TIMER == TIM1) - void TIM1_IRQHandler(void) - #if (STOPWATCH_TIMER == TIM2) - void TIM2_IRQHandler(void) - #elif (STOPWATCH_TIMER == TIM3) - void TIM3_IRQHandler(void) - #elif (STOPWATCH_TIMER == TIM4) - void TIM4_IRQHandler(void) - #endif -#endif -#ifdef STM32F10X_HD - #if (STOPWATCH_TIMER == TIM1) - void TIM1_IRQHandler(void) - #if (STOPWATCH_TIMER == TIM2) - void TIM2_IRQHandler(void) - #elif (STOPWATCH_TIMER == TIM3) - void TIM3_IRQHandler(void) - #elif (STOPWATCH_TIMER == TIM4) - void TIM4_IRQHandler(void) - #elif (STOPWATCH_TIMER == TIM5) - void TIM5_IRQHandler(void) - #elif (STOPWATCH_TIMER == TIM6) - void TIM6_IRQHandler(void) - #elif (STOPWATCH_TIMER == TIM7) - void TIM7_IRQHandler(void) - #elif (STOPWATCH_TIMER == TIM8) - void TIM8_IRQHandler(void) - #endif -#endif -{ - -} -*/ -// ***************************************************************************** -// resets the stopwatch - -void STOPWATCH_reset(void) -{ - if (resolution_us > 0) - { // reset the counter - STOPWATCH_TIMER->CNT = 1; // set to 1 instead of 0 to avoid new IRQ request - TIM_ClearITPendingBit(STOPWATCH_TIMER, TIM_IT_Update); - } -} - -// ***************************************************************************** -// returns the timer count since the last STOPWATCH_reset() call -// return 0xffffffff if counter overrun or not initialised - -uint32_t STOPWATCH_get_count(void) -{ - uint32_t value = STOPWATCH_TIMER->CNT; // get counter value ASAP - - if (resolution_us == 0) - return 0xffffffff; // not initialized - - if (TIM_GetITStatus(STOPWATCH_TIMER, TIM_IT_Update) != RESET) - return 0xffffffff; // timer overfloaw - - return value; // return the timer count -} - -// ***************************************************************************** -// returns number of us since the last STOPWATCH_reset() call -// return 0xffffffff if counter overrun or not initialised - -uint32_t STOPWATCH_get_us(void) -{ - uint32_t value = STOPWATCH_TIMER->CNT; // get counter value ASAP - - if (resolution_us == 0) - return 0xffffffff; // not initialized - - if (TIM_GetITStatus(STOPWATCH_TIMER, TIM_IT_Update) != RESET) - return 0xffffffff; // timer overfloaw - - return (value * resolution_us); // return number of micro seconds -} - -// ***************************************************************************** diff --git a/flight/PipXtreme/stream.c b/flight/PipXtreme/stream.c deleted file mode 100644 index 924333a24..000000000 --- a/flight/PipXtreme/stream.c +++ /dev/null @@ -1,122 +0,0 @@ -/** - ****************************************************************************** - * - * @file stream.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sends or Receives a continuous packet stream to/from the remote unit - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -//#include // memmove - -#include "main.h" -#include "rfm22b.h" -#include "fifo_buffer.h" -#include "aes.h" -#include "crc.h" -#include "saved_settings.h" -#include "stream.h" - -#if defined(PIOS_COM_DEBUG) - #define STREAM_DEBUG -#endif - -// ************************************************************* -// can be called from an interrupt if you wish -// call this once every ms - -void stream_1ms_tick(void) -{ - if (booting) return; - - if (saved_settings.mode == MODE_STREAM_TX) - { - } - else - if (saved_settings.mode == MODE_STREAM_RX) - { - } -} - -// ************************************************************* -// return a byte for the tx packet transmission. -// -// return value < 0 if no more bytes available, otherwise return byte to be sent - -int16_t stream_TxDataByteCallback(void) -{ - return -1; -} - -// ************************************************************* -// we are being given a block of received bytes -// -// return TRUE to continue current packet receive, otherwise return FALSE to halt current packet reception - -bool stream_RxDataCallback(void *data, uint8_t len) -{ - return true; -} - -// ************************************************************* -// call this from the main loop (not interrupt) as often as possible - -void stream_process(void) -{ - if (booting) return; - - if (saved_settings.mode == MODE_STREAM_TX) - { - } - else - if (saved_settings.mode == MODE_STREAM_RX) - { - } -} - -// ************************************************************* - -void stream_deinit(void) -{ -} - -void stream_init(uint32_t our_sn) -{ - #if defined(STREAM_DEBUG) - DEBUG_PRINTF("\r\nSTREAM init\r\n"); - #endif - - if (saved_settings.mode == MODE_STREAM_TX) - rfm22_init_tx_stream(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz); - else - if (saved_settings.mode == MODE_STREAM_RX) - rfm22_init_rx_stream(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz); - - rfm22_TxDataByte_SetCallback(stream_TxDataByteCallback); - rfm22_RxData_SetCallback(stream_RxDataCallback); - - rfm22_setFreqCalibration(saved_settings.rf_xtal_cap); - rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz); - rfm22_setDatarate(saved_settings.max_rf_bandwidth, FALSE); - rfm22_setTxPower(saved_settings.max_tx_power); - - rfm22_setTxStream(); // TEST ONLY -} - -// ************************************************************* diff --git a/flight/PipXtreme/transparent_comms.c b/flight/PipXtreme/transparent_comms.c deleted file mode 100644 index dc5e0384a..000000000 --- a/flight/PipXtreme/transparent_comms.c +++ /dev/null @@ -1,218 +0,0 @@ -/** - ****************************************************************************** - * - * @file transparent_comms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Serial communication port handling routines - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include - -#include "stm32f10x.h" -#include "gpio_in.h" -#include "transparent_comms.h" -#include "packet_handler.h" -#include "saved_settings.h" -#include "main.h" -#include "pios_usb.h" /* PIOS_USB_* */ - -#if defined(PIOS_COM_DEBUG) - #define TRANS_DEBUG -#endif - -// ***************************************************************************** -// local variables - -uint32_t trans_previous_com_port = 0; - -volatile uint16_t trans_rx_timer = 0; -volatile uint16_t trans_tx_timer = 0; - -uint8_t trans_temp_buffer1[128]; - -uint8_t trans_temp_buffer2[128]; -uint16_t trans_temp_buffer2_wr; - -// ***************************************************************************** -// can be called from an interrupt if you wish - -void trans_1ms_tick(void) -{ // call this once every 1ms - if (trans_rx_timer < 0xffff) trans_rx_timer++; - if (trans_tx_timer < 0xffff) trans_tx_timer++; -} - -// ***************************************************************************** -// call this as often as possible - not from an interrupt - -void trans_process(void) -{ // copy data from comm-port RX buffer to RF packet handler TX buffer, and from RF packet handler RX buffer to comm-port TX buffer - - // ******************** - // decide which comm-port we are using (usart or usb) - - bool usb_comms = false; // TRUE if we are using the usb port for comms. - uint32_t comm_port = PIOS_COM_SERIAL; // default to using the usart comm-port - - #if defined(PIOS_INCLUDE_USB) - if (PIOS_USB_CheckAvailable(0)) - { // USB comms is up, use the USB comm-port instead of the USART comm-port - usb_comms = true; - comm_port = PIOS_COM_TELEM_USB; - } - #endif - - // ******************** - // check to see if the local communication port has changed (usart/usb) - - if (trans_previous_com_port == 0 && trans_previous_com_port != comm_port) - { // the local communications port has changed .. remove any data in the buffers - trans_temp_buffer2_wr = 0; - } - else - if (usb_comms) - { // we're using the USB for comms - keep the USART rx buffer empty - uint8_t c; - while (PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL, &c, 1, 0) > 0); - } - - trans_previous_com_port = comm_port; // remember the current comm-port we are using - - // ******************** - - uint16_t connection_index = 0; // the RF connection we are using - - // ******************** - // send the data received down the comm-port to the RF packet handler TX buffer - - if (saved_settings.mode == MODE_NORMAL || saved_settings.mode == MODE_STREAM_TX) - { - // free space size in the RF packet handler tx buffer - uint16_t ph_num = ph_putData_free(connection_index); - - // set the USART RTS handshaking line - if (!usb_comms) - { - if (ph_num < 32 || !ph_connected(connection_index)) - SERIAL_RTS_CLEAR; // lower the USART RTS line - we don't have space in the buffer for anymore bytes - else - SERIAL_RTS_SET; // release the USART RTS line - we have space in the buffer for now bytes - } - else - SERIAL_RTS_SET; // release the USART RTS line - - // limit number of bytes we will get to the size of the temp buffer - if (ph_num > sizeof(trans_temp_buffer1)) - ph_num = sizeof(trans_temp_buffer1); - - // copy data received down the comm-port into our temp buffer - register uint16_t bytes_saved = 0; - bytes_saved = PIOS_COM_ReceiveBuffer(comm_port, trans_temp_buffer1, ph_num, 0); - - // put the received comm-port data bytes into the RF packet handler TX buffer - if (bytes_saved > 0) - { - trans_rx_timer = 0; - ph_putData(connection_index, trans_temp_buffer1, bytes_saved); - } - } - else - { // empty the comm-ports rx buffer - uint8_t c; - while (PIOS_COM_ReceiveBuffer(comm_port, &c, 1, 0) > 0); - } - - // ******************** - // send the data received via the RF link out the comm-port - - if (saved_settings.mode == MODE_NORMAL || saved_settings.mode == MODE_STREAM_RX) - { - if (trans_temp_buffer2_wr < sizeof(trans_temp_buffer2)) - { - // get number of data bytes received via the RF link - uint16_t ph_num = ph_getData_used(connection_index); - - // limit to how much space we have in the temp buffer - if (ph_num > sizeof(trans_temp_buffer2) - trans_temp_buffer2_wr) - ph_num = sizeof(trans_temp_buffer2) - trans_temp_buffer2_wr; - - if (ph_num > 0) - { // fetch the data bytes received via the RF link and save into our temp buffer - ph_num = ph_getData(connection_index, trans_temp_buffer2 + trans_temp_buffer2_wr, ph_num); - trans_temp_buffer2_wr += ph_num; - } - } - - #if (defined(PIOS_COM_DEBUG) && (PIOS_COM_DEBUG == PIOS_COM_SERIAL)) - if (!usb_comms) - { // the serial-port is being used for debugging - don't send data down it - trans_temp_buffer2_wr = 0; - trans_tx_timer = 0; - return; - } - #endif - - if (trans_temp_buffer2_wr > 0) - { // we have data in our temp buffer that needs sending out the comm-port - - if (usb_comms || (!usb_comms && GPIO_IN(SERIAL_CTS_PIN))) - { // we are OK to send the data out the comm-port - - // send the data out the comm-port - int32_t res = PIOS_COM_SendBufferNonBlocking(comm_port, trans_temp_buffer2, trans_temp_buffer2_wr); // this one doesn't work properly with USB :( - if (res >= 0) - { // data was sent out the comm-port OK .. remove the sent data from the temp buffer - trans_temp_buffer2_wr = 0; - trans_tx_timer = 0; - } - else - { // failed to send the data out the comm-port - #if defined(TRANS_DEBUG) - DEBUG_PRINTF("PIOS_COM_SendBuffer %d %d\r\n", trans_temp_buffer2_wr, res); - #endif - - if (trans_tx_timer >= 5000) - trans_temp_buffer2_wr = 0; // seems we can't send our data for at least the last 5 seconds - delete it - } - } - } - } - else - { // empty the buffer - trans_temp_buffer2_wr = 0; - trans_tx_timer = 0; - } - - // ******************** -} - -// ***************************************************************************** - -void trans_init(void) -{ - trans_previous_com_port = 0; - - trans_temp_buffer2_wr = 0; - - trans_rx_timer = 0; - trans_tx_timer = 0; -} - -// ***************************************************************************** diff --git a/flight/PipXtreme/watchdog.c b/flight/PipXtreme/watchdog.c deleted file mode 100644 index 044e3d3f3..000000000 --- a/flight/PipXtreme/watchdog.c +++ /dev/null @@ -1,71 +0,0 @@ -/** - ****************************************************************************** - * - * @file watchdog.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Modem packet handling routines - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pios.h" -#include "stm32f10x_iwdg.h" -#include "stm32f10x_dbgmcu.h" - -/** - * @brief Initialize the watchdog timer for a specified timeout - * - * It is important to note that this function returns the achieved timeout - * for this hardware. For hardware indendence this should be checked when - * scheduling updates. Other hardware dependent details may need to be - * considered such as a window time which sets a minimum update time, - * and this function should return a recommended delay for clearing. - * - * For the STM32 nominal clock rate is 32 khz, but for the maximum clock rate of - * 60 khz and a prescalar of 4 yields a clock rate of 15 khz. The delay that is - * set in the watchdog assumes the nominal clock rate, but the delay for FreeRTOS - * to use is 75% of the minimal delay. - * - * @param[in] delayMs The delay period in ms - * @returns Maximum recommended delay between updates - */ -uint16_t watchdog_Init(uint16_t delayMs) -{ - uint16_t delay = ((uint32_t)delayMs * 60) / 16; - if (delay > 0x0fff) - delay = 0x0fff; - - DBGMCU_Config(DBGMCU_IWDG_STOP, ENABLE); // make the watchdog stop counting in debug mode - IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable); - IWDG_SetPrescaler(IWDG_Prescaler_16); - IWDG_SetReload(delay); - IWDG_ReloadCounter(); - IWDG_Enable(); - - return ((((uint32_t)delay * 16) / 60) * .75f); -} - -/** - * @brief Clear the watchdog timer - * - * This function must be called at the appropriate delay to prevent a reset event occuring - */ -void watchdog_Clear(void) -{ - IWDG_ReloadCounter(); -} diff --git a/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch b/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch new file mode 100644 index 000000000..e5981e1e2 --- /dev/null +++ b/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch @@ -0,0 +1,79 @@ +From 07081d82193928ffd0b45df446546f0a41373db7 Mon Sep 17 00:00:00 2001 +From: Stacey Sheldon +Date: Thu, 2 Feb 2012 22:42:03 -0500 +Subject: [PATCH 1/2] armv7m: remove dummy FP regs for new gdb + +--- + src/rtos/rtos_standard_stackings.c | 7 +++++++ + src/target/armv7m.c | 16 ++++++++++++++++ + 2 files changed, 23 insertions(+), 0 deletions(-) + +diff --git a/src/rtos/rtos_standard_stackings.c b/src/rtos/rtos_standard_stackings.c +index 30d9cd9..6ea6565 100644 +--- a/src/rtos/rtos_standard_stackings.c ++++ b/src/rtos/rtos_standard_stackings.c +@@ -41,6 +41,7 @@ static const struct stack_register_offset rtos_standard_Cortex_M3_stack_offsets[ + { -2, 32 }, /* sp */ + { 0x34, 32 }, /* lr */ + { 0x38, 32 }, /* pc */ ++#ifdef USE_DUMMY_FP_REGS + { -1, 96 }, /* FPA1 */ + { -1, 96 }, /* FPA2 */ + { -1, 96 }, /* FPA3 */ +@@ -50,13 +51,19 @@ static const struct stack_register_offset rtos_standard_Cortex_M3_stack_offsets[ + { -1, 96 }, /* FPA7 */ + { -1, 96 }, /* FPA8 */ + { -1, 32 }, /* FPS */ ++#endif + { 0x3c, 32 }, /* xPSR */ + }; + ++ + const struct rtos_register_stacking rtos_standard_Cortex_M3_stacking = { + 0x40, /* stack_registers_size */ + -1, /* stack_growth_direction */ ++#ifdef USE_DUMMY_FP_REGS + 26, /* num_output_registers */ ++#else ++ 17, ++#endif + 8, /* stack_alignment */ + rtos_standard_Cortex_M3_stack_offsets /* register_offsets */ + }; +diff --git a/src/target/armv7m.c b/src/target/armv7m.c +index 258653e..50b26d4 100644 +--- a/src/target/armv7m.c ++++ b/src/target/armv7m.c +@@ -267,6 +267,7 @@ int armv7m_get_gdb_reg_list(struct target *target, struct reg **reg_list[], int + struct armv7m_common *armv7m = target_to_armv7m(target); + int i; + ++#ifdef USE_DUMMY_FP_REGS + *reg_list_size = 26; + *reg_list = malloc(sizeof(struct reg *) * (*reg_list_size)); + +@@ -295,6 +296,21 @@ int armv7m_get_gdb_reg_list(struct target *target, struct reg **reg_list[], int + (*reg_list)[25] = &armv7m->core_cache->reg_list[ARMV7M_xPSR]; + #endif + ++#else ++ *reg_list_size = 17; ++ *reg_list = malloc(sizeof(struct reg*) * (*reg_list_size)); ++ ++ /* ++ * GDB register packet format for ARM: ++ * - the first 16 registers are r0..r15 ++ * - followed by xPSR ++ */ ++ for (i = 0; i < *reg_list_size; i++) ++ { ++ (*reg_list)[i] = &armv7m->core_cache->reg_list[i]; ++ } ++#endif ++ + return ERROR_OK; + } + +-- +1.7.5.4 + diff --git a/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch b/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch new file mode 100644 index 000000000..6140a4bb1 --- /dev/null +++ b/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch @@ -0,0 +1,35 @@ +From 357f02c963478c4994ba5038accadce1576601d5 Mon Sep 17 00:00:00 2001 +From: Stacey Sheldon +Date: Thu, 2 Feb 2012 22:42:26 -0500 +Subject: [PATCH 2/2] rtos: add stm32_stlink to FreeRTOS targets + +--- + src/rtos/FreeRTOS.c | 12 ++++++++++++ + 1 files changed, 12 insertions(+), 0 deletions(-) + +diff --git a/src/rtos/FreeRTOS.c b/src/rtos/FreeRTOS.c +index a646269..8e99c26 100644 +--- a/src/rtos/FreeRTOS.c ++++ b/src/rtos/FreeRTOS.c +@@ -59,6 +59,18 @@ const struct FreeRTOS_params FreeRTOS_params_list[] = { + 0, /* thread_stack_offset; */ + 52, /* thread_name_offset; */ + &rtos_standard_Cortex_M3_stacking, /* stacking_info */ ++ }, ++ { ++ "stm32_stlink", /* target_name */ ++ 4, /* thread_count_width; */ ++ 4, /* pointer_width; */ ++ 16, /* list_next_offset; */ ++ 20, /* list_width; */ ++ 8, /* list_elem_next_offset; */ ++ 12, /* list_elem_content_offset */ ++ 0, /* thread_stack_offset; */ ++ 52, /* thread_name_offset; */ ++ &rtos_standard_Cortex_M3_stacking, /* stacking_info */ + } + }; + +-- +1.7.5.4 + diff --git a/flight/Project/OpenOCD/stlink-v2.cfg b/flight/Project/OpenOCD/stlink-v2.cfg new file mode 100644 index 000000000..c7f671477 --- /dev/null +++ b/flight/Project/OpenOCD/stlink-v2.cfg @@ -0,0 +1,17 @@ +# +# STMicroelectronics ST-LINK/V2 in-circuit debugger/programmer +# + +interface stlink +stlink_layout usb +stlink_device_desc "ST-LINK/V2" +stlink_vid_pid 0x0483 0x3748 +# +# dummy values, not really needed +# +adapter_khz 1 +reset_config trst_and_srst + +gdb_port 3333 +tcl_port 6666 +telnet_port 4444 diff --git a/flight/Project/OpenOCD/stm32f2xx.cfg b/flight/Project/OpenOCD/stm32f2xx.cfg new file mode 100644 index 000000000..3a489dc8d --- /dev/null +++ b/flight/Project/OpenOCD/stm32f2xx.cfg @@ -0,0 +1,61 @@ +# -*- Tcl -*- +# script for stm32 + +if { [info exists CHIPNAME] } { + set _CHIPNAME $CHIPNAME +} else { + set _CHIPNAME stm32 +} + +if { [info exists ENDIAN] } { + set _ENDIAN $ENDIAN +} else { + set _ENDIAN little +} + +# Work-area is a space in RAM used for flash programming +# By default use 16kB +if { [info exists WORKAREASIZE] } { + set _WORKAREASIZE $WORKAREASIZE +} else { + set _WORKAREASIZE 0x4000 +} + +# JTAG speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so use F_JTAG = 1MHz +jtag_khz 1000 +# use this when breaking in while the device is in reset +#jtag_khz 100 + +jtag_nsrst_delay 100 +jtag_ntrst_delay 100 + +#jtag scan chain +if { [info exists CPUTAPID ] } { + set _CPUTAPID $CPUTAPID +} else { + # CortexM3 r2p0 + set _CPUTAPID 0x4ba00477 +} +jtag newtap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID + +if { [info exists BSTAPID ] } { + set _BSTAPID $BSTAPID +} else { + set _BSTAPID 0x06411041 +} +jtag newtap $_CHIPNAME bs -irlen 5 -expected-id $_BSTAPID + +set _TARGETNAME $_CHIPNAME.cpu +target create $_TARGETNAME cortex_m3 -endian $_ENDIAN -chain-position $_TARGETNAME + +$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0 + +# if srst is not fitted use SYSRESETREQ to +# perform a soft reset +# cortex_m3 reset_config sysresetreq + +set _FLASHNAME $_CHIPNAME.flash +flash bank $_FLASHNAME stm32f2xxx 0 0 0 0 $_TARGETNAME + +# For more information about the configuration files, take a look at: +# openocd.texi diff --git a/flight/Project/OpenOCD/stm32f4xx.cfg b/flight/Project/OpenOCD/stm32f4xx.cfg new file mode 100644 index 000000000..28bfcfbbb --- /dev/null +++ b/flight/Project/OpenOCD/stm32f4xx.cfg @@ -0,0 +1,64 @@ +# script for stm32f2xxx + +if { [info exists CHIPNAME] } { + set _CHIPNAME $CHIPNAME +} else { + set _CHIPNAME stm32f4xxx +} + +if { [info exists ENDIAN] } { + set _ENDIAN $ENDIAN +} else { + set _ENDIAN little +} + +# Work-area is a space in RAM used for flash programming +# By default use 64kB +if { [info exists WORKAREASIZE] } { + set _WORKAREASIZE $WORKAREASIZE +} else { + set _WORKAREASIZE 0x10000 +} + +# JTAG speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so use F_JTAG = 1MHz +# +# Since we may be running of an RC oscilator, we crank down the speed a +# bit more to be on the safe side. Perhaps superstition, but if are +# running off a crystal, we can run closer to the limit. Note +# that there can be a pretty wide band where things are more or less stable. +jtag_khz 1000 + +jtag_nsrst_delay 100 +jtag_ntrst_delay 100 + +#jtag scan chain +if { [info exists CPUTAPID ] } { + set _CPUTAPID $CPUTAPID +} else { + # See STM Document RM0033 + # Section 32.6.3 - corresponds to Cortex-M3 r2p0 + set _CPUTAPID 0x4ba00477 +} +jtag newtap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID + +if { [info exists BSTAPID ] } { + set _BSTAPID $BSTAPID +} else { + # See STM Document RM0033 + # Section 32.6.2 + # + set _BSTAPID 0x06413041 +} +jtag newtap $_CHIPNAME bs -irlen 5 -expected-id $_BSTAPID + +set _TARGETNAME $_CHIPNAME.cpu +target create $_TARGETNAME cortex_m3 -endian $_ENDIAN -chain-position $_TARGETNAME -rtos auto + +$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0 + +set _FLASHNAME $_CHIPNAME.flash +flash bank $_FLASHNAME stm32f2x 0 0 0 0 $_TARGETNAME + +# if srst is not fitted use SYSRESETREQ to +# perform a soft reset +cortex_m3 reset_config sysresetreq diff --git a/flight/Project/OpenOCD/stm32f4xx.stlink.cfg b/flight/Project/OpenOCD/stm32f4xx.stlink.cfg new file mode 100644 index 000000000..3d55f6da5 --- /dev/null +++ b/flight/Project/OpenOCD/stm32f4xx.stlink.cfg @@ -0,0 +1,34 @@ +# +# +# +if { [info exists CHIPNAME] } { + set _CHIPNAME $CHIPNAME +} else { + set _CHIPNAME stm32f4x +} + +# Work-area is a space in RAM used for flash programming +# By default use 64kB +if { [info exists WORKAREASIZE] } { + set _WORKAREASIZE $WORKAREASIZE +} else { + set _WORKAREASIZE 0x10000 +} + +if { [info exists CPUTAPID] } { + set _CPUTAPID $CPUTAPID +} else { + set _CPUTAPID 0x2ba01477 +} + +transport select stlink_swd + +stlink newtap $_CHIPNAME cpu -expected-id $_CPUTAPID + +set _TARGETNAME $_CHIPNAME.cpu +target create $_TARGETNAME stm32_stlink -chain-position $_TARGETNAME -rtos auto + +$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0 + +set _FLASHNAME $_CHIPNAME.flash +flash bank $_FLASHNAME stm32f2x 0x08000000 0 0 0 $_TARGETNAME diff --git a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj index ed4340a11..ca4f7532f 100644 --- a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj +++ b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj @@ -7,8481 +7,178 @@ objects = { /* Begin PBXFileReference section */ - 65003B31121249CA00C183DD /* pios_wdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_wdg.c; sourceTree = ""; }; - 6502584212CA4D2600583CDF /* insgps13state.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = insgps13state.c; path = ../../AHRS/insgps13state.c; sourceTree = SOURCE_ROOT; }; - 65078B09136FCEE600536549 /* flightstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightstatus.xml; sourceTree = ""; }; - 6509C7E912CA57DC002E5DC2 /* insgps16state.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = insgps16state.c; path = ../../AHRS/insgps16state.c; sourceTree = SOURCE_ROOT; }; - 650D8E2112DFE16400D05CC9 /* actuator.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = actuator.c; sourceTree = ""; }; - 650D8E2312DFE16400D05CC9 /* actuator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = actuator.h; sourceTree = ""; }; - 650D8E2512DFE16400D05CC9 /* ahrs_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_comms.c; sourceTree = ""; }; - 650D8E2712DFE16400D05CC9 /* ahrs_comms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_comms.h; sourceTree = ""; }; - 650D8E2912DFE16400D05CC9 /* altitude.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = altitude.c; sourceTree = ""; }; - 650D8E2B12DFE16400D05CC9 /* altitude.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = altitude.h; sourceTree = ""; }; - 650D8E2F12DFE16400D05CC9 /* battery.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = battery.c; sourceTree = ""; }; - 650D8E3112DFE16400D05CC9 /* battery.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = battery.h; sourceTree = ""; }; - 650D8E3312DFE16400D05CC9 /* example.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = example.c; sourceTree = ""; }; - 650D8E3412DFE16400D05CC9 /* examplemodevent.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = examplemodevent.c; sourceTree = ""; }; - 650D8E3512DFE16400D05CC9 /* examplemodperiodic.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = examplemodperiodic.c; sourceTree = ""; }; - 650D8E3612DFE16400D05CC9 /* examplemodthread.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = examplemodthread.c; sourceTree = ""; }; - 650D8E3812DFE16400D05CC9 /* examplemodevent.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = examplemodevent.h; sourceTree = ""; }; - 650D8E3912DFE16400D05CC9 /* examplemodperiodic.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = examplemodperiodic.h; sourceTree = ""; }; - 650D8E3A12DFE16400D05CC9 /* examplemodthread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = examplemodthread.h; sourceTree = ""; }; - 650D8E3C12DFE16400D05CC9 /* firmwareiap.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = firmwareiap.c; sourceTree = ""; }; - 650D8E3E12DFE16400D05CC9 /* firmwareiap.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = firmwareiap.h; sourceTree = ""; }; - 650D8E4012DFE16400D05CC9 /* flightplan.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = flightplan.c; sourceTree = ""; }; - 650D8E4212DFE16400D05CC9 /* test.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = test.py; sourceTree = ""; }; - 650D8E4412DFE16400D05CC9 /* flightplan.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = flightplan.h; sourceTree = ""; }; - 650D8E4612DFE16400D05CC9 /* uavobjects.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = uavobjects.py; sourceTree = ""; }; - 650D8E4812DFE16400D05CC9 /* GPS.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = GPS.c; sourceTree = ""; }; - 650D8E4A12DFE16400D05CC9 /* GPS.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = GPS.h; sourceTree = ""; }; - 650D8E4B12DFE16400D05CC9 /* NMEA.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = NMEA.h; sourceTree = ""; }; - 650D8E4C12DFE16400D05CC9 /* NMEA.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = NMEA.c; sourceTree = ""; }; - 650D8E4E12DFE16400D05CC9 /* guidance.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = guidance.c; sourceTree = ""; }; - 650D8E5012DFE16400D05CC9 /* guidance.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = guidance.h; sourceTree = ""; }; - 650D8E5312DFE16400D05CC9 /* manualcontrol.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = manualcontrol.h; sourceTree = ""; }; - 650D8E5412DFE16400D05CC9 /* manualcontrol.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = manualcontrol.c; sourceTree = ""; }; - 650D8E5812DFE16400D05CC9 /* MkSerial.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = MkSerial.h; sourceTree = ""; }; - 650D8E5912DFE16400D05CC9 /* MKSerial.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = MKSerial.c; sourceTree = ""; }; - 650D8E5C12DFE16400D05CC9 /* OsdEtStd.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = OsdEtStd.c; sourceTree = ""; }; - 650D8E5F12DFE16400D05CC9 /* stabilization.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stabilization.h; sourceTree = ""; }; - 650D8E6012DFE16400D05CC9 /* stabilization.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stabilization.c; sourceTree = ""; }; - 650D8E6312DFE16400D05CC9 /* systemmod.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = systemmod.h; sourceTree = ""; }; - 650D8E6412DFE16400D05CC9 /* systemmod.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = systemmod.c; sourceTree = ""; }; - 650D8E6712DFE16400D05CC9 /* telemetry.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = telemetry.h; sourceTree = ""; }; - 650D8E6812DFE16400D05CC9 /* telemetry.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = telemetry.c; sourceTree = ""; }; - 650D8ED112DFE17500D05CC9 /* uavtalk.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavtalk.h; sourceTree = ""; }; - 650D8ED212DFE17500D05CC9 /* uavtalk.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavtalk.c; sourceTree = ""; }; - 6512D60512ED4CA2008175E5 /* pios_flash_w25x.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_flash_w25x.h; sourceTree = ""; }; - 6512D60712ED4CB8008175E5 /* pios_flash_w25x.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_flash_w25x.c; sourceTree = ""; }; + 4354B66314FED9FE004BA3B4 /* flight */ = {isa = PBXFileReference; lastKnownFileType = folder; name = flight; path = ../..; sourceTree = SOURCE_ROOT; }; 65173C9F12EBFD1700D6A7CB /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; name = Makefile; path = ../../../Makefile; sourceTree = SOURCE_ROOT; }; - 651913371256C5240039C0A3 /* ahrs_comm_objects.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_comm_objects.c; sourceTree = ""; }; - 651913381256C5240039C0A3 /* ahrs_spi_comm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_comm.c; sourceTree = ""; }; - 6519133A1256C52B0039C0A3 /* ahrs_comm_objects.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_comm_objects.h; sourceTree = ""; }; - 6519133B1256C52B0039C0A3 /* ahrs_spi_comm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_comm.h; sourceTree = ""; }; - 651CF9E5120B5D8300EEFD70 /* pios_usb_hid_desc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb_hid_desc.c; sourceTree = ""; }; - 651CF9E6120B5D8300EEFD70 /* pios_usb_hid_istr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb_hid_istr.c; sourceTree = ""; }; - 651CF9E7120B5D8300EEFD70 /* pios_usb_hid_prop.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb_hid_prop.c; sourceTree = ""; }; - 651CF9E8120B5D8300EEFD70 /* pios_usb_hid_pwr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb_hid_pwr.c; sourceTree = ""; }; - 651CF9EF120B700D00EEFD70 /* pios_usb_hid_desc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_desc.h; sourceTree = ""; }; - 651CF9F0120B700D00EEFD70 /* pios_usb_hid_istr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_istr.h; sourceTree = ""; }; - 651CF9F1120B700D00EEFD70 /* pios_usb_hid_prop.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_prop.h; sourceTree = ""; }; - 651CF9F2120B700D00EEFD70 /* pios_usb_hid_pwr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_pwr.h; sourceTree = ""; }; - 651CF9F3120B700D00EEFD70 /* usb_conf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = usb_conf.h; sourceTree = ""; }; - 65209A1812208B0600453371 /* baroaltitude.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = baroaltitude.xml; sourceTree = ""; }; - 65209A1912208B0600453371 /* gpsposition.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gpsposition.xml; sourceTree = ""; }; - 6526645A122DF972006F9A3C /* pios_i2c_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_i2c_priv.h; sourceTree = ""; }; - 6526645B122DF972006F9A3C /* pios_wdg.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_wdg.h; sourceTree = ""; }; - 6528CCB412E406B800CF5144 /* pios_adxl345.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_adxl345.c; sourceTree = ""; }; - 6528CCE212E40F6700CF5144 /* pios_adxl345.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_adxl345.h; sourceTree = ""; }; - 652C8568132B632A00BFCC70 /* firmwareiapobj.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = firmwareiapobj.xml; sourceTree = ""; }; - 652C856A132B6EA600BFCC70 /* sonaraltitude.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = sonaraltitude.xml; sourceTree = ""; }; - 65322D3B122841F60046CD7C /* gpstime.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gpstime.xml; sourceTree = ""; }; - 65345C871288668B00A5E4E8 /* guidancesettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = guidancesettings.xml; sourceTree = ""; }; - 6536D47B1307962C0042A298 /* stabilizationdesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = stabilizationdesired.xml; sourceTree = ""; }; - 6536D4881307AB950042A298 /* UAVObjects.inc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.pascal; path = UAVObjects.inc; sourceTree = ""; }; - 65408AA812BB1648004DACC5 /* i2cstats.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = i2cstats.xml; sourceTree = ""; }; - 6543304F121980300063F913 /* insgps.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = insgps.h; sourceTree = ""; }; - 654612D812B5E9A900B719D0 /* pios_iap.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_iap.c; sourceTree = ""; }; - 6549E0D21279B3C800C5476F /* fifo_buffer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = fifo_buffer.c; sourceTree = ""; }; - 6549E0D31279B3CF00C5476F /* fifo_buffer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fifo_buffer.h; sourceTree = ""; }; - 655268BC121FBD2900410C6E /* ahrscalibration.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrscalibration.xml; sourceTree = ""; }; - 655B1A8E13B2FC0900B0E48D /* camerastabsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = camerastabsettings.xml; sourceTree = ""; }; - 656268C612DC1923007B0A0F /* nedaccel.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = nedaccel.xml; sourceTree = ""; }; - 6562BE1713CCAD0600C823E8 /* pios_rcvr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rcvr.c; sourceTree = ""; }; - 65632DF51251650300469B77 /* pios_board.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_board.h; sourceTree = ""; }; - 65632DF61251650300469B77 /* STM32103CB_AHRS.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM32103CB_AHRS.h; sourceTree = ""; }; - 65632DF71251650300469B77 /* STM3210E_OP.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM3210E_OP.h; sourceTree = ""; }; - 65643CAB1413322000A32F59 /* pios_rcvr_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rcvr_priv.h; sourceTree = ""; }; - 65643CAC1413322000A32F59 /* pios_rcvr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rcvr.h; sourceTree = ""; }; - 65643CAD1413322000A32F59 /* pios_rtc_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rtc_priv.h; sourceTree = ""; }; - 65643CAE1413322000A32F59 /* pios_sbus_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_sbus_priv.h; sourceTree = ""; }; - 65643CAF1413322000A32F59 /* pios_sbus.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_sbus.h; sourceTree = ""; }; - 65643CB01413322000A32F59 /* pios_dsm_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_dsm_priv.h; sourceTree = ""; }; - 65643CB91413456D00A32F59 /* pios_tim.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_tim.c; sourceTree = ""; }; - 65643CBA141350C200A32F59 /* pios_sbus.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_sbus.c; sourceTree = ""; }; - 6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_memory.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_memory.ld; sourceTree = SOURCE_ROOT; }; - 6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_sections.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld; sourceTree = SOURCE_ROOT; }; - 657CEEAD121DB6C8007A1FBE /* homelocation.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = homelocation.xml; sourceTree = ""; }; - 657CEEB7121DBC63007A1FBE /* CoordinateConversions.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = CoordinateConversions.c; sourceTree = ""; }; - 657CEEB9121DBC63007A1FBE /* CoordinateConversions.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = CoordinateConversions.h; sourceTree = ""; }; - 657CEEBA121DBC63007A1FBE /* WorldMagModel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = WorldMagModel.h; sourceTree = ""; }; - 657CEEBB121DBC63007A1FBE /* WorldMagModel.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = WorldMagModel.c; sourceTree = ""; }; - 657CF024121F49CD007A1FBE /* WMMInternal.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = WMMInternal.h; sourceTree = ""; }; - 657FF86A12EA8BFB00801617 /* pios_pwm_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_pwm_priv.h; sourceTree = ""; }; - 6589A972131DDE93006BD67C /* FreeRTOSConfig.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = FreeRTOSConfig.h; sourceTree = ""; }; - 6589A983131DE24F006BD67C /* taskmonitor.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = taskmonitor.c; sourceTree = ""; }; - 6589A9DB131DEE76006BD67C /* pios_rtc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rtc.c; sourceTree = ""; }; - 6589A9E2131DF1C7006BD67C /* pios_rtc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rtc.h; sourceTree = ""; }; - 659ED317122226B60011010E /* ahrssettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrssettings.xml; sourceTree = ""; }; - 65B35D7F121C261E003EAD18 /* bin.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = bin.pro; sourceTree = ""; }; - 65B35D80121C261E003EAD18 /* openpilotgcs */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.sh; path = openpilotgcs; sourceTree = ""; }; - 65B35D81121C261E003EAD18 /* openpilotgcs.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = openpilotgcs.pri; sourceTree = ""; }; - 65B35D82121C261E003EAD18 /* openpilotgcs.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = openpilotgcs.pro; sourceTree = ""; }; - 65B35D83121C261E003EAD18 /* openpilotgcs.pro.user */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = openpilotgcs.pro.user; sourceTree = ""; }; - 65B35D88121C261E003EAD18 /* system-health.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = "system-health.svg"; sourceTree = ""; }; - 65B35D8B121C261E003EAD18 /* altimeter.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = altimeter.svg; sourceTree = ""; }; - 65B35D8C121C261E003EAD18 /* attitude.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitude.svg; sourceTree = ""; }; - 65B35D8D121C261E003EAD18 /* compass.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = compass.svg; sourceTree = ""; }; - 65B35D8E121C261E003EAD18 /* flightmode-status.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = "flightmode-status.svg"; sourceTree = ""; }; - 65B35D8F121C261E003EAD18 /* gps-signal.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = "gps-signal.svg"; sourceTree = ""; }; - 65B35D90121C261E003EAD18 /* gps-status.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = "gps-status.svg"; sourceTree = ""; }; - 65B35D91121C261E003EAD18 /* lineardial-horizontal.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = "lineardial-horizontal.svg"; sourceTree = ""; }; - 65B35D92121C261E003EAD18 /* lineardial-vertical.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = "lineardial-vertical.svg"; sourceTree = ""; }; - 65B35D93121C261E003EAD18 /* Readme.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = Readme.txt; sourceTree = ""; }; - 65B35D94121C261E003EAD18 /* speed.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = speed.svg; sourceTree = ""; }; - 65B35D95121C261E003EAD18 /* textonly.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = textonly.svg; sourceTree = ""; }; - 65B35D96121C261E003EAD18 /* thermometer.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = thermometer.svg; sourceTree = ""; }; - 65B35D97121C261E003EAD18 /* vsi.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = vsi.svg; sourceTree = ""; }; - 65B35D99121C261E003EAD18 /* altimeter.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = altimeter.svg; sourceTree = ""; }; - 65B35D9A121C261E003EAD18 /* speed.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = speed.svg; sourceTree = ""; }; - 65B35D9B121C261E003EAD18 /* vsi.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = vsi.svg; sourceTree = ""; }; - 65B35D9D121C261E003EAD18 /* easystar.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = easystar.png; sourceTree = ""; }; - 65B35D9E121C261E003EAD18 /* quad.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = quad.png; sourceTree = ""; }; - 65B35DA1121C261E003EAD18 /* EasyS.jpg */ = {isa = PBXFileReference; lastKnownFileType = image.jpeg; path = EasyS.jpg; sourceTree = ""; }; - 65B35DA2121C261E003EAD18 /* EasyStar.3ds */ = {isa = PBXFileReference; lastKnownFileType = file; path = EasyStar.3ds; sourceTree = ""; }; - 65B35DA3121C261E003EAD18 /* V1White.jpg */ = {isa = PBXFileReference; lastKnownFileType = image.jpeg; path = V1White.jpg; sourceTree = ""; }; - 65B35DA4121C261E003EAD18 /* V2White.jpg */ = {isa = PBXFileReference; lastKnownFileType = image.jpeg; path = V2White.jpg; sourceTree = ""; }; - 65B35DA5121C261E003EAD18 /* White.jpg */ = {isa = PBXFileReference; lastKnownFileType = image.jpeg; path = White.jpg; sourceTree = ""; }; - 65B35DA6121C261E003EAD18 /* wing.jpg */ = {isa = PBXFileReference; lastKnownFileType = image.jpeg; path = wing.jpg; sourceTree = ""; }; - 65B35DA9121C261E003EAD18 /* pfd.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = pfd.svg; sourceTree = ""; }; - 65B35DAB121C261E003EAD18 /* Complete sound set.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "Complete sound set.txt"; sourceTree = ""; }; - 65B35DAD121C261E003EAD18 /* 0.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 0.wav; sourceTree = ""; }; - 65B35DAE121C261E003EAD18 /* 1.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 1.wav; sourceTree = ""; }; - 65B35DAF121C261E003EAD18 /* 10.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 10.wav; sourceTree = ""; }; - 65B35DB0121C261E003EAD18 /* 100.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 100.wav; sourceTree = ""; }; - 65B35DB1121C261E003EAD18 /* 1000.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 1000.wav; sourceTree = ""; }; - 65B35DB2121C261E003EAD18 /* 11.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 11.wav; sourceTree = ""; }; - 65B35DB3121C261E003EAD18 /* 12.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 12.wav; sourceTree = ""; }; - 65B35DB4121C261E003EAD18 /* 13.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 13.wav; sourceTree = ""; }; - 65B35DB5121C261E003EAD18 /* 14.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 14.wav; sourceTree = ""; }; - 65B35DB6121C261E003EAD18 /* 15.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 15.wav; sourceTree = ""; }; - 65B35DB7121C261E003EAD18 /* 16.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 16.wav; sourceTree = ""; }; - 65B35DB8121C261E003EAD18 /* 17.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 17.wav; sourceTree = ""; }; - 65B35DB9121C261E003EAD18 /* 18.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 18.wav; sourceTree = ""; }; - 65B35DBA121C261E003EAD18 /* 19.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 19.wav; sourceTree = ""; }; - 65B35DBB121C261E003EAD18 /* 2.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 2.wav; sourceTree = ""; }; - 65B35DBC121C261E003EAD18 /* 20.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 20.wav; sourceTree = ""; }; - 65B35DBD121C261E003EAD18 /* 3.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 3.wav; sourceTree = ""; }; - 65B35DBE121C261E003EAD18 /* 30.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 30.wav; sourceTree = ""; }; - 65B35DBF121C261E003EAD18 /* 4.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 4.wav; sourceTree = ""; }; - 65B35DC0121C261E003EAD18 /* 40.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 40.wav; sourceTree = ""; }; - 65B35DC1121C261E003EAD18 /* 5.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 5.wav; sourceTree = ""; }; - 65B35DC2121C261E003EAD18 /* 50.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 50.wav; sourceTree = ""; }; - 65B35DC3121C261E003EAD18 /* 6.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 6.wav; sourceTree = ""; }; - 65B35DC4121C261E003EAD18 /* 60.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 60.wav; sourceTree = ""; }; - 65B35DC5121C261E003EAD18 /* 7.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 7.wav; sourceTree = ""; }; - 65B35DC6121C261E003EAD18 /* 70.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 70.wav; sourceTree = ""; }; - 65B35DC7121C261E003EAD18 /* 8.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 8.wav; sourceTree = ""; }; - 65B35DC8121C261E003EAD18 /* 80.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 80.wav; sourceTree = ""; }; - 65B35DC9121C261E003EAD18 /* 9.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 9.wav; sourceTree = ""; }; - 65B35DCA121C261E003EAD18 /* 90.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = 90.wav; sourceTree = ""; }; - 65B35DCB121C261E003EAD18 /* aborted.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = aborted.wav; sourceTree = ""; }; - 65B35DCC121C261E003EAD18 /* active.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = active.wav; sourceTree = ""; }; - 65B35DCD121C261E003EAD18 /* alarmsound.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = alarmsound.wav; sourceTree = ""; }; - 65B35DCE121C261E003EAD18 /* alert.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = alert.wav; sourceTree = ""; }; - 65B35DCF121C261E003EAD18 /* altitude.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = altitude.wav; sourceTree = ""; }; - 65B35DD0121C261E003EAD18 /* amps.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = amps.wav; sourceTree = ""; }; - 65B35DD1121C261E003EAD18 /* aquired.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = aquired.wav; sourceTree = ""; }; - 65B35DD2121C261E003EAD18 /* auto flight.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "auto flight.wav"; sourceTree = ""; }; - 65B35DD3121C261E003EAD18 /* battery.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = battery.wav; sourceTree = ""; }; - 65B35DD4121C261E003EAD18 /* beepsound.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = beepsound.wav; sourceTree = ""; }; - 65B35DD5121C261E003EAD18 /* camera.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = camera.wav; sourceTree = ""; }; - 65B35DD6121C261E003EAD18 /* cancelled.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = cancelled.wav; sourceTree = ""; }; - 65B35DD7121C261E003EAD18 /* changed.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = changed.wav; sourceTree = ""; }; - 65B35DD8121C261E003EAD18 /* circle position.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "circle position.wav"; sourceTree = ""; }; - 65B35DD9121C261E003EAD18 /* cleared.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = cleared.wav; sourceTree = ""; }; - 65B35DDA121C261E003EAD18 /* complete.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = complete.wav; sourceTree = ""; }; - 65B35DDB121C261E003EAD18 /* connected.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = connected.wav; sourceTree = ""; }; - 65B35DDC121C261E003EAD18 /* connection.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = connection.wav; sourceTree = ""; }; - 65B35DDD121C261E003EAD18 /* control.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = control.wav; sourceTree = ""; }; - 65B35DDE121C261E003EAD18 /* disabled.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = disabled.wav; sourceTree = ""; }; - 65B35DDF121C261E003EAD18 /* disconnected.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = disconnected.wav; sourceTree = ""; }; - 65B35DE0121C261E003EAD18 /* feet.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = feet.wav; sourceTree = ""; }; - 65B35DE1121C261E003EAD18 /* figure eight.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "figure eight.wav"; sourceTree = ""; }; - 65B35DE2121C261E003EAD18 /* flight.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = flight.wav; sourceTree = ""; }; - 65B35DE3121C261E003EAD18 /* geofence.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = geofence.wav; sourceTree = ""; }; - 65B35DE4121C261E003EAD18 /* gps.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = gps.wav; sourceTree = ""; }; - 65B35DE5121C261E003EAD18 /* ground station.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "ground station.wav"; sourceTree = ""; }; - 65B35DE6121C261E003EAD18 /* heading.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = heading.wav; sourceTree = ""; }; - 65B35DE7121C261E003EAD18 /* height.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = height.wav; sourceTree = ""; }; - 65B35DE8121C261E003EAD18 /* high.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = high.wav; sourceTree = ""; }; - 65B35DE9121C261E003EAD18 /* hippodrome.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = hippodrome.wav; sourceTree = ""; }; - 65B35DEA121C261E003EAD18 /* hold position.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "hold position.wav"; sourceTree = ""; }; - 65B35DEB121C261E003EAD18 /* home location.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "home location.wav"; sourceTree = ""; }; - 65B35DEC121C261E003EAD18 /* initialised.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = initialised.wav; sourceTree = ""; }; - 65B35DED121C261E003EAD18 /* initiated.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = initiated.wav; sourceTree = ""; }; - 65B35DEE121C261E003EAD18 /* KPH.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = KPH.wav; sourceTree = ""; }; - 65B35DEF121C261E003EAD18 /* landing.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = landing.wav; sourceTree = ""; }; - 65B35DF0121C261E003EAD18 /* launch.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = launch.wav; sourceTree = ""; }; - 65B35DF1121C261E003EAD18 /* left.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = left.wav; sourceTree = ""; }; - 65B35DF2121C261E003EAD18 /* logging.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = logging.wav; sourceTree = ""; }; - 65B35DF3121C261E003EAD18 /* lost.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = lost.wav; sourceTree = ""; }; - 65B35DF4121C261E003EAD18 /* low altitude.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "low altitude.wav"; sourceTree = ""; }; - 65B35DF5121C261E003EAD18 /* low battery.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "low battery.wav"; sourceTree = ""; }; - 65B35DF6121C261E003EAD18 /* low gps quality.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "low gps quality.wav"; sourceTree = ""; }; - 65B35DF7121C261E003EAD18 /* manual flight.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "manual flight.wav"; sourceTree = ""; }; - 65B35DF8121C261E003EAD18 /* maximum.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = maximum.wav; sourceTree = ""; }; - 65B35DF9121C261E003EAD18 /* meters.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = meters.wav; sourceTree = ""; }; - 65B35DFA121C261E003EAD18 /* minimum.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = minimum.wav; sourceTree = ""; }; - 65B35DFB121C261E003EAD18 /* mode.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = mode.wav; sourceTree = ""; }; - 65B35DFC121C261E003EAD18 /* MPH.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = MPH.wav; sourceTree = ""; }; - 65B35DFD121C261E003EAD18 /* navigation.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = navigation.wav; sourceTree = ""; }; - 65B35DFE121C261E003EAD18 /* openpilot.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = openpilot.wav; sourceTree = ""; }; - 65B35DFF121C261E003EAD18 /* point.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = point.wav; sourceTree = ""; }; - 65B35E00121C261E003EAD18 /* range.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = range.wav; sourceTree = ""; }; - 65B35E01121C261E003EAD18 /* reached.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = reached.wav; sourceTree = ""; }; - 65B35E02121C261E003EAD18 /* ready for flight.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "ready for flight.wav"; sourceTree = ""; }; - 65B35E03121C261E003EAD18 /* return home.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = "return home.wav"; sourceTree = ""; }; - 65B35E04121C261E003EAD18 /* right.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = right.wav; sourceTree = ""; }; - 65B35E05121C261E003EAD18 /* set.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = set.wav; sourceTree = ""; }; - 65B35E06121C261E003EAD18 /* speed.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = speed.wav; sourceTree = ""; }; - 65B35E07121C261E003EAD18 /* stabilization.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = stabilization.wav; sourceTree = ""; }; - 65B35E08121C261E003EAD18 /* started.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = started.wav; sourceTree = ""; }; - 65B35E09121C261E003EAD18 /* stopped.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = stopped.wav; sourceTree = ""; }; - 65B35E0A121C261E003EAD18 /* takeoff.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = takeoff.wav; sourceTree = ""; }; - 65B35E0B121C261E003EAD18 /* telemetry.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = telemetry.wav; sourceTree = ""; }; - 65B35E0C121C261E003EAD18 /* time.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = time.wav; sourceTree = ""; }; - 65B35E0D121C261E003EAD18 /* triggered.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = triggered.wav; sourceTree = ""; }; - 65B35E0E121C261E003EAD18 /* uav.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = uav.wav; sourceTree = ""; }; - 65B35E0F121C261E003EAD18 /* volts.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = volts.wav; sourceTree = ""; }; - 65B35E10121C261E003EAD18 /* warning.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = warning.wav; sourceTree = ""; }; - 65B35E11121C261E003EAD18 /* waypoint.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = waypoint.wav; sourceTree = ""; }; - 65B35E12121C261E003EAD18 /* whoopsound.wav */ = {isa = PBXFileReference; lastKnownFileType = audio.wav; path = whoopsound.wav; sourceTree = ""; }; - 65B35E13121C261E003EAD18 /* License.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = License.txt; sourceTree = ""; }; - 65B35E15121C261E003EAD18 /* extract-mimetypes.xq */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "extract-mimetypes.xq"; sourceTree = ""; }; - 65B35E16121C261E003EAD18 /* extract-mimetypes.xq.in */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "extract-mimetypes.xq.in"; sourceTree = ""; }; - 65B35E17121C261E003EAD18 /* openpilotgcs_de.ts */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = openpilotgcs_de.ts; sourceTree = ""; }; - 65B35E18121C261E003EAD18 /* openpilotgcs_es.ts */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = openpilotgcs_es.ts; sourceTree = ""; }; - 65B35E19121C261E003EAD18 /* openpilotgcs_fr.ts */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = openpilotgcs_fr.ts; sourceTree = ""; }; - 65B35E1A121C261E003EAD18 /* openpilotgcs_it.ts */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = openpilotgcs_it.ts; sourceTree = ""; }; - 65B35E1B121C261E003EAD18 /* Readme.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = Readme.txt; sourceTree = ""; }; - 65B35E1C121C261E003EAD18 /* translations.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = translations.pro; sourceTree = ""; }; - 65B35E1D121C261E003EAD18 /* share.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = share.pro; sourceTree = ""; }; - 65B35E20121C261E003EAD18 /* app.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = app.pro; sourceTree = ""; }; - 65B35E21121C261E003EAD18 /* Info.plist */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.plist.xml; path = Info.plist; sourceTree = ""; }; - 65B35E22121C261E003EAD18 /* main.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cpp; sourceTree = ""; }; - 65B35E23121C261E003EAD18 /* openpilotgcs.icns */ = {isa = PBXFileReference; lastKnownFileType = image.icns; path = openpilotgcs.icns; sourceTree = ""; }; - 65B35E24121C261E003EAD18 /* openpilotgcs.ico */ = {isa = PBXFileReference; lastKnownFileType = image.ico; path = openpilotgcs.ico; sourceTree = ""; }; - 65B35E25121C261E003EAD18 /* openpilotgcs.rc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = openpilotgcs.rc; sourceTree = ""; }; - 65B35E26121C261E003EAD18 /* prifile.icns */ = {isa = PBXFileReference; lastKnownFileType = image.icns; path = prifile.icns; sourceTree = ""; }; - 65B35E27121C261E003EAD18 /* profile.icns */ = {isa = PBXFileReference; lastKnownFileType = image.icns; path = profile.icns; sourceTree = ""; }; - 65B35E2A121C261E003EAD18 /* HIDTest.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = HIDTest.pro; sourceTree = ""; }; - 65B35E2B121C261E003EAD18 /* main.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cpp; sourceTree = ""; }; - 65B35E2D121C261E003EAD18 /* common.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = common.pri; sourceTree = ""; }; - 65B35E2F121C261E003EAD18 /* accessmode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = accessmode.h; sourceTree = ""; }; - 65B35E30121C261E003EAD18 /* alllayersoftype.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = alllayersoftype.cpp; sourceTree = ""; }; - 65B35E31121C261E003EAD18 /* alllayersoftype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = alllayersoftype.h; sourceTree = ""; }; - 65B35E32121C261E003EAD18 /* cache.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = cache.cpp; sourceTree = ""; }; - 65B35E33121C261E003EAD18 /* cache.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = cache.h; sourceTree = ""; }; - 65B35E34121C261E003EAD18 /* cacheitemqueue.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = cacheitemqueue.cpp; sourceTree = ""; }; - 65B35E35121C261E003EAD18 /* cacheitemqueue.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = cacheitemqueue.h; sourceTree = ""; }; - 65B35E36121C261E003EAD18 /* core.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = core.pro; sourceTree = ""; }; - 65B35E37121C261E003EAD18 /* debugheader.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = debugheader.h; sourceTree = ""; }; - 65B35E38121C261E003EAD18 /* geodecoderstatus.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = geodecoderstatus.h; sourceTree = ""; }; - 65B35E39121C261E003EAD18 /* kibertilecache.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = kibertilecache.cpp; sourceTree = ""; }; - 65B35E3A121C261E003EAD18 /* kibertilecache.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = kibertilecache.h; sourceTree = ""; }; - 65B35E3B121C261E003EAD18 /* languagetype.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = languagetype.cpp; sourceTree = ""; }; - 65B35E3C121C261E003EAD18 /* languagetype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = languagetype.h; sourceTree = ""; }; - 65B35E3D121C261E003EAD18 /* maptype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = maptype.h; sourceTree = ""; }; - 65B35E3E121C261E003EAD18 /* memorycache.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = memorycache.cpp; sourceTree = ""; }; - 65B35E3F121C261E003EAD18 /* memorycache.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = memorycache.h; sourceTree = ""; }; - 65B35E40121C261E003EAD18 /* opmaps.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmaps.cpp; sourceTree = ""; }; - 65B35E41121C261E003EAD18 /* opmaps.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmaps.h; sourceTree = ""; }; - 65B35E42121C261E003EAD18 /* placemark.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = placemark.cpp; sourceTree = ""; }; - 65B35E43121C261E003EAD18 /* placemark.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = placemark.h; sourceTree = ""; }; - 65B35E44121C261E003EAD18 /* point.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = point.cpp; sourceTree = ""; }; - 65B35E45121C261E003EAD18 /* point.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = point.h; sourceTree = ""; }; - 65B35E46121C261E003EAD18 /* providerstrings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = providerstrings.cpp; sourceTree = ""; }; - 65B35E47121C261E003EAD18 /* providerstrings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = providerstrings.h; sourceTree = ""; }; - 65B35E48121C261E003EAD18 /* pureimage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pureimage.cpp; sourceTree = ""; }; - 65B35E49121C261E003EAD18 /* pureimage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pureimage.h; sourceTree = ""; }; - 65B35E4A121C261E003EAD18 /* pureimagecache.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pureimagecache.cpp; sourceTree = ""; }; - 65B35E4B121C261E003EAD18 /* pureimagecache.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pureimagecache.h; sourceTree = ""; }; - 65B35E4C121C261E003EAD18 /* rawtile.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = rawtile.cpp; sourceTree = ""; }; - 65B35E4D121C261E003EAD18 /* rawtile.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rawtile.h; sourceTree = ""; }; - 65B35E4E121C261E003EAD18 /* size.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = size.cpp; sourceTree = ""; }; - 65B35E4F121C261E003EAD18 /* size.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = size.h; sourceTree = ""; }; - 65B35E50121C261E003EAD18 /* tilecachequeue.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = tilecachequeue.cpp; sourceTree = ""; }; - 65B35E51121C261E003EAD18 /* tilecachequeue.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = tilecachequeue.h; sourceTree = ""; }; - 65B35E52121C261E003EAD18 /* urlfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = urlfactory.cpp; sourceTree = ""; }; - 65B35E53121C261E003EAD18 /* urlfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = urlfactory.h; sourceTree = ""; }; - 65B35E55121C261E003EAD18 /* finaltest.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = finaltest.pro; sourceTree = ""; }; - 65B35E56121C261E003EAD18 /* main.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cpp; sourceTree = ""; }; - 65B35E57121C261E003EAD18 /* mainwindow.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mainwindow.cpp; sourceTree = ""; }; - 65B35E58121C261E003EAD18 /* mainwindow.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mainwindow.h; sourceTree = ""; }; - 65B35E59121C261E003EAD18 /* mainwindow.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mainwindow.ui; sourceTree = ""; }; - 65B35E5A121C261E003EAD18 /* ui_mainwindow.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ui_mainwindow.h; sourceTree = ""; }; - 65B35E5C121C261E003EAD18 /* gettilestest.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = gettilestest.pro; sourceTree = ""; }; - 65B35E5D121C261E003EAD18 /* main.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cpp; sourceTree = ""; }; - 65B35E5F121C261E003EAD18 /* copyrightstrings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = copyrightstrings.h; sourceTree = ""; }; - 65B35E60121C261E003EAD18 /* core.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = core.cpp; sourceTree = ""; }; - 65B35E61121C261E003EAD18 /* core.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = core.h; sourceTree = ""; }; - 65B35E62121C261E003EAD18 /* debugheader.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = debugheader.h; sourceTree = ""; }; - 65B35E63121C261E003EAD18 /* internals.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = internals.pro; sourceTree = ""; }; - 65B35E64121C261E003EAD18 /* loadtask.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = loadtask.cpp; sourceTree = ""; }; - 65B35E65121C261E003EAD18 /* loadtask.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = loadtask.h; sourceTree = ""; }; - 65B35E66121C261E003EAD18 /* MouseWheelZoomType.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = MouseWheelZoomType.cpp; sourceTree = ""; }; - 65B35E67121C261E003EAD18 /* mousewheelzoomtype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mousewheelzoomtype.h; sourceTree = ""; }; - 65B35E68121C261E003EAD18 /* pointlatlng.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pointlatlng.cpp; sourceTree = ""; }; - 65B35E69121C261E003EAD18 /* pointlatlng.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pointlatlng.h; sourceTree = ""; }; - 65B35E6B121C261E003EAD18 /* lks94projection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = lks94projection.cpp; sourceTree = ""; }; - 65B35E6C121C261E003EAD18 /* lks94projection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = lks94projection.h; sourceTree = ""; }; - 65B35E6D121C261E003EAD18 /* mercatorprojection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mercatorprojection.cpp; sourceTree = ""; }; - 65B35E6E121C261E003EAD18 /* mercatorprojection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mercatorprojection.h; sourceTree = ""; }; - 65B35E6F121C261E003EAD18 /* mercatorprojectionyandex.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mercatorprojectionyandex.cpp; sourceTree = ""; }; - 65B35E70121C261E003EAD18 /* mercatorprojectionyandex.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mercatorprojectionyandex.h; sourceTree = ""; }; - 65B35E71121C261E003EAD18 /* platecarreeprojection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = platecarreeprojection.cpp; sourceTree = ""; }; - 65B35E72121C261E003EAD18 /* platecarreeprojection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = platecarreeprojection.h; sourceTree = ""; }; - 65B35E73121C261E003EAD18 /* platecarreeprojectionpergo.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = platecarreeprojectionpergo.cpp; sourceTree = ""; }; - 65B35E74121C261E003EAD18 /* platecarreeprojectionpergo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = platecarreeprojectionpergo.h; sourceTree = ""; }; - 65B35E75121C261E003EAD18 /* pureprojection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pureprojection.cpp; sourceTree = ""; }; - 65B35E76121C261E003EAD18 /* pureprojection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pureprojection.h; sourceTree = ""; }; - 65B35E77121C261E003EAD18 /* rectangle.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = rectangle.cpp; sourceTree = ""; }; - 65B35E78121C261E003EAD18 /* rectangle.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rectangle.h; sourceTree = ""; }; - 65B35E79121C261E003EAD18 /* rectlatlng.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = rectlatlng.cpp; sourceTree = ""; }; - 65B35E7A121C261E003EAD18 /* rectlatlng.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rectlatlng.h; sourceTree = ""; }; - 65B35E7B121C261E003EAD18 /* sizelatlng.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = sizelatlng.cpp; sourceTree = ""; }; - 65B35E7C121C261E003EAD18 /* sizelatlng.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = sizelatlng.h; sourceTree = ""; }; - 65B35E7D121C261E003EAD18 /* tile.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = tile.cpp; sourceTree = ""; }; - 65B35E7E121C261E003EAD18 /* tile.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = tile.h; sourceTree = ""; }; - 65B35E7F121C261E003EAD18 /* tilematrix.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = tilematrix.cpp; sourceTree = ""; }; - 65B35E80121C261E003EAD18 /* tilematrix.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = tilematrix.h; sourceTree = ""; }; - 65B35E82121C261E003EAD18 /* mapgraphicitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mapgraphicitem.cpp; sourceTree = ""; }; - 65B35E83121C261E003EAD18 /* mapgraphicitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mapgraphicitem.h; sourceTree = ""; }; - 65B35E84121C261E003EAD18 /* mapresources.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = mapresources.qrc; sourceTree = ""; }; - 65B35E85121C261E003EAD18 /* mapwidget.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = mapwidget.pro; sourceTree = ""; }; - 65B35E86121C261E003EAD18 /* opmapcontrol.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmapcontrol.cpp; sourceTree = ""; }; - 65B35E87121C261E003EAD18 /* opmapcontrol.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmapcontrol.h; sourceTree = ""; }; - 65B35E88121C261E003EAD18 /* opmapwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmapwidget.cpp; sourceTree = ""; }; - 65B35E89121C261E003EAD18 /* opmapwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmapwidget.h; sourceTree = ""; }; - 65B35E8A121C261E003EAD18 /* OPMapControl.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = OPMapControl.pro; sourceTree = ""; }; - 65B35E8C121C261E003EAD18 /* main.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cpp; sourceTree = ""; }; - 65B35E8D121C261E003EAD18 /* teste.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = teste.pro; sourceTree = ""; }; - 65B35E8F121C261E003EAD18 /* main.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cpp; sourceTree = ""; }; - 65B35E90121C261E003EAD18 /* map.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = map.cpp; sourceTree = ""; }; - 65B35E91121C261E003EAD18 /* map.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = map.h; sourceTree = ""; }; - 65B35E92121C261E003EAD18 /* widgettest.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = widgettest.pro; sourceTree = ""; }; - 65B35E95121C261E003EAD18 /* DocumentationHelper.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = DocumentationHelper.pro; sourceTree = ""; }; - 65B35E96121C261E003EAD18 /* main.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cpp; sourceTree = ""; }; - 65B35E97121C261E003EAD18 /* mainwindow.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mainwindow.cpp; sourceTree = ""; }; - 65B35E98121C261E003EAD18 /* mainwindow.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mainwindow.h; sourceTree = ""; }; - 65B35E99121C261E003EAD18 /* mainwindow.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mainwindow.ui; sourceTree = ""; }; - 65B35E9C121C261E003EAD18 /* aggregate.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = aggregate.cpp; sourceTree = ""; }; - 65B35E9D121C261E003EAD18 /* aggregate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = aggregate.h; sourceTree = ""; }; - 65B35E9E121C261E003EAD18 /* aggregation.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = aggregation.pri; sourceTree = ""; }; - 65B35E9F121C261E003EAD18 /* aggregation.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = aggregation.pro; sourceTree = ""; }; - 65B35EA0121C261E003EAD18 /* aggregation_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = aggregation_global.h; sourceTree = ""; }; - 65B35EA2121C261E003EAD18 /* examples.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = examples.pro; sourceTree = ""; }; - 65B35EA4121C261E003EAD18 /* main.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cpp; sourceTree = ""; }; - 65B35EA5121C261E003EAD18 /* main.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = main.h; sourceTree = ""; }; - 65B35EA6121C261E003EAD18 /* main.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = main.ui; sourceTree = ""; }; - 65B35EA7121C261E003EAD18 /* myinterfaces.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = myinterfaces.h; sourceTree = ""; }; - 65B35EA8121C261E003EAD18 /* text.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = text.pro; sourceTree = ""; }; - 65B35EAA121C261E003EAD18 /* extensionsystem.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = extensionsystem.pri; sourceTree = ""; }; - 65B35EAB121C261E003EAD18 /* extensionsystem.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = extensionsystem.pro; sourceTree = ""; }; - 65B35EAC121C261E003EAD18 /* extensionsystem_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = extensionsystem_dependencies.pri; sourceTree = ""; }; - 65B35EAD121C261E003EAD18 /* extensionsystem_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = extensionsystem_global.h; sourceTree = ""; }; - 65B35EAF121C261E003EAD18 /* error.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = error.png; sourceTree = ""; }; - 65B35EB0121C261E003EAD18 /* ok.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ok.png; sourceTree = ""; }; - 65B35EB1121C261E003EAD18 /* iplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = iplugin.cpp; sourceTree = ""; }; - 65B35EB2121C261E003EAD18 /* iplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = iplugin.h; sourceTree = ""; }; - 65B35EB3121C261E003EAD18 /* iplugin_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = iplugin_p.h; sourceTree = ""; }; - 65B35EB4121C261E003EAD18 /* optionsparser.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = optionsparser.cpp; sourceTree = ""; }; - 65B35EB5121C261E003EAD18 /* optionsparser.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = optionsparser.h; sourceTree = ""; }; - 65B35EB6121C261E003EAD18 /* plugindetailsview.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugindetailsview.cpp; sourceTree = ""; }; - 65B35EB7121C261E003EAD18 /* plugindetailsview.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugindetailsview.h; sourceTree = ""; }; - 65B35EB8121C261E003EAD18 /* plugindetailsview.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = plugindetailsview.ui; sourceTree = ""; }; - 65B35EB9121C261E003EAD18 /* pluginerrorview.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pluginerrorview.cpp; sourceTree = ""; }; - 65B35EBA121C261E003EAD18 /* pluginerrorview.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pluginerrorview.h; sourceTree = ""; }; - 65B35EBB121C261E003EAD18 /* pluginerrorview.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pluginerrorview.ui; sourceTree = ""; }; - 65B35EBC121C261E003EAD18 /* pluginmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pluginmanager.cpp; sourceTree = ""; }; - 65B35EBD121C261E003EAD18 /* pluginmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pluginmanager.h; sourceTree = ""; }; - 65B35EBE121C261E003EAD18 /* pluginmanager_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pluginmanager_p.h; sourceTree = ""; }; - 65B35EBF121C261E003EAD18 /* pluginspec.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pluginspec.cpp; sourceTree = ""; }; - 65B35EC0121C261E003EAD18 /* pluginspec.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pluginspec.h; sourceTree = ""; }; - 65B35EC1121C261E003EAD18 /* pluginspec_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pluginspec_p.h; sourceTree = ""; }; - 65B35EC2121C261E003EAD18 /* pluginview.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pluginview.cpp; sourceTree = ""; }; - 65B35EC3121C261E003EAD18 /* pluginview.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pluginview.h; sourceTree = ""; }; - 65B35EC4121C261E003EAD18 /* pluginview.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pluginview.qrc; sourceTree = ""; }; - 65B35EC5121C261E003EAD18 /* pluginview.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = pluginview.ui; sourceTree = ""; }; - 65B35EC6121C261E003EAD18 /* pluginview_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pluginview_p.h; sourceTree = ""; }; - 65B35EC9121C261E003EAD18 /* auto.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = auto.pro; sourceTree = ""; }; - 65B35ECC121C261E003EAD18 /* circularplugins.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = circularplugins.pro; sourceTree = ""; }; - 65B35ECE121C261E003EAD18 /* plugin.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = plugin.xml; sourceTree = ""; }; - 65B35ECF121C261E003EAD18 /* plugin1.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugin1.cpp; sourceTree = ""; }; - 65B35ED0121C261E003EAD18 /* plugin1.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugin1.h; sourceTree = ""; }; - 65B35ED1121C261E003EAD18 /* plugin1.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin1.pro; sourceTree = ""; }; - 65B35ED3121C261E003EAD18 /* plugin.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = plugin.xml; sourceTree = ""; }; - 65B35ED4121C261E003EAD18 /* plugin2.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugin2.cpp; sourceTree = ""; }; - 65B35ED5121C261E003EAD18 /* plugin2.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugin2.h; sourceTree = ""; }; - 65B35ED6121C261E003EAD18 /* plugin2.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin2.pro; sourceTree = ""; }; - 65B35ED8121C261E003EAD18 /* plugin.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = plugin.xml; sourceTree = ""; }; - 65B35ED9121C261E003EAD18 /* plugin3.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugin3.cpp; sourceTree = ""; }; - 65B35EDA121C261E003EAD18 /* plugin3.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugin3.h; sourceTree = ""; }; - 65B35EDB121C261E003EAD18 /* plugin3.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin3.pro; sourceTree = ""; }; - 65B35EDD121C261E003EAD18 /* correctplugins1.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = correctplugins1.pro; sourceTree = ""; }; - 65B35EDF121C261E003EAD18 /* plugin.spec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin.spec; sourceTree = ""; }; - 65B35EE0121C261E003EAD18 /* plugin1.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugin1.cpp; sourceTree = ""; }; - 65B35EE1121C261E003EAD18 /* plugin1.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugin1.h; sourceTree = ""; }; - 65B35EE2121C261E003EAD18 /* plugin1.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin1.pro; sourceTree = ""; }; - 65B35EE4121C261E003EAD18 /* plugin.spec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin.spec; sourceTree = ""; }; - 65B35EE5121C261E003EAD18 /* plugin2.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugin2.cpp; sourceTree = ""; }; - 65B35EE6121C261E003EAD18 /* plugin2.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugin2.h; sourceTree = ""; }; - 65B35EE7121C261E003EAD18 /* plugin2.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin2.pro; sourceTree = ""; }; - 65B35EE9121C261E003EAD18 /* plugin.spec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin.spec; sourceTree = ""; }; - 65B35EEA121C261E003EAD18 /* plugin3.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugin3.cpp; sourceTree = ""; }; - 65B35EEB121C261E003EAD18 /* plugin3.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugin3.h; sourceTree = ""; }; - 65B35EEC121C261E003EAD18 /* plugin3.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin3.pro; sourceTree = ""; }; - 65B35EED121C261E003EAD18 /* pluginmanager.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pluginmanager.pro; sourceTree = ""; }; - 65B35EF0121C261E003EAD18 /* myplug.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = myplug.xml; sourceTree = ""; }; - 65B35EF1121C261E003EAD18 /* otherplugin.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = otherplugin.xml; sourceTree = ""; }; - 65B35EF2121C261E003EAD18 /* plugin1.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = plugin1.xml; sourceTree = ""; }; - 65B35EF3121C261E003EAD18 /* test.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = test.pro; sourceTree = ""; }; - 65B35EF4121C261E003EAD18 /* test.sh */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.sh; path = test.sh; sourceTree = ""; }; - 65B35EF5121C261E003EAD18 /* tst_pluginmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = tst_pluginmanager.cpp; sourceTree = ""; }; - 65B35EF7121C261E003EAD18 /* pluginspec.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pluginspec.pro; sourceTree = ""; }; - 65B35EF8121C261E003EAD18 /* test.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = test.pro; sourceTree = ""; }; - 65B35EF9121C261E003EAD18 /* test.sh */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.sh; path = test.sh; sourceTree = ""; }; - 65B35EFB121C261E003EAD18 /* spec1.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec1.xml; sourceTree = ""; }; - 65B35EFC121C261E003EAD18 /* spec2.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec2.xml; sourceTree = ""; }; - 65B35EFD121C261E003EAD18 /* spec3.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec3.xml; sourceTree = ""; }; - 65B35EFE121C261E003EAD18 /* spec4.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec4.xml; sourceTree = ""; }; - 65B35EFF121C261E003EAD18 /* spec5.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec5.xml; sourceTree = ""; }; - 65B35F01121C261E003EAD18 /* spec.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec.xml; sourceTree = ""; }; - 65B35F03121C261E003EAD18 /* testplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = testplugin.cpp; sourceTree = ""; }; - 65B35F04121C261E003EAD18 /* testplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = testplugin.h; sourceTree = ""; }; - 65B35F05121C261E003EAD18 /* testplugin.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = testplugin.pro; sourceTree = ""; }; - 65B35F06121C261E003EAD18 /* testplugin.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = testplugin.xml; sourceTree = ""; }; - 65B35F07121C261E003EAD18 /* testplugin_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = testplugin_global.h; sourceTree = ""; }; - 65B35F09121C261E003EAD18 /* simplespec.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = simplespec.xml; sourceTree = ""; }; - 65B35F0A121C261E003EAD18 /* spec1.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec1.xml; sourceTree = ""; }; - 65B35F0B121C261E003EAD18 /* spec2.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec2.xml; sourceTree = ""; }; - 65B35F0C121C261E003EAD18 /* spec_wrong1.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec_wrong1.xml; sourceTree = ""; }; - 65B35F0D121C261E003EAD18 /* spec_wrong2.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec_wrong2.xml; sourceTree = ""; }; - 65B35F0E121C261E003EAD18 /* spec_wrong3.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec_wrong3.xml; sourceTree = ""; }; - 65B35F0F121C261E003EAD18 /* spec_wrong4.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec_wrong4.xml; sourceTree = ""; }; - 65B35F10121C261E003EAD18 /* spec_wrong5.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = spec_wrong5.xml; sourceTree = ""; }; - 65B35F11121C261E003EAD18 /* tst_pluginspec.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = tst_pluginspec.cpp; sourceTree = ""; }; - 65B35F12121C261E003EAD18 /* extensionsystem_test.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = extensionsystem_test.pri; sourceTree = ""; }; - 65B35F14121C261E003EAD18 /* manual.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = manual.pro; sourceTree = ""; }; - 65B35F16121C261E003EAD18 /* plugindialog.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugindialog.cpp; sourceTree = ""; }; - 65B35F17121C261E003EAD18 /* plugindialog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugindialog.h; sourceTree = ""; }; - 65B35F1A121C261E003EAD18 /* plugin.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = plugin.xml; sourceTree = ""; }; - 65B35F1B121C261E003EAD18 /* plugin1.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugin1.cpp; sourceTree = ""; }; - 65B35F1C121C261E003EAD18 /* plugin1.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugin1.h; sourceTree = ""; }; - 65B35F1D121C261E003EAD18 /* plugin1.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin1.pro; sourceTree = ""; }; - 65B35F1F121C261E003EAD18 /* plugin.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = plugin.xml; sourceTree = ""; }; - 65B35F20121C261E003EAD18 /* plugin2.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugin2.cpp; sourceTree = ""; }; - 65B35F21121C261E003EAD18 /* plugin2.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugin2.h; sourceTree = ""; }; - 65B35F22121C261E003EAD18 /* plugin2.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin2.pro; sourceTree = ""; }; - 65B35F24121C261E003EAD18 /* plugin.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = plugin.xml; sourceTree = ""; }; - 65B35F25121C261E003EAD18 /* plugin3.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugin3.cpp; sourceTree = ""; }; - 65B35F26121C261E003EAD18 /* plugin3.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugin3.h; sourceTree = ""; }; - 65B35F27121C261E003EAD18 /* plugin3.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugin3.pro; sourceTree = ""; }; - 65B35F29121C261E003EAD18 /* plugin.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = plugin.xml; sourceTree = ""; }; - 65B35F2A121C261E003EAD18 /* plugins.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugins.pro; sourceTree = ""; }; - 65B35F2B121C261E003EAD18 /* pluginview.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pluginview.pro; sourceTree = ""; }; - 65B35F2C121C261E003EAD18 /* test.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = test.pro; sourceTree = ""; }; - 65B35F2D121C261E003EAD18 /* test.sh */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.sh; path = test.sh; sourceTree = ""; }; - 65B35F2E121C261E003EAD18 /* test.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = test.pro; sourceTree = ""; }; - 65B35F31121C261E003EAD18 /* glc_3dwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_3dwidget.cpp; sourceTree = ""; }; - 65B35F32121C261E003EAD18 /* glc_3dwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_3dwidget.h; sourceTree = ""; }; - 65B35F33121C261E003EAD18 /* glc_3dwidgetmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_3dwidgetmanager.cpp; sourceTree = ""; }; - 65B35F34121C261E003EAD18 /* glc_3dwidgetmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_3dwidgetmanager.h; sourceTree = ""; }; - 65B35F35121C261E003EAD18 /* glc_3dwidgetmanagerhandle.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_3dwidgetmanagerhandle.cpp; sourceTree = ""; }; - 65B35F36121C261E003EAD18 /* glc_3dwidgetmanagerhandle.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_3dwidgetmanagerhandle.h; sourceTree = ""; }; - 65B35F37121C261E003EAD18 /* glc_abstractmanipulator.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_abstractmanipulator.cpp; sourceTree = ""; }; - 65B35F38121C261E003EAD18 /* glc_abstractmanipulator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_abstractmanipulator.h; sourceTree = ""; }; - 65B35F39121C261E003EAD18 /* glc_axis.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_axis.cpp; sourceTree = ""; }; - 65B35F3A121C261E003EAD18 /* glc_axis.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_axis.h; sourceTree = ""; }; - 65B35F3B121C261E003EAD18 /* glc_cuttingplane.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_cuttingplane.cpp; sourceTree = ""; }; - 65B35F3C121C261E003EAD18 /* glc_cuttingplane.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_cuttingplane.h; sourceTree = ""; }; - 65B35F3D121C261E003EAD18 /* glc_pullmanipulator.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_pullmanipulator.cpp; sourceTree = ""; }; - 65B35F3E121C261E003EAD18 /* glc_pullmanipulator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_pullmanipulator.h; sourceTree = ""; }; - 65B35F3F121C261E003EAD18 /* glc_rotationmanipulator.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_rotationmanipulator.cpp; sourceTree = ""; }; - 65B35F40121C261E003EAD18 /* glc_rotationmanipulator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_rotationmanipulator.h; sourceTree = ""; }; - 65B35F43121C261E003EAD18 /* glext.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glext.h; sourceTree = ""; }; - 65B35F45121C261E003EAD18 /* atmosphere.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = atmosphere.c; sourceTree = ""; }; - 65B35F46121C261E003EAD18 /* atmosphere.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = atmosphere.h; sourceTree = ""; }; - 65B35F47121C261E003EAD18 /* AUTHORS */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = AUTHORS; sourceTree = ""; }; - 65B35F48121C261E003EAD18 /* background.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = background.c; sourceTree = ""; }; - 65B35F49121C261E003EAD18 /* background.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = background.h; sourceTree = ""; }; - 65B35F4A121C261E003EAD18 /* camera.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = camera.c; sourceTree = ""; }; - 65B35F4B121C261E003EAD18 /* camera.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = camera.h; sourceTree = ""; }; - 65B35F4C121C261E003EAD18 /* ChangeLog */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = ChangeLog; sourceTree = ""; }; - 65B35F4D121C261E003EAD18 /* chunk.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = chunk.c; sourceTree = ""; }; - 65B35F4E121C261E003EAD18 /* chunk.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = chunk.h; sourceTree = ""; }; - 65B35F4F121C261E003EAD18 /* chunktable.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = chunktable.h; sourceTree = ""; }; - 65B35F50121C261E003EAD18 /* ease.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ease.c; sourceTree = ""; }; - 65B35F51121C261E003EAD18 /* ease.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ease.h; sourceTree = ""; }; - 65B35F52121C261E003EAD18 /* file.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = file.c; sourceTree = ""; }; - 65B35F53121C261E003EAD18 /* file.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = file.h; sourceTree = ""; }; - 65B35F54121C261E003EAD18 /* io.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = io.c; sourceTree = ""; }; - 65B35F55121C261E003EAD18 /* io.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = io.h; sourceTree = ""; }; - 65B35F56121C261E003EAD18 /* light.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = light.c; sourceTree = ""; }; - 65B35F57121C261E003EAD18 /* light.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = light.h; sourceTree = ""; }; - 65B35F58121C261E003EAD18 /* material.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = material.c; sourceTree = ""; }; - 65B35F59121C261E003EAD18 /* material.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = material.h; sourceTree = ""; }; - 65B35F5A121C261E003EAD18 /* matrix.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = matrix.c; sourceTree = ""; }; - 65B35F5B121C261E003EAD18 /* matrix.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = matrix.h; sourceTree = ""; }; - 65B35F5C121C261E003EAD18 /* mesh.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = mesh.c; sourceTree = ""; }; - 65B35F5D121C261E003EAD18 /* mesh.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mesh.h; sourceTree = ""; }; - 65B35F5E121C261E003EAD18 /* node.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = node.c; sourceTree = ""; }; - 65B35F5F121C261E003EAD18 /* node.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = node.h; sourceTree = ""; }; - 65B35F60121C261E003EAD18 /* quat.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = quat.c; sourceTree = ""; }; - 65B35F61121C261E003EAD18 /* quat.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = quat.h; sourceTree = ""; }; - 65B35F62121C261E003EAD18 /* README */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = README; sourceTree = ""; }; - 65B35F63121C261E003EAD18 /* shadow.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = shadow.c; sourceTree = ""; }; - 65B35F64121C261E003EAD18 /* shadow.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = shadow.h; sourceTree = ""; }; - 65B35F65121C261E003EAD18 /* tcb.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = tcb.c; sourceTree = ""; }; - 65B35F66121C261E003EAD18 /* tcb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = tcb.h; sourceTree = ""; }; - 65B35F67121C261E003EAD18 /* tracks.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = tracks.c; sourceTree = ""; }; - 65B35F68121C261E003EAD18 /* tracks.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = tracks.h; sourceTree = ""; }; - 65B35F69121C261E003EAD18 /* types.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = types.h; sourceTree = ""; }; - 65B35F6A121C261E003EAD18 /* vector.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = vector.c; sourceTree = ""; }; - 65B35F6B121C261E003EAD18 /* vector.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = vector.h; sourceTree = ""; }; - 65B35F6C121C261E003EAD18 /* viewport.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = viewport.c; sourceTree = ""; }; - 65B35F6D121C261E003EAD18 /* viewport.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = viewport.h; sourceTree = ""; }; - 65B35F6F121C261E003EAD18 /* crypt.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = crypt.h; sourceTree = ""; }; - 65B35F70121C261E003EAD18 /* ioapi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ioapi.c; sourceTree = ""; }; - 65B35F71121C261E003EAD18 /* ioapi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ioapi.h; sourceTree = ""; }; - 65B35F72121C261E003EAD18 /* quazip.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = quazip.cpp; sourceTree = ""; }; - 65B35F73121C261E003EAD18 /* quazip.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = quazip.h; sourceTree = ""; }; - 65B35F74121C261E003EAD18 /* quazipfile.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = quazipfile.cpp; sourceTree = ""; }; - 65B35F75121C261E003EAD18 /* quazipfile.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = quazipfile.h; sourceTree = ""; }; - 65B35F76121C261E003EAD18 /* quazipfileinfo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = quazipfileinfo.h; sourceTree = ""; }; - 65B35F77121C261E003EAD18 /* quazipnewinfo.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = quazipnewinfo.cpp; sourceTree = ""; }; - 65B35F78121C261E003EAD18 /* quazipnewinfo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = quazipnewinfo.h; sourceTree = ""; }; - 65B35F79121C261E003EAD18 /* unzip.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = unzip.c; sourceTree = ""; }; - 65B35F7A121C261E003EAD18 /* unzip.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = unzip.h; sourceTree = ""; }; - 65B35F7B121C261E003EAD18 /* zip.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = zip.c; sourceTree = ""; }; - 65B35F7C121C261E003EAD18 /* zip.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = zip.h; sourceTree = ""; }; - 65B35F7E121C261E003EAD18 /* adler32.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = adler32.c; sourceTree = ""; }; - 65B35F7F121C261E003EAD18 /* algorithm.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = algorithm.txt; sourceTree = ""; }; - 65B35F80121C261E003EAD18 /* ChangeLog */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = ChangeLog; sourceTree = ""; }; - 65B35F81121C261E003EAD18 /* compress.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = compress.c; sourceTree = ""; }; - 65B35F82121C261E003EAD18 /* configure */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.sh; path = configure; sourceTree = ""; }; - 65B35F83121C261E003EAD18 /* crc32.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = crc32.c; sourceTree = ""; }; - 65B35F84121C261E003EAD18 /* crc32.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = crc32.h; sourceTree = ""; }; - 65B35F85121C261E003EAD18 /* deflate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = deflate.c; sourceTree = ""; }; - 65B35F86121C261E003EAD18 /* deflate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = deflate.h; sourceTree = ""; }; - 65B35F87121C261E003EAD18 /* example.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = example.c; sourceTree = ""; }; - 65B35F88121C261E003EAD18 /* FAQ */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = FAQ; sourceTree = ""; }; - 65B35F89121C261E003EAD18 /* gzio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = gzio.c; sourceTree = ""; }; - 65B35F8A121C261E003EAD18 /* INDEX */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = INDEX; sourceTree = ""; }; - 65B35F8B121C261E003EAD18 /* infback.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = infback.c; sourceTree = ""; }; - 65B35F8C121C261E003EAD18 /* inffast.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = inffast.c; sourceTree = ""; }; - 65B35F8D121C261E003EAD18 /* inffast.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = inffast.h; sourceTree = ""; }; - 65B35F8E121C261E003EAD18 /* inffixed.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = inffixed.h; sourceTree = ""; }; - 65B35F8F121C261E003EAD18 /* inflate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = inflate.c; sourceTree = ""; }; - 65B35F90121C261E003EAD18 /* inflate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = inflate.h; sourceTree = ""; }; - 65B35F91121C261E003EAD18 /* inftrees.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = inftrees.c; sourceTree = ""; }; - 65B35F92121C261E003EAD18 /* inftrees.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = inftrees.h; sourceTree = ""; }; - 65B35F93121C261E003EAD18 /* make_vms.com */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = make_vms.com; sourceTree = ""; }; - 65B35F94121C261E003EAD18 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65B35F95121C261E003EAD18 /* Makefile.in */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = Makefile.in; sourceTree = ""; }; - 65B35F96121C261E003EAD18 /* minigzip.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = minigzip.c; sourceTree = ""; }; - 65B35F97121C261E003EAD18 /* README */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = README; sourceTree = ""; }; - 65B35F98121C261E003EAD18 /* trees.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = trees.c; sourceTree = ""; }; - 65B35F99121C261E003EAD18 /* trees.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = trees.h; sourceTree = ""; }; - 65B35F9A121C261E003EAD18 /* uncompr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uncompr.c; sourceTree = ""; }; - 65B35F9B121C261E003EAD18 /* zconf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = zconf.h; sourceTree = ""; }; - 65B35F9C121C261E003EAD18 /* zconf.in.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = zconf.in.h; sourceTree = ""; }; - 65B35F9D121C261E003EAD18 /* zlib.3 */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = zlib.3; sourceTree = ""; }; - 65B35F9E121C261E003EAD18 /* zlib.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = zlib.h; sourceTree = ""; }; - 65B35F9F121C261E003EAD18 /* zutil.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = zutil.c; sourceTree = ""; }; - 65B35FA0121C261E003EAD18 /* zutil.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = zutil.h; sourceTree = ""; }; - 65B35FA2121C261E003EAD18 /* COPYING */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = COPYING; sourceTree = ""; }; - 65B35FA4121C261E003EAD18 /* glc_3drep.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_3drep.cpp; sourceTree = ""; }; - 65B35FA5121C261E003EAD18 /* glc_3drep.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_3drep.h; sourceTree = ""; }; - 65B35FA6121C261E003EAD18 /* glc_arrow.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_arrow.cpp; sourceTree = ""; }; - 65B35FA7121C261E003EAD18 /* glc_arrow.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_arrow.h; sourceTree = ""; }; - 65B35FA8121C261E003EAD18 /* glc_box.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_box.cpp; sourceTree = ""; }; - 65B35FA9121C261E003EAD18 /* glc_box.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_box.h; sourceTree = ""; }; - 65B35FAA121C261E003EAD18 /* glc_bsrep.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_bsrep.cpp; sourceTree = ""; }; - 65B35FAB121C261E003EAD18 /* glc_bsrep.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_bsrep.h; sourceTree = ""; }; - 65B35FAC121C261E003EAD18 /* glc_circle.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_circle.cpp; sourceTree = ""; }; - 65B35FAD121C261E003EAD18 /* glc_circle.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_circle.h; sourceTree = ""; }; - 65B35FAE121C261E003EAD18 /* glc_cone.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_cone.cpp; sourceTree = ""; }; - 65B35FAF121C261E003EAD18 /* glc_cone.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_cone.h; sourceTree = ""; }; - 65B35FB0121C261E003EAD18 /* glc_cylinder.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_cylinder.cpp; sourceTree = ""; }; - 65B35FB1121C261E003EAD18 /* glc_cylinder.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_cylinder.h; sourceTree = ""; }; - 65B35FB2121C261E003EAD18 /* glc_disc.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_disc.cpp; sourceTree = ""; }; - 65B35FB3121C261E003EAD18 /* glc_disc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_disc.h; sourceTree = ""; }; - 65B35FB4121C261E003EAD18 /* glc_geometry.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_geometry.cpp; sourceTree = ""; }; - 65B35FB5121C261E003EAD18 /* glc_geometry.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_geometry.h; sourceTree = ""; }; - 65B35FB6121C261E003EAD18 /* glc_line.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_line.cpp; sourceTree = ""; }; - 65B35FB7121C261E003EAD18 /* glc_line.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_line.h; sourceTree = ""; }; - 65B35FB8121C261E003EAD18 /* glc_lod.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_lod.cpp; sourceTree = ""; }; - 65B35FB9121C261E003EAD18 /* glc_lod.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_lod.h; sourceTree = ""; }; - 65B35FBA121C261E003EAD18 /* glc_mesh.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_mesh.cpp; sourceTree = ""; }; - 65B35FBB121C261E003EAD18 /* glc_mesh.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_mesh.h; sourceTree = ""; }; - 65B35FBC121C261E003EAD18 /* glc_meshdata.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_meshdata.cpp; sourceTree = ""; }; - 65B35FBD121C261E003EAD18 /* glc_meshdata.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_meshdata.h; sourceTree = ""; }; - 65B35FBE121C261E003EAD18 /* glc_point.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_point.cpp; sourceTree = ""; }; - 65B35FBF121C261E003EAD18 /* glc_point.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_point.h; sourceTree = ""; }; - 65B35FC0121C261E003EAD18 /* glc_pointsprite.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_pointsprite.cpp; sourceTree = ""; }; - 65B35FC1121C261E003EAD18 /* glc_pointsprite.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_pointsprite.h; sourceTree = ""; }; - 65B35FC2121C261E003EAD18 /* glc_polylines.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_polylines.cpp; sourceTree = ""; }; - 65B35FC3121C261E003EAD18 /* glc_polylines.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_polylines.h; sourceTree = ""; }; - 65B35FC4121C261E003EAD18 /* glc_primitivegroup.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_primitivegroup.cpp; sourceTree = ""; }; - 65B35FC5121C261E003EAD18 /* glc_primitivegroup.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_primitivegroup.h; sourceTree = ""; }; - 65B35FC6121C261E003EAD18 /* glc_rectangle.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_rectangle.cpp; sourceTree = ""; }; - 65B35FC7121C261E003EAD18 /* glc_rectangle.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_rectangle.h; sourceTree = ""; }; - 65B35FC8121C261E003EAD18 /* glc_rep.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_rep.cpp; sourceTree = ""; }; - 65B35FC9121C261E003EAD18 /* glc_rep.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_rep.h; sourceTree = ""; }; - 65B35FCA121C261E003EAD18 /* glc_sphere.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_sphere.cpp; sourceTree = ""; }; - 65B35FCB121C261E003EAD18 /* glc_sphere.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_sphere.h; sourceTree = ""; }; - 65B35FCC121C261E003EAD18 /* glc_wiredata.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_wiredata.cpp; sourceTree = ""; }; - 65B35FCD121C261E003EAD18 /* glc_wiredata.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_wiredata.h; sourceTree = ""; }; - 65B35FCE121C261E003EAD18 /* glc_boundingbox.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_boundingbox.cpp; sourceTree = ""; }; - 65B35FCF121C261E003EAD18 /* glc_boundingbox.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_boundingbox.h; sourceTree = ""; }; - 65B35FD0121C261E003EAD18 /* glc_cachemanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_cachemanager.cpp; sourceTree = ""; }; - 65B35FD1121C261E003EAD18 /* glc_cachemanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_cachemanager.h; sourceTree = ""; }; - 65B35FD2121C261E003EAD18 /* glc_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_config.h; sourceTree = ""; }; - 65B35FD3121C261E003EAD18 /* glc_exception.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_exception.cpp; sourceTree = ""; }; - 65B35FD4121C261E003EAD18 /* glc_exception.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_exception.h; sourceTree = ""; }; - 65B35FD5121C261E003EAD18 /* glc_ext.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_ext.cpp; sourceTree = ""; }; - 65B35FD6121C261E003EAD18 /* glc_ext.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_ext.h; sourceTree = ""; }; - 65B35FD7121C261E003EAD18 /* glc_factory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_factory.cpp; sourceTree = ""; }; - 65B35FD8121C261E003EAD18 /* glc_factory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_factory.h; sourceTree = ""; }; - 65B35FD9121C261E003EAD18 /* glc_fileformatexception.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_fileformatexception.cpp; sourceTree = ""; }; - 65B35FDA121C261E003EAD18 /* glc_fileformatexception.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_fileformatexception.h; sourceTree = ""; }; - 65B35FDB121C261E003EAD18 /* glc_global.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_global.cpp; sourceTree = ""; }; - 65B35FDC121C261E003EAD18 /* glc_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_global.h; sourceTree = ""; }; - 65B35FDD121C261E003EAD18 /* glc_lib.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = glc_lib.pri; sourceTree = ""; }; - 65B35FDE121C261E003EAD18 /* glc_lib.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = glc_lib.pro; sourceTree = ""; }; - 65B35FDF121C261E003EAD18 /* glc_object.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_object.cpp; sourceTree = ""; }; - 65B35FE0121C261E003EAD18 /* glc_object.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_object.h; sourceTree = ""; }; - 65B35FE1121C261E003EAD18 /* glc_openglexception.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_openglexception.cpp; sourceTree = ""; }; - 65B35FE2121C261E003EAD18 /* glc_openglexception.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_openglexception.h; sourceTree = ""; }; - 65B35FE3121C261E003EAD18 /* glc_renderstatistics.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_renderstatistics.cpp; sourceTree = ""; }; - 65B35FE4121C261E003EAD18 /* glc_renderstatistics.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_renderstatistics.h; sourceTree = ""; }; - 65B35FE5121C261E003EAD18 /* glc_state.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_state.cpp; sourceTree = ""; }; - 65B35FE6121C261E003EAD18 /* glc_state.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_state.h; sourceTree = ""; }; - 65B35FE8121C261E003EAD18 /* GLC_3DRep */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_3DRep; sourceTree = ""; }; - 65B35FE9121C261E003EAD18 /* GLC_3DViewCollection */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_3DViewCollection; sourceTree = ""; }; - 65B35FEA121C261E003EAD18 /* GLC_3DViewInstance */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_3DViewInstance; sourceTree = ""; }; - 65B35FEB121C261E003EAD18 /* GLC_3DWidget */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_3DWidget; sourceTree = ""; }; - 65B35FEC121C261E003EAD18 /* GLC_3DWidgetManager */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_3DWidgetManager; sourceTree = ""; }; - 65B35FED121C261E003EAD18 /* GLC_3DWidgetManagerHandle */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_3DWidgetManagerHandle; sourceTree = ""; }; - 65B35FEE121C261E003EAD18 /* GLC_AbstractManipulator */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_AbstractManipulator; sourceTree = ""; }; - 65B35FEF121C261E003EAD18 /* GLC_Arrow */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Arrow; sourceTree = ""; }; - 65B35FF0121C261E003EAD18 /* GLC_Attribute */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Attribute; sourceTree = ""; }; - 65B35FF1121C261E003EAD18 /* GLC_Axis */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Axis; sourceTree = ""; }; - 65B35FF2121C261E003EAD18 /* GLC_BoundingBox */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_BoundingBox; sourceTree = ""; }; - 65B35FF3121C261E003EAD18 /* GLC_Box */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Box; sourceTree = ""; }; - 65B35FF4121C261E003EAD18 /* GLC_BSRep */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_BSRep; sourceTree = ""; }; - 65B35FF5121C261E003EAD18 /* GLC_CacheManager */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_CacheManager; sourceTree = ""; }; - 65B35FF6121C261E003EAD18 /* GLC_Camera */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Camera; sourceTree = ""; }; - 65B35FF7121C261E003EAD18 /* GLC_Circle */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Circle; sourceTree = ""; }; - 65B35FF8121C261E003EAD18 /* GLC_Cone */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Cone; sourceTree = ""; }; - 65B35FF9121C261E003EAD18 /* GLC_CuttingPlane */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_CuttingPlane; sourceTree = ""; }; - 65B35FFA121C261E003EAD18 /* GLC_Cylinder */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Cylinder; sourceTree = ""; }; - 65B35FFB121C261E003EAD18 /* GLC_Disc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Disc; sourceTree = ""; }; - 65B35FFC121C261E003EAD18 /* GLC_Exception */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Exception; sourceTree = ""; }; - 65B35FFD121C261E003EAD18 /* GLC_Ext */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Ext; sourceTree = ""; }; - 65B35FFE121C261E003EAD18 /* GLC_Factory */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Factory; sourceTree = ""; }; - 65B35FFF121C261E003EAD18 /* GLC_FileFormatException */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_FileFormatException; sourceTree = ""; }; - 65B36000121C261E003EAD18 /* GLC_FlyMover */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_FlyMover; sourceTree = ""; }; - 65B36001121C261E003EAD18 /* GLC_Frustum */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Frustum; sourceTree = ""; }; - 65B36002121C261E003EAD18 /* GLC_Geometry */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Geometry; sourceTree = ""; }; - 65B36003121C261E003EAD18 /* GLC_GeomTools */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_GeomTools; sourceTree = ""; }; - 65B36004121C261E003EAD18 /* GLC_Global */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Global; sourceTree = ""; }; - 65B36005121C261E003EAD18 /* GLC_ImagePlane */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_ImagePlane; sourceTree = ""; }; - 65B36006121C261E003EAD18 /* GLC_Interpolator */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Interpolator; sourceTree = ""; }; - 65B36007121C261E003EAD18 /* GLC_Light */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Light; sourceTree = ""; }; - 65B36008121C261E003EAD18 /* GLC_Line */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Line; sourceTree = ""; }; - 65B36009121C261E003EAD18 /* GLC_Line3d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Line3d; sourceTree = ""; }; - 65B3600A121C261E003EAD18 /* GLC_Material */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Material; sourceTree = ""; }; - 65B3600B121C261E003EAD18 /* GLC_Matrix4x4 */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Matrix4x4; sourceTree = ""; }; - 65B3600C121C261E003EAD18 /* GLC_Mesh */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Mesh; sourceTree = ""; }; - 65B3600D121C261E003EAD18 /* GLC_Mover */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Mover; sourceTree = ""; }; - 65B3600E121C261E003EAD18 /* GLC_MoverController */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_MoverController; sourceTree = ""; }; - 65B3600F121C261E003EAD18 /* GLC_Object */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Object; sourceTree = ""; }; - 65B36010121C261E003EAD18 /* GLC_Octree */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Octree; sourceTree = ""; }; - 65B36011121C261E003EAD18 /* GLC_OctreeNode */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_OctreeNode; sourceTree = ""; }; - 65B36012121C261E003EAD18 /* GLC_OpenGlException */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_OpenGlException; sourceTree = ""; }; - 65B36013121C261E003EAD18 /* GLC_PanMover */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_PanMover; sourceTree = ""; }; - 65B36014121C261E003EAD18 /* GLC_Plane */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Plane; sourceTree = ""; }; - 65B36015121C261E003EAD18 /* GLC_Point */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Point; sourceTree = ""; }; - 65B36016121C261E003EAD18 /* GLC_Point2d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Point2d; sourceTree = ""; }; - 65B36017121C261E003EAD18 /* GLC_Point2df */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Point2df; sourceTree = ""; }; - 65B36018121C261E003EAD18 /* GLC_Point3d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Point3d; sourceTree = ""; }; - 65B36019121C261E003EAD18 /* GLC_Point3df */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Point3df; sourceTree = ""; }; - 65B3601A121C261E003EAD18 /* GLC_Point4d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Point4d; sourceTree = ""; }; - 65B3601B121C261E003EAD18 /* GLC_PointSprite */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_PointSprite; sourceTree = ""; }; - 65B3601C121C261E003EAD18 /* GLC_Polylines */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Polylines; sourceTree = ""; }; - 65B3601D121C261E003EAD18 /* GLC_PullManipulator */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_PullManipulator; sourceTree = ""; }; - 65B3601E121C261E003EAD18 /* GLC_Rectangle */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Rectangle; sourceTree = ""; }; - 65B3601F121C261E003EAD18 /* GLC_RenderProperties */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_RenderProperties; sourceTree = ""; }; - 65B36020121C261E003EAD18 /* GLC_RenderStatistics */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_RenderStatistics; sourceTree = ""; }; - 65B36021121C261E003EAD18 /* GLC_Rep */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Rep; sourceTree = ""; }; - 65B36022121C261E003EAD18 /* GLC_RepCrossMover */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_RepCrossMover; sourceTree = ""; }; - 65B36023121C261E003EAD18 /* GLC_RepFlyMover */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_RepFlyMover; sourceTree = ""; }; - 65B36024121C261E003EAD18 /* GLC_RepMover */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_RepMover; sourceTree = ""; }; - 65B36025121C261E003EAD18 /* GLC_RepTrackBallMover */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_RepTrackBallMover; sourceTree = ""; }; - 65B36026121C261E003EAD18 /* GLC_RotationManipulator */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_RotationManipulator; sourceTree = ""; }; - 65B36027121C261E003EAD18 /* GLC_SelectionMaterial */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_SelectionMaterial; sourceTree = ""; }; - 65B36028121C261E003EAD18 /* GLC_Shader */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Shader; sourceTree = ""; }; - 65B36029121C261E003EAD18 /* GLC_SpacePartitioning */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_SpacePartitioning; sourceTree = ""; }; - 65B3602A121C261E003EAD18 /* GLC_Sphere */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Sphere; sourceTree = ""; }; - 65B3602B121C261E003EAD18 /* GLC_State */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_State; sourceTree = ""; }; - 65B3602C121C261E003EAD18 /* GLC_StructInstance */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_StructInstance; sourceTree = ""; }; - 65B3602D121C261E003EAD18 /* GLC_StructOccurence */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_StructOccurence; sourceTree = ""; }; - 65B3602E121C261E003EAD18 /* GLC_StructReference */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_StructReference; sourceTree = ""; }; - 65B3602F121C261E003EAD18 /* GLC_Texture */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Texture; sourceTree = ""; }; - 65B36030121C261E003EAD18 /* GLC_TrackBallMover */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_TrackBallMover; sourceTree = ""; }; - 65B36031121C261E003EAD18 /* GLC_TurnTableMover */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_TurnTableMover; sourceTree = ""; }; - 65B36032121C261E003EAD18 /* GLC_Vector2d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Vector2d; sourceTree = ""; }; - 65B36033121C261E003EAD18 /* GLC_Vector2df */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Vector2df; sourceTree = ""; }; - 65B36034121C261E003EAD18 /* GLC_Vector3d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Vector3d; sourceTree = ""; }; - 65B36035121C261E003EAD18 /* GLC_Vector3df */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Vector3df; sourceTree = ""; }; - 65B36036121C261E003EAD18 /* GLC_Vector4d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Vector4d; sourceTree = ""; }; - 65B36037121C261E003EAD18 /* GLC_Viewport */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_Viewport; sourceTree = ""; }; - 65B36038121C261E003EAD18 /* GLC_World */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_World; sourceTree = ""; }; - 65B36039121C261E003EAD18 /* GLC_WorldTo3dxml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_WorldTo3dxml; sourceTree = ""; }; - 65B3603A121C261E003EAD18 /* GLC_ZoomMover */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GLC_ZoomMover; sourceTree = ""; }; - 65B3603C121C261E003EAD18 /* glc_3dstoworld.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_3dstoworld.cpp; sourceTree = ""; }; - 65B3603D121C261E003EAD18 /* glc_3dstoworld.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_3dstoworld.h; sourceTree = ""; }; - 65B3603E121C261E003EAD18 /* glc_3dxmltoworld.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_3dxmltoworld.cpp; sourceTree = ""; }; - 65B3603F121C261E003EAD18 /* glc_3dxmltoworld.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_3dxmltoworld.h; sourceTree = ""; }; - 65B36040121C261E003EAD18 /* glc_bsreptoworld.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_bsreptoworld.cpp; sourceTree = ""; }; - 65B36041121C261E003EAD18 /* glc_bsreptoworld.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_bsreptoworld.h; sourceTree = ""; }; - 65B36042121C261E003EAD18 /* glc_colladatoworld.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_colladatoworld.cpp; sourceTree = ""; }; - 65B36043121C261E003EAD18 /* glc_colladatoworld.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_colladatoworld.h; sourceTree = ""; }; - 65B36044121C261E003EAD18 /* glc_objmtlloader.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_objmtlloader.cpp; sourceTree = ""; }; - 65B36045121C261E003EAD18 /* glc_objmtlloader.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_objmtlloader.h; sourceTree = ""; }; - 65B36046121C261E003EAD18 /* glc_objtoworld.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_objtoworld.cpp; sourceTree = ""; }; - 65B36047121C261E003EAD18 /* glc_objtoworld.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_objtoworld.h; sourceTree = ""; }; - 65B36048121C261E003EAD18 /* glc_offtoworld.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_offtoworld.cpp; sourceTree = ""; }; - 65B36049121C261E003EAD18 /* glc_offtoworld.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_offtoworld.h; sourceTree = ""; }; - 65B3604A121C261E003EAD18 /* glc_stltoworld.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_stltoworld.cpp; sourceTree = ""; }; - 65B3604B121C261E003EAD18 /* glc_stltoworld.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_stltoworld.h; sourceTree = ""; }; - 65B3604C121C261E003EAD18 /* glc_worldto3dxml.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_worldto3dxml.cpp; sourceTree = ""; }; - 65B3604D121C261E003EAD18 /* glc_worldto3dxml.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_worldto3dxml.h; sourceTree = ""; }; - 65B3604F121C261E003EAD18 /* glc_geomtools.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_geomtools.cpp; sourceTree = ""; }; - 65B36050121C261E003EAD18 /* glc_geomtools.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_geomtools.h; sourceTree = ""; }; - 65B36051121C261E003EAD18 /* glc_interpolator.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_interpolator.cpp; sourceTree = ""; }; - 65B36052121C261E003EAD18 /* glc_interpolator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_interpolator.h; sourceTree = ""; }; - 65B36053121C261E003EAD18 /* glc_line3d.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_line3d.cpp; sourceTree = ""; }; - 65B36054121C261E003EAD18 /* glc_line3d.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_line3d.h; sourceTree = ""; }; - 65B36055121C261E003EAD18 /* glc_matrix4x4.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_matrix4x4.cpp; sourceTree = ""; }; - 65B36056121C261E003EAD18 /* glc_matrix4x4.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_matrix4x4.h; sourceTree = ""; }; - 65B36057121C261E003EAD18 /* glc_plane.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_plane.cpp; sourceTree = ""; }; - 65B36058121C261E003EAD18 /* glc_plane.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_plane.h; sourceTree = ""; }; - 65B36059121C261E003EAD18 /* glc_utils_maths.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_utils_maths.h; sourceTree = ""; }; - 65B3605A121C261E003EAD18 /* glc_vector2d.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_vector2d.h; sourceTree = ""; }; - 65B3605B121C261E003EAD18 /* glc_vector2df.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_vector2df.h; sourceTree = ""; }; - 65B3605C121C261E003EAD18 /* glc_vector3d.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_vector3d.h; sourceTree = ""; }; - 65B3605D121C261E003EAD18 /* glc_vector3df.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_vector3df.h; sourceTree = ""; }; - 65B3605E121C261E003EAD18 /* glc_vector4d.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_vector4d.cpp; sourceTree = ""; }; - 65B3605F121C261E003EAD18 /* glc_vector4d.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_vector4d.h; sourceTree = ""; }; - 65B36061121C261E003EAD18 /* glc_3dviewcollection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_3dviewcollection.cpp; sourceTree = ""; }; - 65B36062121C261E003EAD18 /* glc_3dviewcollection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_3dviewcollection.h; sourceTree = ""; }; - 65B36063121C261E003EAD18 /* glc_3dviewinstance.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_3dviewinstance.cpp; sourceTree = ""; }; - 65B36064121C261E003EAD18 /* glc_3dviewinstance.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_3dviewinstance.h; sourceTree = ""; }; - 65B36065121C261E003EAD18 /* glc_attributes.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_attributes.cpp; sourceTree = ""; }; - 65B36066121C261E003EAD18 /* glc_attributes.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_attributes.h; sourceTree = ""; }; - 65B36067121C261E003EAD18 /* glc_octree.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_octree.cpp; sourceTree = ""; }; - 65B36068121C261E003EAD18 /* glc_octree.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_octree.h; sourceTree = ""; }; - 65B36069121C261E003EAD18 /* glc_octreenode.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_octreenode.cpp; sourceTree = ""; }; - 65B3606A121C261E003EAD18 /* glc_octreenode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_octreenode.h; sourceTree = ""; }; - 65B3606B121C261E003EAD18 /* glc_spacepartitioning.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_spacepartitioning.cpp; sourceTree = ""; }; - 65B3606C121C261E003EAD18 /* glc_spacepartitioning.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_spacepartitioning.h; sourceTree = ""; }; - 65B3606D121C261E003EAD18 /* glc_structinstance.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_structinstance.cpp; sourceTree = ""; }; - 65B3606E121C261E003EAD18 /* glc_structinstance.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_structinstance.h; sourceTree = ""; }; - 65B3606F121C261E003EAD18 /* glc_structoccurence.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_structoccurence.cpp; sourceTree = ""; }; - 65B36070121C261E003EAD18 /* glc_structoccurence.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_structoccurence.h; sourceTree = ""; }; - 65B36071121C261E003EAD18 /* glc_structreference.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_structreference.cpp; sourceTree = ""; }; - 65B36072121C261E003EAD18 /* glc_structreference.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_structreference.h; sourceTree = ""; }; - 65B36073121C261E003EAD18 /* glc_world.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_world.cpp; sourceTree = ""; }; - 65B36074121C261E003EAD18 /* glc_world.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_world.h; sourceTree = ""; }; - 65B36075121C261E003EAD18 /* glc_worldhandle.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_worldhandle.cpp; sourceTree = ""; }; - 65B36076121C261E003EAD18 /* glc_worldhandle.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_worldhandle.h; sourceTree = ""; }; - 65B36078121C261E003EAD18 /* glc_light.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_light.cpp; sourceTree = ""; }; - 65B36079121C261E003EAD18 /* glc_light.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_light.h; sourceTree = ""; }; - 65B3607A121C261E003EAD18 /* glc_material.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_material.cpp; sourceTree = ""; }; - 65B3607B121C261E003EAD18 /* glc_material.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_material.h; sourceTree = ""; }; - 65B3607C121C261E003EAD18 /* glc_renderproperties.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_renderproperties.cpp; sourceTree = ""; }; - 65B3607D121C261E003EAD18 /* glc_renderproperties.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_renderproperties.h; sourceTree = ""; }; - 65B3607E121C261E003EAD18 /* glc_selectionmaterial.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_selectionmaterial.cpp; sourceTree = ""; }; - 65B3607F121C261E003EAD18 /* glc_selectionmaterial.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_selectionmaterial.h; sourceTree = ""; }; - 65B36080121C261E003EAD18 /* glc_shader.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_shader.cpp; sourceTree = ""; }; - 65B36081121C261E003EAD18 /* glc_shader.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_shader.h; sourceTree = ""; }; - 65B36082121C261E003EAD18 /* glc_texture.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_texture.cpp; sourceTree = ""; }; - 65B36083121C261E003EAD18 /* glc_texture.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_texture.h; sourceTree = ""; }; - 65B36085121C261E003EAD18 /* glc_camera.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_camera.cpp; sourceTree = ""; }; - 65B36086121C261E003EAD18 /* glc_camera.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_camera.h; sourceTree = ""; }; - 65B36087121C261E003EAD18 /* glc_flymover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_flymover.cpp; sourceTree = ""; }; - 65B36088121C261E003EAD18 /* glc_flymover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_flymover.h; sourceTree = ""; }; - 65B36089121C261E003EAD18 /* glc_frustum.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_frustum.cpp; sourceTree = ""; }; - 65B3608A121C261E003EAD18 /* glc_frustum.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_frustum.h; sourceTree = ""; }; - 65B3608B121C261E003EAD18 /* glc_imageplane.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_imageplane.cpp; sourceTree = ""; }; - 65B3608C121C261E003EAD18 /* glc_imageplane.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_imageplane.h; sourceTree = ""; }; - 65B3608D121C261E003EAD18 /* glc_mover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_mover.cpp; sourceTree = ""; }; - 65B3608E121C261E003EAD18 /* glc_mover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_mover.h; sourceTree = ""; }; - 65B3608F121C261E003EAD18 /* glc_movercontroller.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_movercontroller.cpp; sourceTree = ""; }; - 65B36090121C261E003EAD18 /* glc_movercontroller.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_movercontroller.h; sourceTree = ""; }; - 65B36091121C261E003EAD18 /* glc_panmover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_panmover.cpp; sourceTree = ""; }; - 65B36092121C261E003EAD18 /* glc_panmover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_panmover.h; sourceTree = ""; }; - 65B36093121C261E003EAD18 /* glc_repcrossmover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_repcrossmover.cpp; sourceTree = ""; }; - 65B36094121C261E003EAD18 /* glc_repcrossmover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_repcrossmover.h; sourceTree = ""; }; - 65B36095121C261E003EAD18 /* glc_repflymover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_repflymover.cpp; sourceTree = ""; }; - 65B36096121C261E003EAD18 /* glc_repflymover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_repflymover.h; sourceTree = ""; }; - 65B36097121C261E003EAD18 /* glc_repmover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_repmover.cpp; sourceTree = ""; }; - 65B36098121C261E003EAD18 /* glc_repmover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_repmover.h; sourceTree = ""; }; - 65B36099121C261E003EAD18 /* glc_reptrackballmover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_reptrackballmover.cpp; sourceTree = ""; }; - 65B3609A121C261E003EAD18 /* glc_reptrackballmover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_reptrackballmover.h; sourceTree = ""; }; - 65B3609B121C261E003EAD18 /* glc_settargetmover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_settargetmover.cpp; sourceTree = ""; }; - 65B3609C121C261E003EAD18 /* glc_settargetmover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_settargetmover.h; sourceTree = ""; }; - 65B3609D121C261E003EAD18 /* glc_trackballmover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_trackballmover.cpp; sourceTree = ""; }; - 65B3609E121C261E003EAD18 /* glc_trackballmover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_trackballmover.h; sourceTree = ""; }; - 65B3609F121C261E003EAD18 /* glc_turntablemover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_turntablemover.cpp; sourceTree = ""; }; - 65B360A0121C261E003EAD18 /* glc_turntablemover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_turntablemover.h; sourceTree = ""; }; - 65B360A1121C261E003EAD18 /* glc_viewport.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_viewport.cpp; sourceTree = ""; }; - 65B360A2121C261E003EAD18 /* glc_viewport.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_viewport.h; sourceTree = ""; }; - 65B360A3121C261E003EAD18 /* glc_zoommover.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = glc_zoommover.cpp; sourceTree = ""; }; - 65B360A4121C261E003EAD18 /* glc_zoommover.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = glc_zoommover.h; sourceTree = ""; }; - 65B360A6121C261E003EAD18 /* AUTHORS */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = AUTHORS; sourceTree = ""; }; - 65B360A7121C261E003EAD18 /* cpl1.0.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = cpl1.0.txt; sourceTree = ""; }; - 65B360A8121C261E003EAD18 /* lgpl-2.1.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "lgpl-2.1.txt"; sourceTree = ""; }; - 65B360A9121C261E003EAD18 /* libqxt.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = libqxt.pri; sourceTree = ""; }; - 65B360AA121C261E003EAD18 /* libqxt.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = libqxt.pro; sourceTree = ""; }; - 65B360AB121C261E003EAD18 /* LICENSE */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = LICENSE; sourceTree = ""; }; - 65B360AC121C261E003EAD18 /* README */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = README; sourceTree = ""; }; - 65B360AF121C261E003EAD18 /* berkeley.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = berkeley.pri; sourceTree = ""; }; - 65B360B0121C261E003EAD18 /* berkeley.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = berkeley.pro; sourceTree = ""; }; - 65B360B1121C261E003EAD18 /* qxtbdb.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtbdb.cpp; sourceTree = ""; }; - 65B360B2121C261E003EAD18 /* qxtbdb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtbdb.h; sourceTree = ""; }; - 65B360B3121C261E003EAD18 /* qxtbdbhash.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtbdbhash.cpp; sourceTree = ""; }; - 65B360B4121C261E003EAD18 /* qxtbdbhash.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtbdbhash.h; sourceTree = ""; }; - 65B360B5121C261E003EAD18 /* qxtbdbtree.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtbdbtree.cpp; sourceTree = ""; }; - 65B360B6121C261E003EAD18 /* qxtbdbtree.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtbdbtree.h; sourceTree = ""; }; - 65B360B7121C261E003EAD18 /* qxtberkeley.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtberkeley.h; sourceTree = ""; }; - 65B360B9121C261E003EAD18 /* core.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = core.pri; sourceTree = ""; }; - 65B360BA121C261E003EAD18 /* core.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = core.pro; sourceTree = ""; }; - 65B360BC121C261E003EAD18 /* logengines.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = logengines.pri; sourceTree = ""; }; - 65B360BD121C261E003EAD18 /* qxtabstractfileloggerengine.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtabstractfileloggerengine.cpp; sourceTree = ""; }; - 65B360BE121C261E003EAD18 /* qxtabstractfileloggerengine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtabstractfileloggerengine.h; sourceTree = ""; }; - 65B360BF121C261E003EAD18 /* qxtabstractiologgerengine.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtabstractiologgerengine.cpp; sourceTree = ""; }; - 65B360C0121C261E003EAD18 /* qxtabstractiologgerengine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtabstractiologgerengine.h; sourceTree = ""; }; - 65B360C1121C261E003EAD18 /* qxtbasicfileloggerengine.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtbasicfileloggerengine.cpp; sourceTree = ""; }; - 65B360C2121C261E003EAD18 /* qxtbasicfileloggerengine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtbasicfileloggerengine.h; sourceTree = ""; }; - 65B360C3121C261E003EAD18 /* qxtbasicstdloggerengine.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtbasicstdloggerengine.cpp; sourceTree = ""; }; - 65B360C4121C261E003EAD18 /* qxtbasicstdloggerengine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtbasicstdloggerengine.h; sourceTree = ""; }; - 65B360C5121C261E003EAD18 /* qxtxmlfileloggerengine.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtxmlfileloggerengine.cpp; sourceTree = ""; }; - 65B360C6121C261E003EAD18 /* qxtxmlfileloggerengine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtxmlfileloggerengine.h; sourceTree = ""; }; - 65B360C7121C261E003EAD18 /* qxtabstractconnectionmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtabstractconnectionmanager.cpp; sourceTree = ""; }; - 65B360C8121C261E003EAD18 /* qxtabstractconnectionmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtabstractconnectionmanager.h; sourceTree = ""; }; - 65B360C9121C261E003EAD18 /* qxtabstractsignalserializer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtabstractsignalserializer.h; sourceTree = ""; }; - 65B360CA121C261E003EAD18 /* qxtalgorithms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtalgorithms.h; sourceTree = ""; }; - 65B360CB121C261E003EAD18 /* qxtboundcfunction.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtboundcfunction.h; sourceTree = ""; }; - 65B360CC121C261E003EAD18 /* qxtboundfunction.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtboundfunction.h; sourceTree = ""; }; - 65B360CD121C261E003EAD18 /* qxtboundfunctionbase.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtboundfunctionbase.h; sourceTree = ""; }; - 65B360CE121C261E003EAD18 /* qxtcommandoptions.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtcommandoptions.cpp; sourceTree = ""; }; - 65B360CF121C261E003EAD18 /* qxtcommandoptions.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcommandoptions.h; sourceTree = ""; }; - 65B360D0121C261E003EAD18 /* qxtcore.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcore.h; sourceTree = ""; }; - 65B360D1121C261E003EAD18 /* qxtcsvmodel.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtcsvmodel.cpp; sourceTree = ""; }; - 65B360D2121C261E003EAD18 /* qxtcsvmodel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcsvmodel.h; sourceTree = ""; }; - 65B360D3121C261E003EAD18 /* qxtdaemon.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtdaemon.cpp; sourceTree = ""; }; - 65B360D4121C261E003EAD18 /* qxtdaemon.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtdaemon.h; sourceTree = ""; }; - 65B360D5121C261E003EAD18 /* qxtdatastreamsignalserializer.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtdatastreamsignalserializer.cpp; sourceTree = ""; }; - 65B360D6121C261E003EAD18 /* qxtdatastreamsignalserializer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtdatastreamsignalserializer.h; sourceTree = ""; }; - 65B360D7121C261E003EAD18 /* qxtdeplex.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtdeplex.cpp; sourceTree = ""; }; - 65B360D8121C261E003EAD18 /* qxtdeplex.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtdeplex.h; sourceTree = ""; }; - 65B360D9121C261E003EAD18 /* qxtdeplex_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtdeplex_p.h; sourceTree = ""; }; - 65B360DA121C261E003EAD18 /* qxterror.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxterror.cpp; sourceTree = ""; }; - 65B360DB121C261E003EAD18 /* qxterror.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxterror.h; sourceTree = ""; }; - 65B360DC121C261E003EAD18 /* qxtfifo.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtfifo.cpp; sourceTree = ""; }; - 65B360DD121C261E003EAD18 /* qxtfifo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtfifo.h; sourceTree = ""; }; - 65B360DE121C261E003EAD18 /* qxtfilelock.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtfilelock.cpp; sourceTree = ""; }; - 65B360DF121C261E003EAD18 /* qxtfilelock.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtfilelock.h; sourceTree = ""; }; - 65B360E0121C261E003EAD18 /* qxtfilelock_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtfilelock_p.h; sourceTree = ""; }; - 65B360E1121C261E003EAD18 /* qxtfilelock_unix.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtfilelock_unix.cpp; sourceTree = ""; }; - 65B360E2121C261E003EAD18 /* qxtfilelock_win.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtfilelock_win.cpp; sourceTree = ""; }; - 65B360E3121C261E003EAD18 /* qxtglobal.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtglobal.cpp; sourceTree = ""; }; - 65B360E4121C261E003EAD18 /* qxtglobal.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtglobal.h; sourceTree = ""; }; - 65B360E5121C261E003EAD18 /* qxthmac.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxthmac.cpp; sourceTree = ""; }; - 65B360E6121C261E003EAD18 /* qxthmac.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxthmac.h; sourceTree = ""; }; - 65B360E7121C261E003EAD18 /* qxtjob.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtjob.cpp; sourceTree = ""; }; - 65B360E8121C261E003EAD18 /* qxtjob.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtjob.h; sourceTree = ""; }; - 65B360E9121C261E003EAD18 /* qxtjob_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtjob_p.h; sourceTree = ""; }; - 65B360EA121C261E003EAD18 /* qxtjson.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtjson.cpp; sourceTree = ""; }; - 65B360EB121C261E003EAD18 /* qxtjson.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtjson.h; sourceTree = ""; }; - 65B360EC121C261E003EAD18 /* qxtlinesocket.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlinesocket.cpp; sourceTree = ""; }; - 65B360ED121C261E003EAD18 /* qxtlinesocket.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlinesocket.h; sourceTree = ""; }; - 65B360EE121C261E003EAD18 /* qxtlinesocket_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlinesocket_p.h; sourceTree = ""; }; - 65B360EF121C261E003EAD18 /* qxtlinkedtree.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlinkedtree.cpp; sourceTree = ""; }; - 65B360F0121C261E003EAD18 /* qxtlinkedtree.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlinkedtree.h; sourceTree = ""; }; - 65B360F1121C261E003EAD18 /* qxtlocale.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlocale.cpp; sourceTree = ""; }; - 65B360F2121C261E003EAD18 /* qxtlocale.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlocale.h; sourceTree = ""; }; - 65B360F3121C261E003EAD18 /* qxtlocale_data_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlocale_data_p.h; sourceTree = ""; }; - 65B360F4121C261E003EAD18 /* qxtlogger.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlogger.cpp; sourceTree = ""; }; - 65B360F5121C261E003EAD18 /* qxtlogger.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlogger.h; sourceTree = ""; }; - 65B360F6121C261E003EAD18 /* qxtlogger_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlogger_p.h; sourceTree = ""; }; - 65B360F7121C261E003EAD18 /* qxtloggerengine.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtloggerengine.cpp; sourceTree = ""; }; - 65B360F8121C261E003EAD18 /* qxtloggerengine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtloggerengine.h; sourceTree = ""; }; - 65B360F9121C261E003EAD18 /* qxtlogstream.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlogstream.cpp; sourceTree = ""; }; - 65B360FA121C261E003EAD18 /* qxtlogstream.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlogstream.h; sourceTree = ""; }; - 65B360FB121C261E003EAD18 /* qxtlogstream_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlogstream_p.h; sourceTree = ""; }; - 65B360FC121C261E003EAD18 /* qxtmetaobject.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtmetaobject.cpp; sourceTree = ""; }; - 65B360FD121C261E003EAD18 /* qxtmetaobject.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtmetaobject.h; sourceTree = ""; }; - 65B360FE121C261E003EAD18 /* qxtmetatype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtmetatype.h; sourceTree = ""; }; - 65B360FF121C261E003EAD18 /* qxtmodelserializer.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtmodelserializer.cpp; sourceTree = ""; }; - 65B36100121C261E003EAD18 /* qxtmodelserializer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtmodelserializer.h; sourceTree = ""; }; - 65B36101121C261E003EAD18 /* qxtmultisignalwaiter.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtmultisignalwaiter.cpp; sourceTree = ""; }; - 65B36102121C261E003EAD18 /* qxtmultisignalwaiter.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtmultisignalwaiter.h; sourceTree = ""; }; - 65B36103121C261E003EAD18 /* qxtnamespace.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtnamespace.h; sourceTree = ""; }; - 65B36104121C261F003EAD18 /* qxtnull.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtnull.cpp; sourceTree = ""; }; - 65B36105121C261F003EAD18 /* qxtnull.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtnull.h; sourceTree = ""; }; - 65B36106121C261F003EAD18 /* qxtnullable.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtnullable.h; sourceTree = ""; }; - 65B36107121C261F003EAD18 /* qxtpairlist.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtpairlist.h; sourceTree = ""; }; - 65B36108121C261F003EAD18 /* qxtpimpl.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtpimpl.h; sourceTree = ""; }; - 65B36109121C261F003EAD18 /* qxtpipe.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtpipe.cpp; sourceTree = ""; }; - 65B3610A121C261F003EAD18 /* qxtpipe.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtpipe.h; sourceTree = ""; }; - 65B3610B121C261F003EAD18 /* qxtpipe_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtpipe_p.h; sourceTree = ""; }; - 65B3610C121C261F003EAD18 /* qxtpointerlist.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtpointerlist.cpp; sourceTree = ""; }; - 65B3610D121C261F003EAD18 /* qxtpointerlist.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtpointerlist.h; sourceTree = ""; }; - 65B3610E121C261F003EAD18 /* qxtrpcservice.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtrpcservice.cpp; sourceTree = ""; }; - 65B3610F121C261F003EAD18 /* qxtrpcservice.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtrpcservice.h; sourceTree = ""; }; - 65B36110121C261F003EAD18 /* qxtrpcservice_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtrpcservice_p.h; sourceTree = ""; }; - 65B36111121C261F003EAD18 /* qxtserialdevice.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtserialdevice.cpp; sourceTree = ""; }; - 65B36112121C261F003EAD18 /* qxtserialdevice.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtserialdevice.h; sourceTree = ""; }; - 65B36113121C261F003EAD18 /* qxtserialdevice_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtserialdevice_p.h; sourceTree = ""; }; - 65B36114121C261F003EAD18 /* qxtserialdevice_unix.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtserialdevice_unix.cpp; sourceTree = ""; }; - 65B36115121C261F003EAD18 /* qxtsharedprivate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtsharedprivate.h; sourceTree = ""; }; - 65B36116121C261F003EAD18 /* qxtsignalgroup.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtsignalgroup.cpp; sourceTree = ""; }; - 65B36117121C261F003EAD18 /* qxtsignalgroup.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtsignalgroup.h; sourceTree = ""; }; - 65B36118121C261F003EAD18 /* qxtsignalwaiter.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtsignalwaiter.cpp; sourceTree = ""; }; - 65B36119121C261F003EAD18 /* qxtsignalwaiter.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtsignalwaiter.h; sourceTree = ""; }; - 65B3611A121C261F003EAD18 /* qxtslotjob.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtslotjob.cpp; sourceTree = ""; }; - 65B3611B121C261F003EAD18 /* qxtslotjob.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtslotjob.h; sourceTree = ""; }; - 65B3611C121C261F003EAD18 /* qxtslotjob_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtslotjob_p.h; sourceTree = ""; }; - 65B3611D121C261F003EAD18 /* qxtslotmapper.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtslotmapper.cpp; sourceTree = ""; }; - 65B3611E121C261F003EAD18 /* qxtslotmapper.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtslotmapper.h; sourceTree = ""; }; - 65B3611F121C261F003EAD18 /* qxtstdio.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtstdio.cpp; sourceTree = ""; }; - 65B36120121C261F003EAD18 /* qxtstdio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstdio.h; sourceTree = ""; }; - 65B36121121C261F003EAD18 /* qxtstdio_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstdio_p.h; sourceTree = ""; }; - 65B36122121C261F003EAD18 /* qxtstdstreambufdevice.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtstdstreambufdevice.cpp; sourceTree = ""; }; - 65B36123121C261F003EAD18 /* qxtstdstreambufdevice.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstdstreambufdevice.h; sourceTree = ""; }; - 65B36124121C261F003EAD18 /* qxttimer.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxttimer.cpp; sourceTree = ""; }; - 65B36125121C261F003EAD18 /* qxttimer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttimer.h; sourceTree = ""; }; - 65B36126121C261F003EAD18 /* qxttypelist.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttypelist.h; sourceTree = ""; }; - 65B36128121C261F003EAD18 /* designer.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = designer.pri; sourceTree = ""; }; - 65B36129121C261F003EAD18 /* designer.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = designer.pro; sourceTree = ""; }; - 65B3612A121C261F003EAD18 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65B3612B121C261F003EAD18 /* qxtbasespinboxplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtbasespinboxplugin.cpp; sourceTree = ""; }; - 65B3612C121C261F003EAD18 /* qxtbasespinboxplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtbasespinboxplugin.h; sourceTree = ""; }; - 65B3612D121C261F003EAD18 /* qxtcheckcomboboxplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtcheckcomboboxplugin.cpp; sourceTree = ""; }; - 65B3612E121C261F003EAD18 /* qxtcheckcomboboxplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcheckcomboboxplugin.h; sourceTree = ""; }; - 65B3612F121C261F003EAD18 /* qxtcountrycomboboxplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtcountrycomboboxplugin.cpp; sourceTree = ""; }; - 65B36130121C261F003EAD18 /* qxtcountrycomboboxplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcountrycomboboxplugin.h; sourceTree = ""; }; - 65B36131121C261F003EAD18 /* qxtdesignerplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtdesignerplugin.cpp; sourceTree = ""; }; - 65B36132121C261F003EAD18 /* qxtdesignerplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtdesignerplugin.h; sourceTree = ""; }; - 65B36133121C261F003EAD18 /* qxtdesignerplugins.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtdesignerplugins.cpp; sourceTree = ""; }; - 65B36134121C261F003EAD18 /* qxtdesignerplugins.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtdesignerplugins.h; sourceTree = ""; }; - 65B36135121C261F003EAD18 /* qxtflowviewplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtflowviewplugin.cpp; sourceTree = ""; }; - 65B36136121C261F003EAD18 /* qxtflowviewplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtflowviewplugin.h; sourceTree = ""; }; - 65B36137121C261F003EAD18 /* qxtgroupboxplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtgroupboxplugin.cpp; sourceTree = ""; }; - 65B36138121C261F003EAD18 /* qxtgroupboxplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtgroupboxplugin.h; sourceTree = ""; }; - 65B36139121C261F003EAD18 /* qxtlabelplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlabelplugin.cpp; sourceTree = ""; }; - 65B3613A121C261F003EAD18 /* qxtlabelplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlabelplugin.h; sourceTree = ""; }; - 65B3613B121C261F003EAD18 /* qxtlanguagecomboboxplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlanguagecomboboxplugin.cpp; sourceTree = ""; }; - 65B3613C121C261F003EAD18 /* qxtlanguagecomboboxplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlanguagecomboboxplugin.h; sourceTree = ""; }; - 65B3613D121C261F003EAD18 /* qxtletterboxwidgetplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtletterboxwidgetplugin.cpp; sourceTree = ""; }; - 65B3613E121C261F003EAD18 /* qxtletterboxwidgetplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtletterboxwidgetplugin.h; sourceTree = ""; }; - 65B3613F121C261F003EAD18 /* qxtlineeditplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlineeditplugin.cpp; sourceTree = ""; }; - 65B36140121C261F003EAD18 /* qxtlineeditplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlineeditplugin.h; sourceTree = ""; }; - 65B36141121C261F003EAD18 /* qxtlistwidgetplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlistwidgetplugin.cpp; sourceTree = ""; }; - 65B36142121C261F003EAD18 /* qxtlistwidgetplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlistwidgetplugin.h; sourceTree = ""; }; - 65B36143121C261F003EAD18 /* qxtprogresslabelplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtprogresslabelplugin.cpp; sourceTree = ""; }; - 65B36144121C261F003EAD18 /* qxtprogresslabelplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtprogresslabelplugin.h; sourceTree = ""; }; - 65B36145121C261F003EAD18 /* qxtpushbuttonplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtpushbuttonplugin.cpp; sourceTree = ""; }; - 65B36146121C261F003EAD18 /* qxtpushbuttonplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtpushbuttonplugin.h; sourceTree = ""; }; - 65B36147121C261F003EAD18 /* qxtspansliderplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtspansliderplugin.cpp; sourceTree = ""; }; - 65B36148121C261F003EAD18 /* qxtspansliderplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtspansliderplugin.h; sourceTree = ""; }; - 65B36149121C261F003EAD18 /* qxtstarsplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtstarsplugin.cpp; sourceTree = ""; }; - 65B3614A121C261F003EAD18 /* qxtstarsplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstarsplugin.h; sourceTree = ""; }; - 65B3614B121C261F003EAD18 /* qxtstringspinboxplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtstringspinboxplugin.cpp; sourceTree = ""; }; - 65B3614C121C261F003EAD18 /* qxtstringspinboxplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstringspinboxplugin.h; sourceTree = ""; }; - 65B3614D121C261F003EAD18 /* qxttablewidgetplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxttablewidgetplugin.cpp; sourceTree = ""; }; - 65B3614E121C261F003EAD18 /* qxttablewidgetplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttablewidgetplugin.h; sourceTree = ""; }; - 65B3614F121C261F003EAD18 /* qxttreewidgetplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxttreewidgetplugin.cpp; sourceTree = ""; }; - 65B36150121C261F003EAD18 /* qxttreewidgetplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttreewidgetplugin.h; sourceTree = ""; }; - 65B36151121C261F003EAD18 /* resources.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = resources.qrc; sourceTree = ""; }; - 65B36153121C261F003EAD18 /* gui.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = gui.pri; sourceTree = ""; }; - 65B36154121C261F003EAD18 /* gui.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = gui.pro; sourceTree = ""; }; - 65B36155121C261F003EAD18 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65B36156121C261F003EAD18 /* qxtapplication.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtapplication.cpp; sourceTree = ""; }; - 65B36157121C261F003EAD18 /* qxtapplication.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtapplication.h; sourceTree = ""; }; - 65B36158121C261F003EAD18 /* qxtapplication_mac.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtapplication_mac.cpp; sourceTree = ""; }; - 65B36159121C261F003EAD18 /* qxtapplication_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtapplication_p.h; sourceTree = ""; }; - 65B3615A121C261F003EAD18 /* qxtapplication_win.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtapplication_win.cpp; sourceTree = ""; }; - 65B3615B121C261F003EAD18 /* qxtapplication_x11.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtapplication_x11.cpp; sourceTree = ""; }; - 65B3615C121C261F003EAD18 /* qxtbasespinbox.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtbasespinbox.cpp; sourceTree = ""; }; - 65B3615D121C261F003EAD18 /* qxtbasespinbox.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtbasespinbox.h; sourceTree = ""; }; - 65B3615E121C261F003EAD18 /* qxtcheckcombobox.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtcheckcombobox.cpp; sourceTree = ""; }; - 65B3615F121C261F003EAD18 /* qxtcheckcombobox.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcheckcombobox.h; sourceTree = ""; }; - 65B36160121C261F003EAD18 /* qxtcheckcombobox_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcheckcombobox_p.h; sourceTree = ""; }; - 65B36161121C261F003EAD18 /* qxtconfigdialog.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtconfigdialog.cpp; sourceTree = ""; }; - 65B36162121C261F003EAD18 /* qxtconfigdialog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtconfigdialog.h; sourceTree = ""; }; - 65B36163121C261F003EAD18 /* qxtconfigdialog_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtconfigdialog_p.h; sourceTree = ""; }; - 65B36164121C261F003EAD18 /* qxtconfigwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtconfigwidget.cpp; sourceTree = ""; }; - 65B36165121C261F003EAD18 /* qxtconfigwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtconfigwidget.h; sourceTree = ""; }; - 65B36166121C261F003EAD18 /* qxtconfigwidget_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtconfigwidget_p.h; sourceTree = ""; }; - 65B36167121C261F003EAD18 /* qxtconfirmationmessage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtconfirmationmessage.cpp; sourceTree = ""; }; - 65B36168121C261F003EAD18 /* qxtconfirmationmessage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtconfirmationmessage.h; sourceTree = ""; }; - 65B36169121C261F003EAD18 /* qxtcountrycombobox.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtcountrycombobox.cpp; sourceTree = ""; }; - 65B3616A121C261F003EAD18 /* qxtcountrycombobox.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcountrycombobox.h; sourceTree = ""; }; - 65B3616B121C261F003EAD18 /* qxtcountrycombobox_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcountrycombobox_p.h; sourceTree = ""; }; - 65B3616C121C261F003EAD18 /* qxtcountrymodel.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtcountrymodel.cpp; sourceTree = ""; }; - 65B3616D121C261F003EAD18 /* qxtcountrymodel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcountrymodel.h; sourceTree = ""; }; - 65B3616E121C261F003EAD18 /* qxtcountrymodel_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcountrymodel_p.h; sourceTree = ""; }; - 65B3616F121C261F003EAD18 /* qxtcrumbview.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtcrumbview.cpp; sourceTree = ""; }; - 65B36170121C261F003EAD18 /* qxtcrumbview.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcrumbview.h; sourceTree = ""; }; - 65B36171121C261F003EAD18 /* qxtcrumbview_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtcrumbview_p.h; sourceTree = ""; }; - 65B36172121C261F003EAD18 /* qxtfilterdialog.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtfilterdialog.cpp; sourceTree = ""; }; - 65B36173121C261F003EAD18 /* qxtfilterdialog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtfilterdialog.h; sourceTree = ""; }; - 65B36174121C261F003EAD18 /* qxtfilterdialog_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtfilterdialog_p.h; sourceTree = ""; }; - 65B36175121C261F003EAD18 /* qxtflowview.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtflowview.cpp; sourceTree = ""; }; - 65B36176121C261F003EAD18 /* qxtflowview.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtflowview.h; sourceTree = ""; }; - 65B36177121C261F003EAD18 /* qxtflowview_p.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtflowview_p.cpp; sourceTree = ""; }; - 65B36178121C261F003EAD18 /* qxtflowview_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtflowview_p.h; sourceTree = ""; }; - 65B36179121C261F003EAD18 /* qxtglobalshortcut.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtglobalshortcut.cpp; sourceTree = ""; }; - 65B3617A121C261F003EAD18 /* qxtglobalshortcut.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtglobalshortcut.h; sourceTree = ""; }; - 65B3617B121C261F003EAD18 /* qxtglobalshortcut_mac.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtglobalshortcut_mac.cpp; sourceTree = ""; }; - 65B3617C121C261F003EAD18 /* qxtglobalshortcut_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtglobalshortcut_p.h; sourceTree = ""; }; - 65B3617D121C261F003EAD18 /* qxtglobalshortcut_win.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtglobalshortcut_win.cpp; sourceTree = ""; }; - 65B3617E121C261F003EAD18 /* qxtglobalshortcut_x11.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtglobalshortcut_x11.cpp; sourceTree = ""; }; - 65B3617F121C261F003EAD18 /* qxtgroupbox.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtgroupbox.cpp; sourceTree = ""; }; - 65B36180121C261F003EAD18 /* qxtgroupbox.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtgroupbox.h; sourceTree = ""; }; - 65B36181121C261F003EAD18 /* qxtgui.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtgui.h; sourceTree = ""; }; - 65B36182121C261F003EAD18 /* qxtheaderview.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtheaderview.cpp; sourceTree = ""; }; - 65B36183121C261F003EAD18 /* qxtheaderview.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtheaderview.h; sourceTree = ""; }; - 65B36184121C261F003EAD18 /* qxtitemdelegate.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtitemdelegate.cpp; sourceTree = ""; }; - 65B36185121C261F003EAD18 /* qxtitemdelegate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtitemdelegate.h; sourceTree = ""; }; - 65B36186121C261F003EAD18 /* qxtitemdelegate_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtitemdelegate_p.h; sourceTree = ""; }; - 65B36187121C261F003EAD18 /* qxtitemeditorcreator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtitemeditorcreator.h; sourceTree = ""; }; - 65B36188121C261F003EAD18 /* qxtitemeditorcreatorbase.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtitemeditorcreatorbase.h; sourceTree = ""; }; - 65B36189121C261F003EAD18 /* qxtlabel.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlabel.cpp; sourceTree = ""; }; - 65B3618A121C261F003EAD18 /* qxtlabel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlabel.h; sourceTree = ""; }; - 65B3618B121C261F003EAD18 /* qxtlanguagecombobox.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlanguagecombobox.cpp; sourceTree = ""; }; - 65B3618C121C261F003EAD18 /* qxtlanguagecombobox.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlanguagecombobox.h; sourceTree = ""; }; - 65B3618D121C261F003EAD18 /* qxtlanguagecombobox_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlanguagecombobox_p.h; sourceTree = ""; }; - 65B3618E121C261F003EAD18 /* qxtletterboxwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtletterboxwidget.cpp; sourceTree = ""; }; - 65B3618F121C261F003EAD18 /* qxtletterboxwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtletterboxwidget.h; sourceTree = ""; }; - 65B36190121C261F003EAD18 /* qxtletterboxwidget_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtletterboxwidget_p.h; sourceTree = ""; }; - 65B36191121C261F003EAD18 /* qxtlineedit.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlineedit.cpp; sourceTree = ""; }; - 65B36192121C261F003EAD18 /* qxtlineedit.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlineedit.h; sourceTree = ""; }; - 65B36193121C261F003EAD18 /* qxtlistwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlistwidget.cpp; sourceTree = ""; }; - 65B36194121C261F003EAD18 /* qxtlistwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlistwidget.h; sourceTree = ""; }; - 65B36195121C261F003EAD18 /* qxtlistwidget_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlistwidget_p.h; sourceTree = ""; }; - 65B36196121C261F003EAD18 /* qxtlistwidgetitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlistwidgetitem.cpp; sourceTree = ""; }; - 65B36197121C261F003EAD18 /* qxtlistwidgetitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlistwidgetitem.h; sourceTree = ""; }; - 65B36198121C261F003EAD18 /* qxtlookuplineedit.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtlookuplineedit.cpp; sourceTree = ""; }; - 65B36199121C261F003EAD18 /* qxtlookuplineedit.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlookuplineedit.h; sourceTree = ""; }; - 65B3619A121C261F003EAD18 /* qxtlookuplineedit_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtlookuplineedit_p.h; sourceTree = ""; }; - 65B3619B121C261F003EAD18 /* qxtnativeeventfilter.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtnativeeventfilter.h; sourceTree = ""; }; - 65B3619C121C261F003EAD18 /* qxtprogresslabel.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtprogresslabel.cpp; sourceTree = ""; }; - 65B3619D121C261F003EAD18 /* qxtprogresslabel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtprogresslabel.h; sourceTree = ""; }; - 65B3619E121C261F003EAD18 /* qxtproxystyle.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtproxystyle.cpp; sourceTree = ""; }; - 65B3619F121C261F003EAD18 /* qxtproxystyle.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtproxystyle.h; sourceTree = ""; }; - 65B361A0121C261F003EAD18 /* qxtpushbutton.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtpushbutton.cpp; sourceTree = ""; }; - 65B361A1121C261F003EAD18 /* qxtpushbutton.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtpushbutton.h; sourceTree = ""; }; - 65B361A2121C261F003EAD18 /* qxtscheduleheaderwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtscheduleheaderwidget.cpp; sourceTree = ""; }; - 65B361A3121C261F003EAD18 /* qxtscheduleheaderwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtscheduleheaderwidget.h; sourceTree = ""; }; - 65B361A4121C261F003EAD18 /* qxtscheduleitemdelegate.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtscheduleitemdelegate.cpp; sourceTree = ""; }; - 65B361A5121C261F003EAD18 /* qxtscheduleitemdelegate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtscheduleitemdelegate.h; sourceTree = ""; }; - 65B361A6121C261F003EAD18 /* qxtscheduleview.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtscheduleview.cpp; sourceTree = ""; }; - 65B361A7121C261F003EAD18 /* qxtscheduleview.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtscheduleview.h; sourceTree = ""; }; - 65B361A8121C261F003EAD18 /* qxtscheduleview_p.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtscheduleview_p.cpp; sourceTree = ""; }; - 65B361A9121C261F003EAD18 /* qxtscheduleview_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtscheduleview_p.h; sourceTree = ""; }; - 65B361AA121C261F003EAD18 /* qxtscheduleviewheadermodel_p.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtscheduleviewheadermodel_p.cpp; sourceTree = ""; }; - 65B361AB121C261F003EAD18 /* qxtscheduleviewheadermodel_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtscheduleviewheadermodel_p.h; sourceTree = ""; }; - 65B361AC121C261F003EAD18 /* qxtscreen.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtscreen.cpp; sourceTree = ""; }; - 65B361AD121C261F003EAD18 /* qxtscreen.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtscreen.h; sourceTree = ""; }; - 65B361AE121C261F003EAD18 /* qxtscreen_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtscreen_p.h; sourceTree = ""; }; - 65B361AF121C261F003EAD18 /* qxtscreen_win.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtscreen_win.cpp; sourceTree = ""; }; - 65B361B0121C261F003EAD18 /* qxtscreen_x11.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtscreen_x11.cpp; sourceTree = ""; }; - 65B361B1121C261F003EAD18 /* qxtsortfilterproxymodel.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtsortfilterproxymodel.cpp; sourceTree = ""; }; - 65B361B2121C261F003EAD18 /* qxtsortfilterproxymodel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtsortfilterproxymodel.h; sourceTree = ""; }; - 65B361B3121C261F003EAD18 /* qxtspanslider.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtspanslider.cpp; sourceTree = ""; }; - 65B361B4121C261F003EAD18 /* qxtspanslider.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtspanslider.h; sourceTree = ""; }; - 65B361B5121C261F003EAD18 /* qxtspanslider_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtspanslider_p.h; sourceTree = ""; }; - 65B361B6121C261F003EAD18 /* qxtstandarditemeditorcreator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstandarditemeditorcreator.h; sourceTree = ""; }; - 65B361B7121C261F003EAD18 /* qxtstars.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtstars.cpp; sourceTree = ""; }; - 65B361B8121C261F003EAD18 /* qxtstars.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstars.h; sourceTree = ""; }; - 65B361B9121C261F003EAD18 /* qxtstringspinbox.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtstringspinbox.cpp; sourceTree = ""; }; - 65B361BA121C261F003EAD18 /* qxtstringspinbox.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstringspinbox.h; sourceTree = ""; }; - 65B361BB121C261F003EAD18 /* qxtstringvalidator.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtstringvalidator.cpp; sourceTree = ""; }; - 65B361BC121C261F003EAD18 /* qxtstringvalidator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstringvalidator.h; sourceTree = ""; }; - 65B361BD121C261F003EAD18 /* qxtstringvalidator_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstringvalidator_p.h; sourceTree = ""; }; - 65B361BE121C261F003EAD18 /* qxtstyleoptionscheduleviewitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtstyleoptionscheduleviewitem.cpp; sourceTree = ""; }; - 65B361BF121C261F003EAD18 /* qxtstyleoptionscheduleviewitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtstyleoptionscheduleviewitem.h; sourceTree = ""; }; - 65B361C0121C261F003EAD18 /* qxttablewidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxttablewidget.cpp; sourceTree = ""; }; - 65B361C1121C261F003EAD18 /* qxttablewidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttablewidget.h; sourceTree = ""; }; - 65B361C2121C261F003EAD18 /* qxttablewidget_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttablewidget_p.h; sourceTree = ""; }; - 65B361C3121C261F003EAD18 /* qxttablewidgetitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxttablewidgetitem.cpp; sourceTree = ""; }; - 65B361C4121C261F003EAD18 /* qxttablewidgetitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttablewidgetitem.h; sourceTree = ""; }; - 65B361C5121C261F003EAD18 /* qxttabwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxttabwidget.cpp; sourceTree = ""; }; - 65B361C6121C261F003EAD18 /* qxttabwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttabwidget.h; sourceTree = ""; }; - 65B361C7121C261F003EAD18 /* qxttabwidget_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttabwidget_p.h; sourceTree = ""; }; - 65B361C8121C261F003EAD18 /* qxttooltip.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxttooltip.cpp; sourceTree = ""; }; - 65B361C9121C261F003EAD18 /* qxttooltip.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttooltip.h; sourceTree = ""; }; - 65B361CA121C261F003EAD18 /* qxttooltip_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttooltip_p.h; sourceTree = ""; }; - 65B361CB121C261F003EAD18 /* qxttreewidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxttreewidget.cpp; sourceTree = ""; }; - 65B361CC121C261F003EAD18 /* qxttreewidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttreewidget.h; sourceTree = ""; }; - 65B361CD121C261F003EAD18 /* qxttreewidget_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttreewidget_p.h; sourceTree = ""; }; - 65B361CE121C261F003EAD18 /* qxttreewidgetitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxttreewidgetitem.cpp; sourceTree = ""; }; - 65B361CF121C261F003EAD18 /* qxttreewidgetitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttreewidgetitem.h; sourceTree = ""; }; - 65B361D0121C261F003EAD18 /* qxtwindowsystem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtwindowsystem.cpp; sourceTree = ""; }; - 65B361D1121C261F003EAD18 /* qxtwindowsystem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtwindowsystem.h; sourceTree = ""; }; - 65B361D2121C261F003EAD18 /* qxtwindowsystem_win.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtwindowsystem_win.cpp; sourceTree = ""; }; - 65B361D3121C261F003EAD18 /* qxtwindowsystem_x11.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtwindowsystem_x11.cpp; sourceTree = ""; }; - 65B361D6121C261F003EAD18 /* AD.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AD.png; sourceTree = ""; }; - 65B361D7121C261F003EAD18 /* AE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AE.png; sourceTree = ""; }; - 65B361D8121C261F003EAD18 /* AF.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AF.png; sourceTree = ""; }; - 65B361D9121C261F003EAD18 /* AG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AG.png; sourceTree = ""; }; - 65B361DA121C261F003EAD18 /* AI.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AI.png; sourceTree = ""; }; - 65B361DB121C261F003EAD18 /* AL.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AL.png; sourceTree = ""; }; - 65B361DC121C261F003EAD18 /* AM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AM.png; sourceTree = ""; }; - 65B361DD121C261F003EAD18 /* AN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AN.png; sourceTree = ""; }; - 65B361DE121C261F003EAD18 /* AO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AO.png; sourceTree = ""; }; - 65B361DF121C261F003EAD18 /* AQ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AQ.png; sourceTree = ""; }; - 65B361E0121C261F003EAD18 /* AR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AR.png; sourceTree = ""; }; - 65B361E1121C261F003EAD18 /* AS.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AS.png; sourceTree = ""; }; - 65B361E2121C261F003EAD18 /* AT.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AT.png; sourceTree = ""; }; - 65B361E3121C261F003EAD18 /* AU.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AU.png; sourceTree = ""; }; - 65B361E4121C261F003EAD18 /* AW.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AW.png; sourceTree = ""; }; - 65B361E5121C261F003EAD18 /* AX.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AX.png; sourceTree = ""; }; - 65B361E6121C261F003EAD18 /* AZ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = AZ.png; sourceTree = ""; }; - 65B361E7121C261F003EAD18 /* BA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BA.png; sourceTree = ""; }; - 65B361E8121C261F003EAD18 /* BB.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BB.png; sourceTree = ""; }; - 65B361E9121C261F003EAD18 /* BD.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BD.png; sourceTree = ""; }; - 65B361EA121C261F003EAD18 /* BE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BE.png; sourceTree = ""; }; - 65B361EB121C261F003EAD18 /* BF.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BF.png; sourceTree = ""; }; - 65B361EC121C261F003EAD18 /* BG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BG.png; sourceTree = ""; }; - 65B361ED121C261F003EAD18 /* BH.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BH.png; sourceTree = ""; }; - 65B361EE121C261F003EAD18 /* BI.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BI.png; sourceTree = ""; }; - 65B361EF121C261F003EAD18 /* BJ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BJ.png; sourceTree = ""; }; - 65B361F0121C261F003EAD18 /* BM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BM.png; sourceTree = ""; }; - 65B361F1121C261F003EAD18 /* BN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BN.png; sourceTree = ""; }; - 65B361F2121C261F003EAD18 /* BO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BO.png; sourceTree = ""; }; - 65B361F3121C261F003EAD18 /* BR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BR.png; sourceTree = ""; }; - 65B361F4121C261F003EAD18 /* BS.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BS.png; sourceTree = ""; }; - 65B361F5121C261F003EAD18 /* BT.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BT.png; sourceTree = ""; }; - 65B361F6121C261F003EAD18 /* BV.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BV.png; sourceTree = ""; }; - 65B361F7121C261F003EAD18 /* BW.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BW.png; sourceTree = ""; }; - 65B361F8121C261F003EAD18 /* BY.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BY.png; sourceTree = ""; }; - 65B361F9121C261F003EAD18 /* BZ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = BZ.png; sourceTree = ""; }; - 65B361FA121C261F003EAD18 /* C.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = C.png; sourceTree = ""; }; - 65B361FB121C261F003EAD18 /* CA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CA.png; sourceTree = ""; }; - 65B361FC121C261F003EAD18 /* CC.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CC.png; sourceTree = ""; }; - 65B361FD121C261F003EAD18 /* CD.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CD.png; sourceTree = ""; }; - 65B361FE121C261F003EAD18 /* CF.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CF.png; sourceTree = ""; }; - 65B361FF121C261F003EAD18 /* CG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CG.png; sourceTree = ""; }; - 65B36200121C261F003EAD18 /* CH.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CH.png; sourceTree = ""; }; - 65B36201121C261F003EAD18 /* CI.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CI.png; sourceTree = ""; }; - 65B36202121C261F003EAD18 /* CK.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CK.png; sourceTree = ""; }; - 65B36203121C261F003EAD18 /* CL.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CL.png; sourceTree = ""; }; - 65B36204121C261F003EAD18 /* CM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CM.png; sourceTree = ""; }; - 65B36205121C261F003EAD18 /* CN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CN.png; sourceTree = ""; }; - 65B36206121C261F003EAD18 /* CO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CO.png; sourceTree = ""; }; - 65B36207121C261F003EAD18 /* CR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CR.png; sourceTree = ""; }; - 65B36208121C261F003EAD18 /* CS.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CS.png; sourceTree = ""; }; - 65B36209121C261F003EAD18 /* CU.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CU.png; sourceTree = ""; }; - 65B3620A121C261F003EAD18 /* CV.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CV.png; sourceTree = ""; }; - 65B3620B121C261F003EAD18 /* CX.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CX.png; sourceTree = ""; }; - 65B3620C121C261F003EAD18 /* CY.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CY.png; sourceTree = ""; }; - 65B3620D121C261F003EAD18 /* CZ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = CZ.png; sourceTree = ""; }; - 65B3620E121C261F003EAD18 /* DE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = DE.png; sourceTree = ""; }; - 65B3620F121C261F003EAD18 /* DJ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = DJ.png; sourceTree = ""; }; - 65B36210121C261F003EAD18 /* DK.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = DK.png; sourceTree = ""; }; - 65B36211121C261F003EAD18 /* DM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = DM.png; sourceTree = ""; }; - 65B36212121C261F003EAD18 /* DO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = DO.png; sourceTree = ""; }; - 65B36213121C261F003EAD18 /* DZ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = DZ.png; sourceTree = ""; }; - 65B36214121C261F003EAD18 /* EC.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = EC.png; sourceTree = ""; }; - 65B36215121C261F003EAD18 /* EE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = EE.png; sourceTree = ""; }; - 65B36216121C261F003EAD18 /* EG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = EG.png; sourceTree = ""; }; - 65B36217121C261F003EAD18 /* EH.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = EH.png; sourceTree = ""; }; - 65B36218121C261F003EAD18 /* ER.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ER.png; sourceTree = ""; }; - 65B36219121C261F003EAD18 /* ES.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ES.png; sourceTree = ""; }; - 65B3621A121C261F003EAD18 /* ET.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ET.png; sourceTree = ""; }; - 65B3621B121C261F003EAD18 /* FI.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = FI.png; sourceTree = ""; }; - 65B3621C121C261F003EAD18 /* FJ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = FJ.png; sourceTree = ""; }; - 65B3621D121C261F003EAD18 /* FK.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = FK.png; sourceTree = ""; }; - 65B3621E121C261F003EAD18 /* FM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = FM.png; sourceTree = ""; }; - 65B3621F121C261F003EAD18 /* FO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = FO.png; sourceTree = ""; }; - 65B36220121C261F003EAD18 /* FR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = FR.png; sourceTree = ""; }; - 65B36221121C261F003EAD18 /* FX.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = FX.png; sourceTree = ""; }; - 65B36222121C261F003EAD18 /* GA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GA.png; sourceTree = ""; }; - 65B36223121C261F003EAD18 /* GB.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GB.png; sourceTree = ""; }; - 65B36224121C261F003EAD18 /* GD.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GD.png; sourceTree = ""; }; - 65B36225121C261F003EAD18 /* GE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GE.png; sourceTree = ""; }; - 65B36226121C261F003EAD18 /* GF.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GF.png; sourceTree = ""; }; - 65B36227121C261F003EAD18 /* GG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GG.png; sourceTree = ""; }; - 65B36228121C261F003EAD18 /* GH.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GH.png; sourceTree = ""; }; - 65B36229121C261F003EAD18 /* GI.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GI.png; sourceTree = ""; }; - 65B3622A121C261F003EAD18 /* GL.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GL.png; sourceTree = ""; }; - 65B3622B121C261F003EAD18 /* GM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GM.png; sourceTree = ""; }; - 65B3622C121C261F003EAD18 /* GN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GN.png; sourceTree = ""; }; - 65B3622D121C261F003EAD18 /* GP.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GP.png; sourceTree = ""; }; - 65B3622E121C261F003EAD18 /* GQ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GQ.png; sourceTree = ""; }; - 65B3622F121C261F003EAD18 /* GR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GR.png; sourceTree = ""; }; - 65B36230121C261F003EAD18 /* GS.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GS.png; sourceTree = ""; }; - 65B36231121C261F003EAD18 /* GT.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GT.png; sourceTree = ""; }; - 65B36232121C261F003EAD18 /* GU.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GU.png; sourceTree = ""; }; - 65B36233121C261F003EAD18 /* GW.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GW.png; sourceTree = ""; }; - 65B36234121C261F003EAD18 /* GY.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = GY.png; sourceTree = ""; }; - 65B36235121C261F003EAD18 /* HK.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = HK.png; sourceTree = ""; }; - 65B36236121C261F003EAD18 /* HM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = HM.png; sourceTree = ""; }; - 65B36237121C261F003EAD18 /* HN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = HN.png; sourceTree = ""; }; - 65B36238121C261F003EAD18 /* HR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = HR.png; sourceTree = ""; }; - 65B36239121C261F003EAD18 /* HT.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = HT.png; sourceTree = ""; }; - 65B3623A121C261F003EAD18 /* HU.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = HU.png; sourceTree = ""; }; - 65B3623B121C261F003EAD18 /* ID.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ID.png; sourceTree = ""; }; - 65B3623C121C261F003EAD18 /* IE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = IE.png; sourceTree = ""; }; - 65B3623D121C261F003EAD18 /* IL.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = IL.png; sourceTree = ""; }; - 65B3623E121C261F003EAD18 /* IM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = IM.png; sourceTree = ""; }; - 65B3623F121C261F003EAD18 /* IN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = IN.png; sourceTree = ""; }; - 65B36240121C261F003EAD18 /* IO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = IO.png; sourceTree = ""; }; - 65B36241121C261F003EAD18 /* IQ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = IQ.png; sourceTree = ""; }; - 65B36242121C261F003EAD18 /* IR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = IR.png; sourceTree = ""; }; - 65B36243121C261F003EAD18 /* IS.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = IS.png; sourceTree = ""; }; - 65B36244121C261F003EAD18 /* IT.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = IT.png; sourceTree = ""; }; - 65B36245121C261F003EAD18 /* JE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = JE.png; sourceTree = ""; }; - 65B36246121C261F003EAD18 /* JM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = JM.png; sourceTree = ""; }; - 65B36247121C261F003EAD18 /* JO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = JO.png; sourceTree = ""; }; - 65B36248121C261F003EAD18 /* JP.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = JP.png; sourceTree = ""; }; - 65B36249121C261F003EAD18 /* KE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KE.png; sourceTree = ""; }; - 65B3624A121C261F003EAD18 /* KG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KG.png; sourceTree = ""; }; - 65B3624B121C261F003EAD18 /* KH.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KH.png; sourceTree = ""; }; - 65B3624C121C261F003EAD18 /* KI.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KI.png; sourceTree = ""; }; - 65B3624D121C261F003EAD18 /* KM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KM.png; sourceTree = ""; }; - 65B3624E121C261F003EAD18 /* KN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KN.png; sourceTree = ""; }; - 65B3624F121C261F003EAD18 /* KP.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KP.png; sourceTree = ""; }; - 65B36250121C261F003EAD18 /* KR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KR.png; sourceTree = ""; }; - 65B36251121C261F003EAD18 /* KW.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KW.png; sourceTree = ""; }; - 65B36252121C261F003EAD18 /* KY.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KY.png; sourceTree = ""; }; - 65B36253121C261F003EAD18 /* KZ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = KZ.png; sourceTree = ""; }; - 65B36254121C261F003EAD18 /* LA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LA.png; sourceTree = ""; }; - 65B36255121C261F003EAD18 /* LB.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LB.png; sourceTree = ""; }; - 65B36256121C261F003EAD18 /* LC.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LC.png; sourceTree = ""; }; - 65B36257121C261F003EAD18 /* LI.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LI.png; sourceTree = ""; }; - 65B36258121C261F003EAD18 /* LK.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LK.png; sourceTree = ""; }; - 65B36259121C261F003EAD18 /* LR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LR.png; sourceTree = ""; }; - 65B3625A121C261F003EAD18 /* LS.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LS.png; sourceTree = ""; }; - 65B3625B121C261F003EAD18 /* LT.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LT.png; sourceTree = ""; }; - 65B3625C121C261F003EAD18 /* LU.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LU.png; sourceTree = ""; }; - 65B3625D121C261F003EAD18 /* LV.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LV.png; sourceTree = ""; }; - 65B3625E121C261F003EAD18 /* LY.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = LY.png; sourceTree = ""; }; - 65B3625F121C261F003EAD18 /* MA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MA.png; sourceTree = ""; }; - 65B36260121C261F003EAD18 /* MC.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MC.png; sourceTree = ""; }; - 65B36261121C261F003EAD18 /* MD.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MD.png; sourceTree = ""; }; - 65B36262121C261F003EAD18 /* ME.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ME.png; sourceTree = ""; }; - 65B36263121C261F003EAD18 /* MG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MG.png; sourceTree = ""; }; - 65B36264121C261F003EAD18 /* MH.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MH.png; sourceTree = ""; }; - 65B36265121C261F003EAD18 /* MK.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MK.png; sourceTree = ""; }; - 65B36266121C261F003EAD18 /* ML.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ML.png; sourceTree = ""; }; - 65B36267121C261F003EAD18 /* MM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MM.png; sourceTree = ""; }; - 65B36268121C261F003EAD18 /* MN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MN.png; sourceTree = ""; }; - 65B36269121C261F003EAD18 /* MO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MO.png; sourceTree = ""; }; - 65B3626A121C261F003EAD18 /* MP.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MP.png; sourceTree = ""; }; - 65B3626B121C261F003EAD18 /* MQ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MQ.png; sourceTree = ""; }; - 65B3626C121C261F003EAD18 /* MR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MR.png; sourceTree = ""; }; - 65B3626D121C261F003EAD18 /* MS.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MS.png; sourceTree = ""; }; - 65B3626E121C261F003EAD18 /* MT.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MT.png; sourceTree = ""; }; - 65B3626F121C261F003EAD18 /* MU.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MU.png; sourceTree = ""; }; - 65B36270121C261F003EAD18 /* MV.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MV.png; sourceTree = ""; }; - 65B36271121C261F003EAD18 /* MW.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MW.png; sourceTree = ""; }; - 65B36272121C261F003EAD18 /* MX.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MX.png; sourceTree = ""; }; - 65B36273121C261F003EAD18 /* MY.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MY.png; sourceTree = ""; }; - 65B36274121C261F003EAD18 /* MZ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = MZ.png; sourceTree = ""; }; - 65B36275121C261F003EAD18 /* NA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NA.png; sourceTree = ""; }; - 65B36276121C261F003EAD18 /* NC.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NC.png; sourceTree = ""; }; - 65B36277121C261F003EAD18 /* NE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NE.png; sourceTree = ""; }; - 65B36278121C261F003EAD18 /* NF.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NF.png; sourceTree = ""; }; - 65B36279121C261F003EAD18 /* NG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NG.png; sourceTree = ""; }; - 65B3627A121C261F003EAD18 /* NI.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NI.png; sourceTree = ""; }; - 65B3627B121C261F003EAD18 /* NL.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NL.png; sourceTree = ""; }; - 65B3627C121C261F003EAD18 /* NO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NO.png; sourceTree = ""; }; - 65B3627D121C261F003EAD18 /* NP.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NP.png; sourceTree = ""; }; - 65B3627E121C261F003EAD18 /* NR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NR.png; sourceTree = ""; }; - 65B3627F121C261F003EAD18 /* NU.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NU.png; sourceTree = ""; }; - 65B36280121C261F003EAD18 /* NZ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = NZ.png; sourceTree = ""; }; - 65B36281121C261F003EAD18 /* OM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = OM.png; sourceTree = ""; }; - 65B36282121C261F003EAD18 /* PA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PA.png; sourceTree = ""; }; - 65B36283121C261F003EAD18 /* PE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PE.png; sourceTree = ""; }; - 65B36284121C261F003EAD18 /* PF.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PF.png; sourceTree = ""; }; - 65B36285121C261F003EAD18 /* PG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PG.png; sourceTree = ""; }; - 65B36286121C261F003EAD18 /* PH.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PH.png; sourceTree = ""; }; - 65B36287121C261F003EAD18 /* PK.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PK.png; sourceTree = ""; }; - 65B36288121C261F003EAD18 /* PL.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PL.png; sourceTree = ""; }; - 65B36289121C261F003EAD18 /* PM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PM.png; sourceTree = ""; }; - 65B3628A121C261F003EAD18 /* PN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PN.png; sourceTree = ""; }; - 65B3628B121C261F003EAD18 /* PR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PR.png; sourceTree = ""; }; - 65B3628C121C261F003EAD18 /* PS.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PS.png; sourceTree = ""; }; - 65B3628D121C261F003EAD18 /* PT.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PT.png; sourceTree = ""; }; - 65B3628E121C261F003EAD18 /* PW.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PW.png; sourceTree = ""; }; - 65B3628F121C261F003EAD18 /* PY.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = PY.png; sourceTree = ""; }; - 65B36290121C261F003EAD18 /* QA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = QA.png; sourceTree = ""; }; - 65B36291121C261F003EAD18 /* RE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = RE.png; sourceTree = ""; }; - 65B36292121C261F003EAD18 /* RO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = RO.png; sourceTree = ""; }; - 65B36293121C261F003EAD18 /* RS.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = RS.png; sourceTree = ""; }; - 65B36294121C261F003EAD18 /* RU.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = RU.png; sourceTree = ""; }; - 65B36295121C261F003EAD18 /* RW.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = RW.png; sourceTree = ""; }; - 65B36296121C261F003EAD18 /* SA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SA.png; sourceTree = ""; }; - 65B36297121C261F003EAD18 /* SB.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SB.png; sourceTree = ""; }; - 65B36298121C261F003EAD18 /* SC.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SC.png; sourceTree = ""; }; - 65B36299121C261F003EAD18 /* SD.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SD.png; sourceTree = ""; }; - 65B3629A121C261F003EAD18 /* SE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SE.png; sourceTree = ""; }; - 65B3629B121C261F003EAD18 /* SG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SG.png; sourceTree = ""; }; - 65B3629C121C261F003EAD18 /* SH.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SH.png; sourceTree = ""; }; - 65B3629D121C261F003EAD18 /* SI.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SI.png; sourceTree = ""; }; - 65B3629E121C261F003EAD18 /* SJ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SJ.png; sourceTree = ""; }; - 65B3629F121C261F003EAD18 /* SK.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SK.png; sourceTree = ""; }; - 65B362A0121C261F003EAD18 /* SL.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SL.png; sourceTree = ""; }; - 65B362A1121C261F003EAD18 /* SM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SM.png; sourceTree = ""; }; - 65B362A2121C261F003EAD18 /* SN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SN.png; sourceTree = ""; }; - 65B362A3121C261F003EAD18 /* SO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SO.png; sourceTree = ""; }; - 65B362A4121C261F003EAD18 /* SR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SR.png; sourceTree = ""; }; - 65B362A5121C261F003EAD18 /* ST.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ST.png; sourceTree = ""; }; - 65B362A6121C261F003EAD18 /* SV.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SV.png; sourceTree = ""; }; - 65B362A7121C261F003EAD18 /* SY.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SY.png; sourceTree = ""; }; - 65B362A8121C261F003EAD18 /* SZ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = SZ.png; sourceTree = ""; }; - 65B362A9121C261F003EAD18 /* TC.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TC.png; sourceTree = ""; }; - 65B362AA121C261F003EAD18 /* TD.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TD.png; sourceTree = ""; }; - 65B362AB121C261F003EAD18 /* TF.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TF.png; sourceTree = ""; }; - 65B362AC121C261F003EAD18 /* TG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TG.png; sourceTree = ""; }; - 65B362AD121C261F003EAD18 /* TH.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TH.png; sourceTree = ""; }; - 65B362AE121C261F003EAD18 /* TJ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TJ.png; sourceTree = ""; }; - 65B362AF121C261F003EAD18 /* TK.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TK.png; sourceTree = ""; }; - 65B362B0121C261F003EAD18 /* TL.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TL.png; sourceTree = ""; }; - 65B362B1121C261F003EAD18 /* TM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TM.png; sourceTree = ""; }; - 65B362B2121C261F003EAD18 /* TN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TN.png; sourceTree = ""; }; - 65B362B3121C261F003EAD18 /* TO.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TO.png; sourceTree = ""; }; - 65B362B4121C261F003EAD18 /* TR.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TR.png; sourceTree = ""; }; - 65B362B5121C261F003EAD18 /* TT.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TT.png; sourceTree = ""; }; - 65B362B6121C261F003EAD18 /* TV.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TV.png; sourceTree = ""; }; - 65B362B7121C261F003EAD18 /* TW.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TW.png; sourceTree = ""; }; - 65B362B8121C261F003EAD18 /* TZ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = TZ.png; sourceTree = ""; }; - 65B362B9121C261F003EAD18 /* UA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = UA.png; sourceTree = ""; }; - 65B362BA121C261F003EAD18 /* UG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = UG.png; sourceTree = ""; }; - 65B362BB121C261F003EAD18 /* UM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = UM.png; sourceTree = ""; }; - 65B362BC121C261F003EAD18 /* US.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = US.png; sourceTree = ""; }; - 65B362BD121C261F003EAD18 /* UY.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = UY.png; sourceTree = ""; }; - 65B362BE121C261F003EAD18 /* UZ.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = UZ.png; sourceTree = ""; }; - 65B362BF121C261F003EAD18 /* VA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = VA.png; sourceTree = ""; }; - 65B362C0121C261F003EAD18 /* VC.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = VC.png; sourceTree = ""; }; - 65B362C1121C261F003EAD18 /* VE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = VE.png; sourceTree = ""; }; - 65B362C2121C261F003EAD18 /* VG.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = VG.png; sourceTree = ""; }; - 65B362C3121C261F003EAD18 /* VI.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = VI.png; sourceTree = ""; }; - 65B362C4121C261F003EAD18 /* VN.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = VN.png; sourceTree = ""; }; - 65B362C5121C261F003EAD18 /* VU.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = VU.png; sourceTree = ""; }; - 65B362C6121C261F003EAD18 /* WF.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = WF.png; sourceTree = ""; }; - 65B362C7121C261F003EAD18 /* WS.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = WS.png; sourceTree = ""; }; - 65B362C8121C261F003EAD18 /* YE.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = YE.png; sourceTree = ""; }; - 65B362C9121C261F003EAD18 /* YT.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = YT.png; sourceTree = ""; }; - 65B362CA121C261F003EAD18 /* ZA.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ZA.png; sourceTree = ""; }; - 65B362CB121C261F003EAD18 /* ZM.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ZM.png; sourceTree = ""; }; - 65B362CC121C261F003EAD18 /* ZW.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ZW.png; sourceTree = ""; }; - 65B362CD121C261F003EAD18 /* resources.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = resources.qrc; sourceTree = ""; }; - 65B362CF121C261F003EAD18 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65B362D0121C261F003EAD18 /* network.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = network.pri; sourceTree = ""; }; - 65B362D1121C261F003EAD18 /* network.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = network.pro; sourceTree = ""; }; - 65B362D2121C261F003EAD18 /* qxtjsonrpccall.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtjsonrpccall.cpp; sourceTree = ""; }; - 65B362D3121C261F003EAD18 /* qxtjsonrpccall.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtjsonrpccall.h; sourceTree = ""; }; - 65B362D4121C261F003EAD18 /* qxtjsonrpcclient.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtjsonrpcclient.cpp; sourceTree = ""; }; - 65B362D5121C261F003EAD18 /* qxtjsonrpcclient.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtjsonrpcclient.h; sourceTree = ""; }; - 65B362D6121C261F003EAD18 /* qxtmail_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtmail_p.h; sourceTree = ""; }; - 65B362D7121C261F003EAD18 /* qxtmailattachment.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtmailattachment.cpp; sourceTree = ""; }; - 65B362D8121C261F003EAD18 /* qxtmailattachment.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtmailattachment.h; sourceTree = ""; }; - 65B362D9121C261F003EAD18 /* qxtmailmessage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtmailmessage.cpp; sourceTree = ""; }; - 65B362DA121C261F003EAD18 /* qxtmailmessage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtmailmessage.h; sourceTree = ""; }; - 65B362DB121C261F003EAD18 /* qxtnetwork.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtnetwork.h; sourceTree = ""; }; - 65B362DC121C261F003EAD18 /* qxtrpcpeer.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtrpcpeer.cpp; sourceTree = ""; }; - 65B362DD121C261F003EAD18 /* qxtrpcpeer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtrpcpeer.h; sourceTree = ""; }; - 65B362DE121C261F003EAD18 /* qxtsmtp.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtsmtp.cpp; sourceTree = ""; }; - 65B362DF121C261F003EAD18 /* qxtsmtp.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtsmtp.h; sourceTree = ""; }; - 65B362E0121C261F003EAD18 /* qxtsmtp_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtsmtp_p.h; sourceTree = ""; }; - 65B362E1121C261F003EAD18 /* qxttcpconnectionmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxttcpconnectionmanager.cpp; sourceTree = ""; }; - 65B362E2121C261F003EAD18 /* qxttcpconnectionmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttcpconnectionmanager.h; sourceTree = ""; }; - 65B362E3121C261F003EAD18 /* qxttcpconnectionmanager_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxttcpconnectionmanager_p.h; sourceTree = ""; }; - 65B362E4121C261F003EAD18 /* qxtxmlrpc_p.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtxmlrpc_p.cpp; sourceTree = ""; }; - 65B362E5121C261F003EAD18 /* qxtxmlrpc_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtxmlrpc_p.h; sourceTree = ""; }; - 65B362E6121C261F003EAD18 /* qxtxmlrpccall.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtxmlrpccall.cpp; sourceTree = ""; }; - 65B362E7121C261F003EAD18 /* qxtxmlrpccall.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtxmlrpccall.h; sourceTree = ""; }; - 65B362E8121C261F003EAD18 /* qxtxmlrpcclient.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtxmlrpcclient.cpp; sourceTree = ""; }; - 65B362E9121C261F003EAD18 /* qxtxmlrpcclient.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtxmlrpcclient.h; sourceTree = ""; }; - 65B362EA121C261F003EAD18 /* qxtbase.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qxtbase.pri; sourceTree = ""; }; - 65B362EB121C261F003EAD18 /* qxtlibs.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qxtlibs.pri; sourceTree = ""; }; - 65B362ED121C261F003EAD18 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65B362EE121C261F003EAD18 /* qxtsql.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtsql.h; sourceTree = ""; }; - 65B362EF121C261F003EAD18 /* qxtsqlpackage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtsqlpackage.cpp; sourceTree = ""; }; - 65B362F0121C261F003EAD18 /* qxtsqlpackage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtsqlpackage.h; sourceTree = ""; }; - 65B362F1121C261F003EAD18 /* qxtsqlpackagemodel.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtsqlpackagemodel.cpp; sourceTree = ""; }; - 65B362F2121C261F003EAD18 /* qxtsqlpackagemodel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtsqlpackagemodel.h; sourceTree = ""; }; - 65B362F3121C261F003EAD18 /* sql.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = sql.pri; sourceTree = ""; }; - 65B362F4121C261F003EAD18 /* sql.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = sql.pro; sourceTree = ""; }; - 65B362F6121C261F003EAD18 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65B362F7121C261F003EAD18 /* qxtabstracthttpconnector.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtabstracthttpconnector.cpp; sourceTree = ""; }; - 65B362F8121C261F003EAD18 /* qxtabstracthttpconnector.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtabstracthttpconnector.h; sourceTree = ""; }; - 65B362F9121C261F003EAD18 /* qxtabstractwebservice.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtabstractwebservice.cpp; sourceTree = ""; }; - 65B362FA121C261F003EAD18 /* qxtabstractwebservice.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtabstractwebservice.h; sourceTree = ""; }; - 65B362FB121C261F003EAD18 /* qxtabstractwebsessionmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtabstractwebsessionmanager.cpp; sourceTree = ""; }; - 65B362FC121C261F003EAD18 /* qxtabstractwebsessionmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtabstractwebsessionmanager.h; sourceTree = ""; }; - 65B362FD121C261F003EAD18 /* qxtabstractwebsessionmanager_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtabstractwebsessionmanager_p.h; sourceTree = ""; }; - 65B362FE121C261F003EAD18 /* qxthtmltemplate.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxthtmltemplate.cpp; sourceTree = ""; }; - 65B362FF121C261F003EAD18 /* qxthtmltemplate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxthtmltemplate.h; sourceTree = ""; }; - 65B36300121C261F003EAD18 /* qxthttpserverconnector.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxthttpserverconnector.cpp; sourceTree = ""; }; - 65B36301121C261F003EAD18 /* qxthttpsessionmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxthttpsessionmanager.cpp; sourceTree = ""; }; - 65B36302121C261F003EAD18 /* qxthttpsessionmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxthttpsessionmanager.h; sourceTree = ""; }; - 65B36303121C261F003EAD18 /* qxtscgiserverconnector.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtscgiserverconnector.cpp; sourceTree = ""; }; - 65B36304121C261F003EAD18 /* qxtweb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtweb.h; sourceTree = ""; }; - 65B36305121C261F003EAD18 /* qxtwebcgiservice.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtwebcgiservice.cpp; sourceTree = ""; }; - 65B36306121C261F003EAD18 /* qxtwebcgiservice.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtwebcgiservice.h; sourceTree = ""; }; - 65B36307121C261F003EAD18 /* qxtwebcgiservice_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtwebcgiservice_p.h; sourceTree = ""; }; - 65B36308121C261F003EAD18 /* qxtwebcontent.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtwebcontent.cpp; sourceTree = ""; }; - 65B36309121C261F003EAD18 /* qxtwebcontent.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtwebcontent.h; sourceTree = ""; }; - 65B3630A121C261F003EAD18 /* qxtwebevent.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtwebevent.cpp; sourceTree = ""; }; - 65B3630B121C261F003EAD18 /* qxtwebevent.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtwebevent.h; sourceTree = ""; }; - 65B3630C121C261F003EAD18 /* qxtwebservicedirectory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtwebservicedirectory.cpp; sourceTree = ""; }; - 65B3630D121C261F003EAD18 /* qxtwebservicedirectory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtwebservicedirectory.h; sourceTree = ""; }; - 65B3630E121C261F003EAD18 /* qxtwebservicedirectory_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtwebservicedirectory_p.h; sourceTree = ""; }; - 65B3630F121C261F003EAD18 /* qxtwebslotservice.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtwebslotservice.cpp; sourceTree = ""; }; - 65B36310121C261F003EAD18 /* qxtwebslotservice.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtwebslotservice.h; sourceTree = ""; }; - 65B36311121C261F003EAD18 /* web.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = web.pri; sourceTree = ""; }; - 65B36312121C261F003EAD18 /* web.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = web.pro; sourceTree = ""; }; - 65B36314121C261F003EAD18 /* qxtavahipoll.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtavahipoll.cpp; sourceTree = ""; }; - 65B36315121C261F003EAD18 /* qxtavahipoll.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtavahipoll.h; sourceTree = ""; }; - 65B36316121C261F003EAD18 /* qxtavahipoll_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtavahipoll_p.h; sourceTree = ""; }; - 65B36317121C261F003EAD18 /* qxtdiscoverableservice.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtdiscoverableservice.cpp; sourceTree = ""; }; - 65B36318121C261F003EAD18 /* qxtdiscoverableservice.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtdiscoverableservice.h; sourceTree = ""; }; - 65B36319121C261F003EAD18 /* qxtdiscoverableservice_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtdiscoverableservice_p.h; sourceTree = ""; }; - 65B3631A121C261F003EAD18 /* qxtdiscoverableservicename.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtdiscoverableservicename.cpp; sourceTree = ""; }; - 65B3631B121C261F003EAD18 /* qxtdiscoverableservicename.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtdiscoverableservicename.h; sourceTree = ""; }; - 65B3631C121C261F003EAD18 /* qxtmdns_avahi.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtmdns_avahi.cpp; sourceTree = ""; }; - 65B3631D121C261F003EAD18 /* qxtmdns_avahi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtmdns_avahi.h; sourceTree = ""; }; - 65B3631E121C261F003EAD18 /* qxtmdns_avahi_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtmdns_avahi_p.h; sourceTree = ""; }; - 65B3631F121C261F003EAD18 /* qxtmdns_bonjour.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtmdns_bonjour.cpp; sourceTree = ""; }; - 65B36320121C261F003EAD18 /* qxtmdns_bonjour.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtmdns_bonjour.h; sourceTree = ""; }; - 65B36321121C261F003EAD18 /* qxtservicebrowser.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qxtservicebrowser.cpp; sourceTree = ""; }; - 65B36322121C261F003EAD18 /* qxtservicebrowser.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtservicebrowser.h; sourceTree = ""; }; - 65B36323121C261F003EAD18 /* qxtservicebrowser_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtservicebrowser_p.h; sourceTree = ""; }; - 65B36324121C261F003EAD18 /* qxtzeroconf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qxtzeroconf.h; sourceTree = ""; }; - 65B36325121C261F003EAD18 /* zeroconf.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = zeroconf.pri; sourceTree = ""; }; - 65B36326121C261F003EAD18 /* zeroconf.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = zeroconf.pro; sourceTree = ""; }; - 65B36328121C261F003EAD18 /* gen_qlocale.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gen_qlocale.cpp; sourceTree = ""; }; - 65B36329121C261F003EAD18 /* qxt_de.ts */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = qxt_de.ts; sourceTree = ""; }; - 65B3632A121C261F003EAD18 /* qxt_en.ts */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = qxt_en.ts; sourceTree = ""; }; - 65B3632B121C261F003EAD18 /* qxt_es.ts */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = qxt_es.ts; sourceTree = ""; }; - 65B3632C121C261F003EAD18 /* qxt_fi.ts */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = qxt_fi.ts; sourceTree = ""; }; - 65B3632D121C261F003EAD18 /* qxt_fr.ts */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = qxt_fr.ts; sourceTree = ""; }; - 65B3632E121C261F003EAD18 /* qxt_it.ts */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = qxt_it.ts; sourceTree = ""; }; - 65B3632F121C261F003EAD18 /* libs.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = libs.pro; sourceTree = ""; }; - 65B36331121C261F003EAD18 /* opmapcontrol.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmapcontrol.h; sourceTree = ""; }; - 65B36332121C261F003EAD18 /* opmapcontrol.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = opmapcontrol.pri; sourceTree = ""; }; - 65B36333121C261F003EAD18 /* opmapcontrol.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = opmapcontrol.pro; sourceTree = ""; }; - 65B36335121C261F003EAD18 /* common.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = common.pri; sourceTree = ""; }; - 65B36337121C261F003EAD18 /* accessmode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = accessmode.h; sourceTree = ""; }; - 65B36338121C261F003EAD18 /* alllayersoftype.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = alllayersoftype.cpp; sourceTree = ""; }; - 65B36339121C261F003EAD18 /* alllayersoftype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = alllayersoftype.h; sourceTree = ""; }; - 65B3633A121C261F003EAD18 /* cache.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = cache.cpp; sourceTree = ""; }; - 65B3633B121C261F003EAD18 /* cache.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = cache.h; sourceTree = ""; }; - 65B3633C121C261F003EAD18 /* cacheitemqueue.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = cacheitemqueue.cpp; sourceTree = ""; }; - 65B3633D121C261F003EAD18 /* cacheitemqueue.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = cacheitemqueue.h; sourceTree = ""; }; - 65B3633E121C261F003EAD18 /* core.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = core.pro; sourceTree = ""; }; - 65B3633F121C261F003EAD18 /* debugheader.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = debugheader.h; sourceTree = ""; }; - 65B36340121C261F003EAD18 /* geodecoderstatus.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = geodecoderstatus.h; sourceTree = ""; }; - 65B36341121C261F003EAD18 /* kibertilecache.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = kibertilecache.cpp; sourceTree = ""; }; - 65B36342121C261F003EAD18 /* kibertilecache.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = kibertilecache.h; sourceTree = ""; }; - 65B36343121C261F003EAD18 /* languagetype.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = languagetype.cpp; sourceTree = ""; }; - 65B36344121C261F003EAD18 /* languagetype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = languagetype.h; sourceTree = ""; }; - 65B36345121C261F003EAD18 /* maptype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = maptype.h; sourceTree = ""; }; - 65B36346121C261F003EAD18 /* memorycache.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = memorycache.cpp; sourceTree = ""; }; - 65B36347121C261F003EAD18 /* memorycache.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = memorycache.h; sourceTree = ""; }; - 65B36348121C261F003EAD18 /* opmaps.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmaps.cpp; sourceTree = ""; }; - 65B36349121C261F003EAD18 /* opmaps.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmaps.h; sourceTree = ""; }; - 65B3634A121C261F003EAD18 /* placemark.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = placemark.cpp; sourceTree = ""; }; - 65B3634B121C261F003EAD18 /* placemark.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = placemark.h; sourceTree = ""; }; - 65B3634C121C261F003EAD18 /* point.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = point.cpp; sourceTree = ""; }; - 65B3634D121C261F003EAD18 /* point.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = point.h; sourceTree = ""; }; - 65B3634E121C261F003EAD18 /* providerstrings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = providerstrings.cpp; sourceTree = ""; }; - 65B3634F121C261F003EAD18 /* providerstrings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = providerstrings.h; sourceTree = ""; }; - 65B36350121C261F003EAD18 /* pureimage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pureimage.cpp; sourceTree = ""; }; - 65B36351121C261F003EAD18 /* pureimage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pureimage.h; sourceTree = ""; }; - 65B36352121C261F003EAD18 /* pureimagecache.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pureimagecache.cpp; sourceTree = ""; }; - 65B36353121C261F003EAD18 /* pureimagecache.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pureimagecache.h; sourceTree = ""; }; - 65B36354121C261F003EAD18 /* rawtile.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = rawtile.cpp; sourceTree = ""; }; - 65B36355121C261F003EAD18 /* rawtile.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rawtile.h; sourceTree = ""; }; - 65B36356121C261F003EAD18 /* size.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = size.cpp; sourceTree = ""; }; - 65B36357121C261F003EAD18 /* size.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = size.h; sourceTree = ""; }; - 65B36358121C261F003EAD18 /* tilecachequeue.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = tilecachequeue.cpp; sourceTree = ""; }; - 65B36359121C261F003EAD18 /* tilecachequeue.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = tilecachequeue.h; sourceTree = ""; }; - 65B3635A121C261F003EAD18 /* urlfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = urlfactory.cpp; sourceTree = ""; }; - 65B3635B121C261F003EAD18 /* urlfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = urlfactory.h; sourceTree = ""; }; - 65B3635D121C261F003EAD18 /* copyrightstrings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = copyrightstrings.h; sourceTree = ""; }; - 65B3635E121C261F003EAD18 /* core.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = core.cpp; sourceTree = ""; }; - 65B3635F121C261F003EAD18 /* core.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = core.h; sourceTree = ""; }; - 65B36360121C261F003EAD18 /* debugheader.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = debugheader.h; sourceTree = ""; }; - 65B36361121C261F003EAD18 /* internals.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = internals.pro; sourceTree = ""; }; - 65B36362121C261F003EAD18 /* loadtask.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = loadtask.cpp; sourceTree = ""; }; - 65B36363121C261F003EAD18 /* loadtask.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = loadtask.h; sourceTree = ""; }; - 65B36364121C261F003EAD18 /* MouseWheelZoomType.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = MouseWheelZoomType.cpp; sourceTree = ""; }; - 65B36365121C261F003EAD18 /* mousewheelzoomtype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mousewheelzoomtype.h; sourceTree = ""; }; - 65B36366121C261F003EAD18 /* pointlatlng.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pointlatlng.cpp; sourceTree = ""; }; - 65B36367121C261F003EAD18 /* pointlatlng.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pointlatlng.h; sourceTree = ""; }; - 65B36369121C261F003EAD18 /* lks94projection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = lks94projection.cpp; sourceTree = ""; }; - 65B3636A121C261F003EAD18 /* lks94projection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = lks94projection.h; sourceTree = ""; }; - 65B3636B121C261F003EAD18 /* mercatorprojection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mercatorprojection.cpp; sourceTree = ""; }; - 65B3636C121C261F003EAD18 /* mercatorprojection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mercatorprojection.h; sourceTree = ""; }; - 65B3636D121C261F003EAD18 /* mercatorprojectionyandex.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mercatorprojectionyandex.cpp; sourceTree = ""; }; - 65B3636E121C261F003EAD18 /* mercatorprojectionyandex.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mercatorprojectionyandex.h; sourceTree = ""; }; - 65B3636F121C261F003EAD18 /* platecarreeprojection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = platecarreeprojection.cpp; sourceTree = ""; }; - 65B36370121C261F003EAD18 /* platecarreeprojection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = platecarreeprojection.h; sourceTree = ""; }; - 65B36371121C261F003EAD18 /* platecarreeprojectionpergo.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = platecarreeprojectionpergo.cpp; sourceTree = ""; }; - 65B36372121C261F003EAD18 /* platecarreeprojectionpergo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = platecarreeprojectionpergo.h; sourceTree = ""; }; - 65B36373121C261F003EAD18 /* pureprojection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pureprojection.cpp; sourceTree = ""; }; - 65B36374121C261F003EAD18 /* pureprojection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pureprojection.h; sourceTree = ""; }; - 65B36375121C261F003EAD18 /* rectangle.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = rectangle.cpp; sourceTree = ""; }; - 65B36376121C261F003EAD18 /* rectangle.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rectangle.h; sourceTree = ""; }; - 65B36377121C261F003EAD18 /* rectlatlng.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = rectlatlng.cpp; sourceTree = ""; }; - 65B36378121C261F003EAD18 /* rectlatlng.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rectlatlng.h; sourceTree = ""; }; - 65B36379121C261F003EAD18 /* sizelatlng.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = sizelatlng.cpp; sourceTree = ""; }; - 65B3637A121C261F003EAD18 /* sizelatlng.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = sizelatlng.h; sourceTree = ""; }; - 65B3637B121C261F003EAD18 /* tile.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = tile.cpp; sourceTree = ""; }; - 65B3637C121C261F003EAD18 /* tile.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = tile.h; sourceTree = ""; }; - 65B3637D121C261F003EAD18 /* tilematrix.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = tilematrix.cpp; sourceTree = ""; }; - 65B3637E121C261F003EAD18 /* tilematrix.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = tilematrix.h; sourceTree = ""; }; - 65B36380121C261F003EAD18 /* configuration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = configuration.cpp; sourceTree = ""; }; - 65B36381121C261F003EAD18 /* configuration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = configuration.h; sourceTree = ""; }; - 65B36382121C261F003EAD18 /* homeitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = homeitem.cpp; sourceTree = ""; }; - 65B36383121C261F003EAD18 /* homeitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = homeitem.h; sourceTree = ""; }; - 65B36385121C261F003EAD18 /* airplane.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = airplane.png; sourceTree = ""; }; - 65B36386121C261F003EAD18 /* airplane.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = airplane.svg; sourceTree = ""; }; - 65B36387121C261F003EAD18 /* airplanepip.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = airplanepip.png; sourceTree = ""; }; - 65B36388121C261F003EAD18 /* bigMarkerGreen.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = bigMarkerGreen.png; sourceTree = ""; }; - 65B36389121C261F003EAD18 /* compas.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = compas.svg; sourceTree = ""; }; - 65B3638A121C261F003EAD18 /* EasystarBlue.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = EasystarBlue.png; sourceTree = ""; }; - 65B3638B121C261F003EAD18 /* home.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = home.png; sourceTree = ""; }; - 65B3638C121C261F003EAD18 /* home.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = home.svg; sourceTree = ""; }; - 65B3638D121C261F003EAD18 /* home2.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = home2.svg; sourceTree = ""; }; - 65B3638E121C261F003EAD18 /* mapquad.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = mapquad.png; sourceTree = ""; }; - 65B3638F121C261F003EAD18 /* marker.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = marker.png; sourceTree = ""; }; - 65B36390121C261F003EAD18 /* mapgraphicitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mapgraphicitem.cpp; sourceTree = ""; }; - 65B36391121C261F003EAD18 /* mapgraphicitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mapgraphicitem.h; sourceTree = ""; }; - 65B36392121C261F003EAD18 /* mapresources.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = mapresources.qrc; sourceTree = ""; }; - 65B36393121C261F003EAD18 /* mapripform.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mapripform.cpp; sourceTree = ""; }; - 65B36394121C261F003EAD18 /* mapripform.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mapripform.h; sourceTree = ""; }; - 65B36395121C261F003EAD18 /* mapripform.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mapripform.ui; sourceTree = ""; }; - 65B36396121C261F003EAD18 /* mapripper.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mapripper.cpp; sourceTree = ""; }; - 65B36397121C261F003EAD18 /* mapripper.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mapripper.h; sourceTree = ""; }; - 65B36398121C261F003EAD18 /* mapwidget.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = mapwidget.pro; sourceTree = ""; }; - 65B36399121C261F003EAD18 /* opmapwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmapwidget.cpp; sourceTree = ""; }; - 65B3639A121C261F003EAD18 /* opmapwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmapwidget.h; sourceTree = ""; }; - 65B3639B121C261F003EAD18 /* trailitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = trailitem.cpp; sourceTree = ""; }; - 65B3639C121C261F003EAD18 /* trailitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = trailitem.h; sourceTree = ""; }; - 65B3639D121C261F003EAD18 /* uavitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavitem.cpp; sourceTree = ""; }; - 65B3639E121C261F003EAD18 /* uavitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavitem.h; sourceTree = ""; }; - 65B3639F121C261F003EAD18 /* uavmapfollowtype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavmapfollowtype.h; sourceTree = ""; }; - 65B363A0121C261F003EAD18 /* uavtrailtype.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavtrailtype.h; sourceTree = ""; }; - 65B363A1121C261F003EAD18 /* waypointitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = waypointitem.cpp; sourceTree = ""; }; - 65B363A2121C261F003EAD18 /* waypointitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = waypointitem.h; sourceTree = ""; }; - 65B363A3121C261F003EAD18 /* src.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = src.pro; sourceTree = ""; }; - 65B363A5121C261F003EAD18 /* qextserialport.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qextserialport.pri; sourceTree = ""; }; - 65B363A6121C261F003EAD18 /* qextserialport.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qextserialport.pro; sourceTree = ""; }; - 65B363A8121C261F003EAD18 /* posix_qextserialport.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = posix_qextserialport.cpp; sourceTree = ""; }; - 65B363A9121C261F003EAD18 /* qextserialenumerator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qextserialenumerator.h; sourceTree = ""; }; - 65B363AA121C261F003EAD18 /* qextserialenumerator_osx.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qextserialenumerator_osx.cpp; sourceTree = ""; }; - 65B363AB121C261F003EAD18 /* qextserialenumerator_unix.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qextserialenumerator_unix.cpp; sourceTree = ""; }; - 65B363AC121C261F003EAD18 /* qextserialenumerator_win.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qextserialenumerator_win.cpp; sourceTree = ""; }; - 65B363AD121C261F003EAD18 /* qextserialport.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qextserialport.cpp; sourceTree = ""; }; - 65B363AE121C261F003EAD18 /* qextserialport.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qextserialport.h; sourceTree = ""; }; - 65B363AF121C261F003EAD18 /* qextserialport_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qextserialport_global.h; sourceTree = ""; }; - 65B363B0121C261F003EAD18 /* src.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = src.pro; sourceTree = ""; }; - 65B363B1121C261F003EAD18 /* win_qextserialport.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = win_qextserialport.cpp; sourceTree = ""; }; - 65B363B3121C261F003EAD18 /* multitask.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = multitask.h; sourceTree = ""; }; - 65B363B4121C261F003EAD18 /* qtconcurrent.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qtconcurrent.pri; sourceTree = ""; }; - 65B363B5121C261F003EAD18 /* qtconcurrent.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qtconcurrent.pro; sourceTree = ""; }; - 65B363B6121C261F003EAD18 /* qtconcurrent_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qtconcurrent_global.h; sourceTree = ""; }; - 65B363B7121C261F003EAD18 /* QtConcurrentTools */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = QtConcurrentTools; sourceTree = ""; }; - 65B363B8121C261F003EAD18 /* runextensions.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = runextensions.h; sourceTree = ""; }; - 65B363BA121C261F003EAD18 /* COPYING */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = COPYING; sourceTree = ""; }; - 65B363BB121C261F003EAD18 /* qwt.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qwt.pri; sourceTree = ""; }; - 65B363BC121C261F003EAD18 /* qwt.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qwt.pro; sourceTree = ""; }; - 65B363BD121C261F003EAD18 /* qwtconfig.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qwtconfig.pri; sourceTree = ""; }; - 65B363BF121C261F003EAD18 /* qwt.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt.h; sourceTree = ""; }; - 65B363C0121C261F003EAD18 /* qwt_abstract_scale.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_abstract_scale.cpp; sourceTree = ""; }; - 65B363C1121C261F003EAD18 /* qwt_abstract_scale.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_abstract_scale.h; sourceTree = ""; }; - 65B363C2121C261F003EAD18 /* qwt_abstract_scale_draw.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_abstract_scale_draw.cpp; sourceTree = ""; }; - 65B363C3121C261F003EAD18 /* qwt_abstract_scale_draw.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_abstract_scale_draw.h; sourceTree = ""; }; - 65B363C4121C261F003EAD18 /* qwt_abstract_slider.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_abstract_slider.cpp; sourceTree = ""; }; - 65B363C5121C261F003EAD18 /* qwt_abstract_slider.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_abstract_slider.h; sourceTree = ""; }; - 65B363C6121C261F003EAD18 /* qwt_analog_clock.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_analog_clock.cpp; sourceTree = ""; }; - 65B363C7121C261F003EAD18 /* qwt_analog_clock.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_analog_clock.h; sourceTree = ""; }; - 65B363C8121C261F003EAD18 /* qwt_array.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_array.h; sourceTree = ""; }; - 65B363C9121C261F003EAD18 /* qwt_arrow_button.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_arrow_button.cpp; sourceTree = ""; }; - 65B363CA121C261F003EAD18 /* qwt_arrow_button.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_arrow_button.h; sourceTree = ""; }; - 65B363CB121C261F003EAD18 /* qwt_clipper.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_clipper.cpp; sourceTree = ""; }; - 65B363CC121C261F003EAD18 /* qwt_clipper.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_clipper.h; sourceTree = ""; }; - 65B363CD121C261F003EAD18 /* qwt_color_map.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_color_map.cpp; sourceTree = ""; }; - 65B363CE121C261F003EAD18 /* qwt_color_map.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_color_map.h; sourceTree = ""; }; - 65B363CF121C261F003EAD18 /* qwt_compass.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_compass.cpp; sourceTree = ""; }; - 65B363D0121C261F003EAD18 /* qwt_compass.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_compass.h; sourceTree = ""; }; - 65B363D1121C261F003EAD18 /* qwt_compass_rose.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_compass_rose.cpp; sourceTree = ""; }; - 65B363D2121C261F003EAD18 /* qwt_compass_rose.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_compass_rose.h; sourceTree = ""; }; - 65B363D3121C261F003EAD18 /* qwt_counter.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_counter.cpp; sourceTree = ""; }; - 65B363D4121C261F003EAD18 /* qwt_counter.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_counter.h; sourceTree = ""; }; - 65B363D5121C261F003EAD18 /* qwt_curve_fitter.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_curve_fitter.cpp; sourceTree = ""; }; - 65B363D6121C261F003EAD18 /* qwt_curve_fitter.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_curve_fitter.h; sourceTree = ""; }; - 65B363D7121C261F003EAD18 /* qwt_data.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_data.cpp; sourceTree = ""; }; - 65B363D8121C261F003EAD18 /* qwt_data.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_data.h; sourceTree = ""; }; - 65B363D9121C261F003EAD18 /* qwt_dial.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_dial.cpp; sourceTree = ""; }; - 65B363DA121C261F003EAD18 /* qwt_dial.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_dial.h; sourceTree = ""; }; - 65B363DB121C261F003EAD18 /* qwt_dial_needle.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_dial_needle.cpp; sourceTree = ""; }; - 65B363DC121C261F003EAD18 /* qwt_dial_needle.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_dial_needle.h; sourceTree = ""; }; - 65B363DD121C261F003EAD18 /* qwt_double_interval.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_double_interval.cpp; sourceTree = ""; }; - 65B363DE121C261F003EAD18 /* qwt_double_interval.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_double_interval.h; sourceTree = ""; }; - 65B363DF121C261F003EAD18 /* qwt_double_range.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_double_range.cpp; sourceTree = ""; }; - 65B363E0121C261F003EAD18 /* qwt_double_range.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_double_range.h; sourceTree = ""; }; - 65B363E1121C261F003EAD18 /* qwt_double_rect.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_double_rect.cpp; sourceTree = ""; }; - 65B363E2121C261F003EAD18 /* qwt_double_rect.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_double_rect.h; sourceTree = ""; }; - 65B363E3121C261F003EAD18 /* qwt_dyngrid_layout.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_dyngrid_layout.cpp; sourceTree = ""; }; - 65B363E4121C261F003EAD18 /* qwt_dyngrid_layout.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_dyngrid_layout.h; sourceTree = ""; }; - 65B363E5121C261F003EAD18 /* qwt_event_pattern.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_event_pattern.cpp; sourceTree = ""; }; - 65B363E6121C261F003EAD18 /* qwt_event_pattern.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_event_pattern.h; sourceTree = ""; }; - 65B363E7121C261F003EAD18 /* qwt_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_global.h; sourceTree = ""; }; - 65B363E8121C261F003EAD18 /* qwt_interval_data.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_interval_data.cpp; sourceTree = ""; }; - 65B363E9121C261F003EAD18 /* qwt_interval_data.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_interval_data.h; sourceTree = ""; }; - 65B363EA121C261F003EAD18 /* qwt_knob.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_knob.cpp; sourceTree = ""; }; - 65B363EB121C261F003EAD18 /* qwt_knob.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_knob.h; sourceTree = ""; }; - 65B363EC121C261F003EAD18 /* qwt_layout_metrics.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_layout_metrics.cpp; sourceTree = ""; }; - 65B363ED121C261F003EAD18 /* qwt_layout_metrics.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_layout_metrics.h; sourceTree = ""; }; - 65B363EE121C261F003EAD18 /* qwt_legend.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_legend.cpp; sourceTree = ""; }; - 65B363EF121C261F003EAD18 /* qwt_legend.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_legend.h; sourceTree = ""; }; - 65B363F0121C261F003EAD18 /* qwt_legend_item.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_legend_item.cpp; sourceTree = ""; }; - 65B363F1121C261F003EAD18 /* qwt_legend_item.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_legend_item.h; sourceTree = ""; }; - 65B363F2121C261F003EAD18 /* qwt_legend_itemmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_legend_itemmanager.h; sourceTree = ""; }; - 65B363F3121C261F003EAD18 /* qwt_magnifier.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_magnifier.cpp; sourceTree = ""; }; - 65B363F4121C261F003EAD18 /* qwt_magnifier.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_magnifier.h; sourceTree = ""; }; - 65B363F5121C261F003EAD18 /* qwt_math.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_math.cpp; sourceTree = ""; }; - 65B363F6121C261F003EAD18 /* qwt_math.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_math.h; sourceTree = ""; }; - 65B363F7121C261F003EAD18 /* qwt_paint_buffer.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_paint_buffer.cpp; sourceTree = ""; }; - 65B363F8121C261F003EAD18 /* qwt_paint_buffer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_paint_buffer.h; sourceTree = ""; }; - 65B363F9121C261F003EAD18 /* qwt_painter.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_painter.cpp; sourceTree = ""; }; - 65B363FA121C261F003EAD18 /* qwt_painter.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_painter.h; sourceTree = ""; }; - 65B363FB121C261F003EAD18 /* qwt_panner.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_panner.cpp; sourceTree = ""; }; - 65B363FC121C261F003EAD18 /* qwt_panner.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_panner.h; sourceTree = ""; }; - 65B363FD121C261F003EAD18 /* qwt_picker.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_picker.cpp; sourceTree = ""; }; - 65B363FE121C261F003EAD18 /* qwt_picker.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_picker.h; sourceTree = ""; }; - 65B363FF121C261F003EAD18 /* qwt_picker_machine.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_picker_machine.cpp; sourceTree = ""; }; - 65B36400121C261F003EAD18 /* qwt_picker_machine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_picker_machine.h; sourceTree = ""; }; - 65B36401121C261F003EAD18 /* qwt_plot.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot.cpp; sourceTree = ""; }; - 65B36402121C261F003EAD18 /* qwt_plot.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot.h; sourceTree = ""; }; - 65B36403121C261F003EAD18 /* qwt_plot_axis.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_axis.cpp; sourceTree = ""; }; - 65B36404121C261F003EAD18 /* qwt_plot_canvas.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_canvas.cpp; sourceTree = ""; }; - 65B36405121C261F003EAD18 /* qwt_plot_canvas.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_canvas.h; sourceTree = ""; }; - 65B36406121C261F003EAD18 /* qwt_plot_curve.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_curve.cpp; sourceTree = ""; }; - 65B36407121C261F003EAD18 /* qwt_plot_curve.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_curve.h; sourceTree = ""; }; - 65B36408121C261F003EAD18 /* qwt_plot_dict.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_dict.cpp; sourceTree = ""; }; - 65B36409121C261F003EAD18 /* qwt_plot_dict.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_dict.h; sourceTree = ""; }; - 65B3640A121C261F003EAD18 /* qwt_plot_grid.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_grid.cpp; sourceTree = ""; }; - 65B3640B121C261F003EAD18 /* qwt_plot_grid.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_grid.h; sourceTree = ""; }; - 65B3640C121C261F003EAD18 /* qwt_plot_item.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_item.cpp; sourceTree = ""; }; - 65B3640D121C261F003EAD18 /* qwt_plot_item.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_item.h; sourceTree = ""; }; - 65B3640E121C261F003EAD18 /* qwt_plot_layout.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_layout.cpp; sourceTree = ""; }; - 65B3640F121C261F003EAD18 /* qwt_plot_layout.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_layout.h; sourceTree = ""; }; - 65B36410121C261F003EAD18 /* qwt_plot_magnifier.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_magnifier.cpp; sourceTree = ""; }; - 65B36411121C261F003EAD18 /* qwt_plot_magnifier.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_magnifier.h; sourceTree = ""; }; - 65B36412121C261F003EAD18 /* qwt_plot_marker.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_marker.cpp; sourceTree = ""; }; - 65B36413121C261F003EAD18 /* qwt_plot_marker.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_marker.h; sourceTree = ""; }; - 65B36414121C261F003EAD18 /* qwt_plot_panner.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_panner.cpp; sourceTree = ""; }; - 65B36415121C261F003EAD18 /* qwt_plot_panner.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_panner.h; sourceTree = ""; }; - 65B36416121C261F003EAD18 /* qwt_plot_picker.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_picker.cpp; sourceTree = ""; }; - 65B36417121C261F003EAD18 /* qwt_plot_picker.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_picker.h; sourceTree = ""; }; - 65B36418121C261F003EAD18 /* qwt_plot_print.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_print.cpp; sourceTree = ""; }; - 65B36419121C261F003EAD18 /* qwt_plot_printfilter.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_printfilter.cpp; sourceTree = ""; }; - 65B3641A121C261F003EAD18 /* qwt_plot_printfilter.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_printfilter.h; sourceTree = ""; }; - 65B3641B121C261F003EAD18 /* qwt_plot_rasteritem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_rasteritem.cpp; sourceTree = ""; }; - 65B3641C121C261F003EAD18 /* qwt_plot_rasteritem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_rasteritem.h; sourceTree = ""; }; - 65B3641D121C261F003EAD18 /* qwt_plot_rescaler.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_rescaler.cpp; sourceTree = ""; }; - 65B3641E121C261F003EAD18 /* qwt_plot_rescaler.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_rescaler.h; sourceTree = ""; }; - 65B3641F121C261F003EAD18 /* qwt_plot_scaleitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_scaleitem.cpp; sourceTree = ""; }; - 65B36420121C261F003EAD18 /* qwt_plot_scaleitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_scaleitem.h; sourceTree = ""; }; - 65B36421121C261F003EAD18 /* qwt_plot_spectrogram.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_spectrogram.cpp; sourceTree = ""; }; - 65B36422121C261F003EAD18 /* qwt_plot_spectrogram.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_spectrogram.h; sourceTree = ""; }; - 65B36423121C261F003EAD18 /* qwt_plot_svgitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_svgitem.cpp; sourceTree = ""; }; - 65B36424121C261F003EAD18 /* qwt_plot_svgitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_svgitem.h; sourceTree = ""; }; - 65B36425121C261F003EAD18 /* qwt_plot_xml.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_xml.cpp; sourceTree = ""; }; - 65B36426121C261F003EAD18 /* qwt_plot_zoomer.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_plot_zoomer.cpp; sourceTree = ""; }; - 65B36427121C261F003EAD18 /* qwt_plot_zoomer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_plot_zoomer.h; sourceTree = ""; }; - 65B36428121C261F003EAD18 /* qwt_polygon.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_polygon.h; sourceTree = ""; }; - 65B36429121C261F003EAD18 /* qwt_raster_data.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_raster_data.cpp; sourceTree = ""; }; - 65B3642A121C261F003EAD18 /* qwt_raster_data.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_raster_data.h; sourceTree = ""; }; - 65B3642B121C261F003EAD18 /* qwt_round_scale_draw.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_round_scale_draw.cpp; sourceTree = ""; }; - 65B3642C121C261F003EAD18 /* qwt_round_scale_draw.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_round_scale_draw.h; sourceTree = ""; }; - 65B3642D121C261F003EAD18 /* qwt_scale_div.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_scale_div.cpp; sourceTree = ""; }; - 65B3642E121C261F003EAD18 /* qwt_scale_div.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_scale_div.h; sourceTree = ""; }; - 65B3642F121C261F003EAD18 /* qwt_scale_draw.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_scale_draw.cpp; sourceTree = ""; }; - 65B36430121C261F003EAD18 /* qwt_scale_draw.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_scale_draw.h; sourceTree = ""; }; - 65B36431121C261F003EAD18 /* qwt_scale_engine.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_scale_engine.cpp; sourceTree = ""; }; - 65B36432121C261F003EAD18 /* qwt_scale_engine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_scale_engine.h; sourceTree = ""; }; - 65B36433121C261F003EAD18 /* qwt_scale_map.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_scale_map.cpp; sourceTree = ""; }; - 65B36434121C261F003EAD18 /* qwt_scale_map.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_scale_map.h; sourceTree = ""; }; - 65B36435121C261F003EAD18 /* qwt_scale_widget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_scale_widget.cpp; sourceTree = ""; }; - 65B36436121C261F003EAD18 /* qwt_scale_widget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_scale_widget.h; sourceTree = ""; }; - 65B36437121C261F003EAD18 /* qwt_slider.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_slider.cpp; sourceTree = ""; }; - 65B36438121C261F003EAD18 /* qwt_slider.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_slider.h; sourceTree = ""; }; - 65B36439121C261F003EAD18 /* qwt_spline.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_spline.cpp; sourceTree = ""; }; - 65B3643A121C261F003EAD18 /* qwt_spline.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_spline.h; sourceTree = ""; }; - 65B3643B121C261F003EAD18 /* qwt_symbol.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_symbol.cpp; sourceTree = ""; }; - 65B3643C121C261F003EAD18 /* qwt_symbol.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_symbol.h; sourceTree = ""; }; - 65B3643D121C261F003EAD18 /* qwt_text.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_text.cpp; sourceTree = ""; }; - 65B3643E121C261F003EAD18 /* qwt_text.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_text.h; sourceTree = ""; }; - 65B3643F121C261F003EAD18 /* qwt_text_engine.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_text_engine.cpp; sourceTree = ""; }; - 65B36440121C261F003EAD18 /* qwt_text_engine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_text_engine.h; sourceTree = ""; }; - 65B36441121C261F003EAD18 /* qwt_text_label.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_text_label.cpp; sourceTree = ""; }; - 65B36442121C261F003EAD18 /* qwt_text_label.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_text_label.h; sourceTree = ""; }; - 65B36443121C261F003EAD18 /* qwt_thermo.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_thermo.cpp; sourceTree = ""; }; - 65B36444121C261F003EAD18 /* qwt_thermo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_thermo.h; sourceTree = ""; }; - 65B36445121C261F003EAD18 /* qwt_valuelist.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_valuelist.h; sourceTree = ""; }; - 65B36446121C261F003EAD18 /* qwt_wheel.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qwt_wheel.cpp; sourceTree = ""; }; - 65B36447121C261F003EAD18 /* qwt_wheel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qwt_wheel.h; sourceTree = ""; }; - 65B36448121C261F003EAD18 /* src.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = src.pro; sourceTree = ""; }; - 65B3644A121C261F003EAD18 /* qymodem.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qymodem.pri; sourceTree = ""; }; - 65B3644B121C261F003EAD18 /* qymodem.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qymodem.pro; sourceTree = ""; }; - 65B3644D121C261F003EAD18 /* qymodem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qymodem.cpp; sourceTree = ""; }; - 65B3644E121C261F003EAD18 /* qymodem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qymodem.h; sourceTree = ""; }; - 65B3644F121C261F003EAD18 /* qymodem_tx.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qymodem_tx.cpp; sourceTree = ""; }; - 65B36450121C261F003EAD18 /* qymodem_tx.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qymodem_tx.h; sourceTree = ""; }; - 65B36451121C261F003EAD18 /* qymodemfilestream.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qymodemfilestream.cpp; sourceTree = ""; }; - 65B36452121C261F003EAD18 /* qymodemsend.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qymodemsend.cpp; sourceTree = ""; }; - 65B36453121C261F003EAD18 /* qymodemsend.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qymodemsend.h; sourceTree = ""; }; - 65B36454121C261F003EAD18 /* src.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = src.pro; sourceTree = ""; }; - 65B36456121C261F003EAD18 /* main.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cpp; sourceTree = ""; }; - 65B36457121C261F003EAD18 /* uavobjectgenerator.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectgenerator.cpp; sourceTree = ""; }; - 65B36458121C261F003EAD18 /* uavobjectgenerator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectgenerator.h; sourceTree = ""; }; - 65B36459121C261F003EAD18 /* uavobjectparser.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectparser.cpp; sourceTree = ""; }; - 65B3645A121C261F003EAD18 /* uavobjectparser.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectparser.h; sourceTree = ""; }; - 65B3645B121C261F003EAD18 /* uavobjgenerator.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavobjgenerator.pro; sourceTree = ""; }; - 65B3645D121C261F003EAD18 /* abstractprocess.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = abstractprocess.h; sourceTree = ""; }; - 65B3645E121C261F003EAD18 /* abstractprocess_win.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = abstractprocess_win.cpp; sourceTree = ""; }; - 65B3645F121C261F003EAD18 /* basevalidatinglineedit.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = basevalidatinglineedit.cpp; sourceTree = ""; }; - 65B36460121C261F003EAD18 /* basevalidatinglineedit.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = basevalidatinglineedit.h; sourceTree = ""; }; - 65B36461121C261F003EAD18 /* checkablemessagebox.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = checkablemessagebox.cpp; sourceTree = ""; }; - 65B36462121C261F003EAD18 /* checkablemessagebox.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = checkablemessagebox.h; sourceTree = ""; }; - 65B36463121C261F003EAD18 /* checkablemessagebox.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = checkablemessagebox.ui; sourceTree = ""; }; - 65B36464121C261F003EAD18 /* classnamevalidatinglineedit.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = classnamevalidatinglineedit.cpp; sourceTree = ""; }; - 65B36465121C261F003EAD18 /* classnamevalidatinglineedit.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = classnamevalidatinglineedit.h; sourceTree = ""; }; - 65B36466121C261F003EAD18 /* codegeneration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = codegeneration.cpp; sourceTree = ""; }; - 65B36467121C261F003EAD18 /* codegeneration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = codegeneration.h; sourceTree = ""; }; - 65B36468121C261F003EAD18 /* consoleprocess.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = consoleprocess.cpp; sourceTree = ""; }; - 65B36469121C261F003EAD18 /* consoleprocess.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = consoleprocess.h; sourceTree = ""; }; - 65B3646A121C261F003EAD18 /* consoleprocess_unix.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = consoleprocess_unix.cpp; sourceTree = ""; }; - 65B3646B121C261F003EAD18 /* consoleprocess_win.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = consoleprocess_win.cpp; sourceTree = ""; }; - 65B3646C121C261F003EAD18 /* detailsbutton.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = detailsbutton.cpp; sourceTree = ""; }; - 65B3646D121C261F003EAD18 /* detailsbutton.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = detailsbutton.h; sourceTree = ""; }; - 65B3646E121C261F003EAD18 /* detailswidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = detailswidget.cpp; sourceTree = ""; }; - 65B3646F121C261F003EAD18 /* detailswidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = detailswidget.h; sourceTree = ""; }; - 65B36470121C261F003EAD18 /* fancylineedit.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = fancylineedit.cpp; sourceTree = ""; }; - 65B36471121C261F003EAD18 /* fancylineedit.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fancylineedit.h; sourceTree = ""; }; - 65B36472121C261F003EAD18 /* fancymainwindow.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = fancymainwindow.cpp; sourceTree = ""; }; - 65B36473121C261F003EAD18 /* fancymainwindow.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fancymainwindow.h; sourceTree = ""; }; - 65B36474121C261F003EAD18 /* filenamevalidatinglineedit.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = filenamevalidatinglineedit.cpp; sourceTree = ""; }; - 65B36475121C261F003EAD18 /* filenamevalidatinglineedit.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = filenamevalidatinglineedit.h; sourceTree = ""; }; - 65B36476121C261F003EAD18 /* filesearch.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = filesearch.cpp; sourceTree = ""; }; - 65B36477121C261F003EAD18 /* filesearch.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = filesearch.h; sourceTree = ""; }; - 65B36478121C261F003EAD18 /* filewizarddialog.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = filewizarddialog.cpp; sourceTree = ""; }; - 65B36479121C261F003EAD18 /* filewizarddialog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = filewizarddialog.h; sourceTree = ""; }; - 65B3647A121C261F003EAD18 /* filewizardpage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = filewizardpage.cpp; sourceTree = ""; }; - 65B3647B121C261F003EAD18 /* filewizardpage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = filewizardpage.h; sourceTree = ""; }; - 65B3647C121C261F003EAD18 /* filewizardpage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = filewizardpage.ui; sourceTree = ""; }; - 65B3647E121C261F003EAD18 /* removesubmitfield.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = removesubmitfield.png; sourceTree = ""; }; - 65B3647F121C261F003EAD18 /* iwelcomepage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = iwelcomepage.cpp; sourceTree = ""; }; - 65B36480121C261F003EAD18 /* iwelcomepage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = iwelcomepage.h; sourceTree = ""; }; - 65B36481121C261F003EAD18 /* linecolumnlabel.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = linecolumnlabel.cpp; sourceTree = ""; }; - 65B36482121C261F003EAD18 /* linecolumnlabel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = linecolumnlabel.h; sourceTree = ""; }; - 65B36483121C261F003EAD18 /* listutils.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = listutils.h; sourceTree = ""; }; - 65B36484121C261F003EAD18 /* newclasswidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = newclasswidget.cpp; sourceTree = ""; }; - 65B36485121C261F003EAD18 /* newclasswidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = newclasswidget.h; sourceTree = ""; }; - 65B36486121C261F003EAD18 /* newclasswidget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = newclasswidget.ui; sourceTree = ""; }; - 65B36487121C261F003EAD18 /* parameteraction.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = parameteraction.cpp; sourceTree = ""; }; - 65B36488121C261F003EAD18 /* parameteraction.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = parameteraction.h; sourceTree = ""; }; - 65B36489121C261F003EAD18 /* pathchooser.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pathchooser.cpp; sourceTree = ""; }; - 65B3648A121C261F003EAD18 /* pathchooser.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pathchooser.h; sourceTree = ""; }; - 65B3648B121C261F003EAD18 /* pathlisteditor.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pathlisteditor.cpp; sourceTree = ""; }; - 65B3648C121C261F003EAD18 /* pathlisteditor.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pathlisteditor.h; sourceTree = ""; }; - 65B3648D121C261F003EAD18 /* projectintropage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = projectintropage.cpp; sourceTree = ""; }; - 65B3648E121C261F003EAD18 /* projectintropage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = projectintropage.h; sourceTree = ""; }; - 65B3648F121C261F003EAD18 /* projectintropage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = projectintropage.ui; sourceTree = ""; }; - 65B36490121C261F003EAD18 /* projectnamevalidatinglineedit.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = projectnamevalidatinglineedit.cpp; sourceTree = ""; }; - 65B36491121C261F003EAD18 /* projectnamevalidatinglineedit.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = projectnamevalidatinglineedit.h; sourceTree = ""; }; - 65B36492121C261F003EAD18 /* qtcassert.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qtcassert.h; sourceTree = ""; }; - 65B36493121C261F003EAD18 /* qtcolorbutton.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qtcolorbutton.cpp; sourceTree = ""; }; - 65B36494121C261F003EAD18 /* qtcolorbutton.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qtcolorbutton.h; sourceTree = ""; }; - 65B36495121C261F003EAD18 /* reloadpromptutils.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = reloadpromptutils.cpp; sourceTree = ""; }; - 65B36496121C261F003EAD18 /* reloadpromptutils.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = reloadpromptutils.h; sourceTree = ""; }; - 65B36497121C261F003EAD18 /* savedaction.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = savedaction.cpp; sourceTree = ""; }; - 65B36498121C261F003EAD18 /* savedaction.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = savedaction.h; sourceTree = ""; }; - 65B36499121C261F003EAD18 /* settingsutils.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = settingsutils.cpp; sourceTree = ""; }; - 65B3649A121C261F003EAD18 /* settingsutils.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = settingsutils.h; sourceTree = ""; }; - 65B3649B121C261F003EAD18 /* styledbar.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = styledbar.cpp; sourceTree = ""; }; - 65B3649C121C261F003EAD18 /* styledbar.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = styledbar.h; sourceTree = ""; }; - 65B3649D121C261F003EAD18 /* stylehelper.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = stylehelper.cpp; sourceTree = ""; }; - 65B3649E121C261F003EAD18 /* stylehelper.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stylehelper.h; sourceTree = ""; }; - 65B3649F121C261F003EAD18 /* submiteditorwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = submiteditorwidget.cpp; sourceTree = ""; }; - 65B364A0121C261F003EAD18 /* submiteditorwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = submiteditorwidget.h; sourceTree = ""; }; - 65B364A1121C261F003EAD18 /* submiteditorwidget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = submiteditorwidget.ui; sourceTree = ""; }; - 65B364A2121C261F003EAD18 /* submitfieldwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = submitfieldwidget.cpp; sourceTree = ""; }; - 65B364A3121C261F003EAD18 /* submitfieldwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = submitfieldwidget.h; sourceTree = ""; }; - 65B364A4121C261F003EAD18 /* synchronousprocess.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = synchronousprocess.cpp; sourceTree = ""; }; - 65B364A5121C261F003EAD18 /* synchronousprocess.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = synchronousprocess.h; sourceTree = ""; }; - 65B364A6121C261F003EAD18 /* treewidgetcolumnstretcher.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = treewidgetcolumnstretcher.cpp; sourceTree = ""; }; - 65B364A7121C261F003EAD18 /* treewidgetcolumnstretcher.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = treewidgetcolumnstretcher.h; sourceTree = ""; }; - 65B364A8121C261F003EAD18 /* uncommentselection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uncommentselection.cpp; sourceTree = ""; }; - 65B364A9121C261F003EAD18 /* uncommentselection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uncommentselection.h; sourceTree = ""; }; - 65B364AA121C261F003EAD18 /* utils.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = utils.pri; sourceTree = ""; }; - 65B364AB121C261F003EAD18 /* utils.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = utils.pro; sourceTree = ""; }; - 65B364AC121C261F003EAD18 /* utils.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = utils.qrc; sourceTree = ""; }; - 65B364AD121C261F003EAD18 /* utils_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = utils_global.h; sourceTree = ""; }; - 65B364AE121C261F003EAD18 /* welcomemodetreewidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = welcomemodetreewidget.cpp; sourceTree = ""; }; - 65B364AF121C261F003EAD18 /* welcomemodetreewidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = welcomemodetreewidget.h; sourceTree = ""; }; - 65B364B0121C261F003EAD18 /* winutils.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = winutils.cpp; sourceTree = ""; }; - 65B364B1121C261F003EAD18 /* winutils.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = winutils.h; sourceTree = ""; }; - 65B364B2121C261F003EAD18 /* openpilotgcslibrary.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = openpilotgcslibrary.pri; sourceTree = ""; }; - 65B364B3121C261F003EAD18 /* openpilotgcsplugin.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = openpilotgcsplugin.pri; sourceTree = ""; }; - 65B364B6121C261F003EAD18 /* airframe.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = airframe.ui; sourceTree = ""; }; - 65B364B7121C261F003EAD18 /* Config.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = Config.pluginspec; sourceTree = ""; }; - 65B364B8121C261F003EAD18 /* config.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = config.pro; sourceTree = ""; }; - 65B364B9121C261F003EAD18 /* configfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = configfactory.h; sourceTree = ""; }; - 65B364BA121C261F003EAD18 /* configgadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = configgadget.cpp; sourceTree = ""; }; - 65B364BB121C261F003EAD18 /* configgadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = configgadget.h; sourceTree = ""; }; - 65B364BC121C261F003EAD18 /* configgadget.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = configgadget.qrc; sourceTree = ""; }; - 65B364BD121C261F003EAD18 /* configgadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = configgadgetconfiguration.cpp; sourceTree = ""; }; - 65B364BE121C261F003EAD18 /* configgadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = configgadgetconfiguration.h; sourceTree = ""; }; - 65B364BF121C261F003EAD18 /* configgadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = configgadgetfactory.cpp; sourceTree = ""; }; - 65B364C0121C261F003EAD18 /* configgadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = configgadgetfactory.h; sourceTree = ""; }; - 65B364C1121C261F003EAD18 /* configgadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = configgadgetoptionspage.cpp; sourceTree = ""; }; - 65B364C2121C261F003EAD18 /* configgadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = configgadgetoptionspage.h; sourceTree = ""; }; - 65B364C3121C261F003EAD18 /* configgadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = configgadgetwidget.cpp; sourceTree = ""; }; - 65B364C4121C261F003EAD18 /* configgadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = configgadgetwidget.h; sourceTree = ""; }; - 65B364C5121C261F003EAD18 /* configplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = configplugin.cpp; sourceTree = ""; }; - 65B364C6121C261F003EAD18 /* configplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = configplugin.h; sourceTree = ""; }; - 65B364C7121C261F003EAD18 /* fancytabwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = fancytabwidget.cpp; sourceTree = ""; }; - 65B364C8121C261F003EAD18 /* fancytabwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fancytabwidget.h; sourceTree = ""; }; - 65B364CA121C261F003EAD18 /* Airframe.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = Airframe.png; sourceTree = ""; }; - 65B364CB121C261F003EAD18 /* Servo.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = Servo.png; sourceTree = ""; }; - 65B364CC121C261F003EAD18 /* XBee.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = XBee.svg; sourceTree = ""; }; - 65B364CD121C261F003EAD18 /* settingswidget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = settingswidget.ui; sourceTree = ""; }; - 65B364CE121C261F003EAD18 /* telemetry.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = telemetry.ui; sourceTree = ""; }; - 65B364D0121C261F003EAD18 /* consolegadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = consolegadget.cpp; sourceTree = ""; }; - 65B364D1121C261F003EAD18 /* consolegadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = consolegadget.h; sourceTree = ""; }; - 65B364D2121C261F003EAD18 /* ConsoleGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = ConsoleGadget.pluginspec; sourceTree = ""; }; - 65B364D3121C261F003EAD18 /* consolegadget.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = consolegadget.pro; sourceTree = ""; }; - 65B364D4121C261F003EAD18 /* consolegadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = consolegadgetfactory.cpp; sourceTree = ""; }; - 65B364D5121C261F003EAD18 /* consolegadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = consolegadgetfactory.h; sourceTree = ""; }; - 65B364D6121C261F003EAD18 /* consolegadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = consolegadgetwidget.cpp; sourceTree = ""; }; - 65B364D7121C261F003EAD18 /* consolegadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = consolegadgetwidget.h; sourceTree = ""; }; - 65B364D8121C261F003EAD18 /* consoleplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = consoleplugin.cpp; sourceTree = ""; }; - 65B364D9121C261F003EAD18 /* consoleplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = consoleplugin.h; sourceTree = ""; }; - 65B364DA121C261F003EAD18 /* texteditloggerengine.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = texteditloggerengine.cpp; sourceTree = ""; }; - 65B364DB121C261F003EAD18 /* texteditloggerengine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = texteditloggerengine.h; sourceTree = ""; }; - 65B364DE121C261F003EAD18 /* actioncontainer.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = actioncontainer.cpp; sourceTree = ""; }; - 65B364DF121C261F003EAD18 /* actioncontainer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = actioncontainer.h; sourceTree = ""; }; - 65B364E0121C261F003EAD18 /* actioncontainer_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = actioncontainer_p.h; sourceTree = ""; }; - 65B364E1121C261F003EAD18 /* actionmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = actionmanager.cpp; sourceTree = ""; }; - 65B364E2121C261F003EAD18 /* actionmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = actionmanager.h; sourceTree = ""; }; - 65B364E3121C261F003EAD18 /* actionmanager_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = actionmanager_p.h; sourceTree = ""; }; - 65B364E4121C261F003EAD18 /* command.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = command.cpp; sourceTree = ""; }; - 65B364E5121C261F003EAD18 /* command.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = command.h; sourceTree = ""; }; - 65B364E6121C261F003EAD18 /* command_p.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = command_p.h; sourceTree = ""; }; - 65B364E7121C261F003EAD18 /* commandsfile.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = commandsfile.cpp; sourceTree = ""; }; - 65B364E8121C261F003EAD18 /* commandsfile.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = commandsfile.h; sourceTree = ""; }; - 65B364E9121C261F003EAD18 /* basemode.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = basemode.cpp; sourceTree = ""; }; - 65B364EA121C261F003EAD18 /* basemode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = basemode.h; sourceTree = ""; }; - 65B364EB121C261F003EAD18 /* baseview.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = baseview.cpp; sourceTree = ""; }; - 65B364EC121C261F003EAD18 /* baseview.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = baseview.h; sourceTree = ""; }; - 65B364ED121C261F003EAD18 /* connectionmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = connectionmanager.cpp; sourceTree = ""; }; - 65B364EE121C261F003EAD18 /* connectionmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = connectionmanager.h; sourceTree = ""; }; - 65B364EF121C261F003EAD18 /* Core.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = Core.pluginspec; sourceTree = ""; }; - 65B364F0121C261F003EAD18 /* core.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = core.qrc; sourceTree = ""; }; - 65B364F1121C261F003EAD18 /* core_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = core_global.h; sourceTree = ""; }; - 65B364F2121C261F003EAD18 /* coreconstants.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = coreconstants.h; sourceTree = ""; }; - 65B364F3121C261F003EAD18 /* coreimpl.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = coreimpl.cpp; sourceTree = ""; }; - 65B364F4121C261F003EAD18 /* coreimpl.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = coreimpl.h; sourceTree = ""; }; - 65B364F5121C261F003EAD18 /* coreplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = coreplugin.cpp; sourceTree = ""; }; - 65B364F6121C261F003EAD18 /* coreplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = coreplugin.h; sourceTree = ""; }; - 65B364F7121C261F003EAD18 /* coreplugin.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = coreplugin.pri; sourceTree = ""; }; - 65B364F8121C261F003EAD18 /* coreplugin.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = coreplugin.pro; sourceTree = ""; }; - 65B364F9121C261F003EAD18 /* coreplugin_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = coreplugin_dependencies.pri; sourceTree = ""; }; - 65B364FB121C261F003EAD18 /* ioptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = ioptionspage.cpp; sourceTree = ""; }; - 65B364FC121C261F003EAD18 /* ioptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ioptionspage.h; sourceTree = ""; }; - 65B364FD121C261F003EAD18 /* iwizard.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = iwizard.cpp; sourceTree = ""; }; - 65B364FE121C261F003EAD18 /* iwizard.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = iwizard.h; sourceTree = ""; }; - 65B364FF121C261F003EAD18 /* settingsdialog.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = settingsdialog.cpp; sourceTree = ""; }; - 65B36500121C261F003EAD18 /* settingsdialog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = settingsdialog.h; sourceTree = ""; }; - 65B36501121C261F003EAD18 /* settingsdialog.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = settingsdialog.ui; sourceTree = ""; }; - 65B36502121C261F003EAD18 /* shortcutsettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = shortcutsettings.cpp; sourceTree = ""; }; - 65B36503121C261F003EAD18 /* shortcutsettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = shortcutsettings.h; sourceTree = ""; }; - 65B36504121C261F003EAD18 /* shortcutsettings.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = shortcutsettings.ui; sourceTree = ""; }; - 65B36505121C261F003EAD18 /* eventfilteringmainwindow.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = eventfilteringmainwindow.cpp; sourceTree = ""; }; - 65B36506121C261F003EAD18 /* eventfilteringmainwindow.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = eventfilteringmainwindow.h; sourceTree = ""; }; - 65B36507121C261F003EAD18 /* fancyactionbar.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = fancyactionbar.cpp; sourceTree = ""; }; - 65B36508121C261F003EAD18 /* fancyactionbar.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fancyactionbar.h; sourceTree = ""; }; - 65B36509121C261F003EAD18 /* fancyactionbar.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = fancyactionbar.qrc; sourceTree = ""; }; - 65B3650A121C261F003EAD18 /* fancytabwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = fancytabwidget.cpp; sourceTree = ""; }; - 65B3650B121C261F003EAD18 /* fancytabwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fancytabwidget.h; sourceTree = ""; }; - 65B3650C121C261F003EAD18 /* fileiconprovider.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = fileiconprovider.cpp; sourceTree = ""; }; - 65B3650D121C261F003EAD18 /* fileiconprovider.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fileiconprovider.h; sourceTree = ""; }; - 65B3650E121C261F003EAD18 /* generalsettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = generalsettings.cpp; sourceTree = ""; }; - 65B3650F121C261F003EAD18 /* generalsettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = generalsettings.h; sourceTree = ""; }; - 65B36510121C261F003EAD18 /* generalsettings.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = generalsettings.ui; sourceTree = ""; }; - 65B36511121C261F003EAD18 /* iconnection.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = iconnection.cpp; sourceTree = ""; }; - 65B36512121C261F003EAD18 /* iconnection.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = iconnection.h; sourceTree = ""; }; - 65B36513121C261F003EAD18 /* icontext.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = icontext.h; sourceTree = ""; }; - 65B36514121C261F003EAD18 /* icore.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = icore.cpp; sourceTree = ""; }; - 65B36515121C261F003EAD18 /* icore.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = icore.h; sourceTree = ""; }; - 65B36516121C261F003EAD18 /* icorelistener.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = icorelistener.h; sourceTree = ""; }; - 65B36518121C261F003EAD18 /* clean_pane_small.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = clean_pane_small.png; sourceTree = ""; }; - 65B36519121C261F003EAD18 /* clear.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = clear.png; sourceTree = ""; }; - 65B3651A121C261F003EAD18 /* closebutton.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = closebutton.png; sourceTree = ""; }; - 65B3651B121C261F003EAD18 /* darkclosebutton.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = darkclosebutton.png; sourceTree = ""; }; - 65B3651C121C261F003EAD18 /* dir.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = dir.png; sourceTree = ""; }; - 65B3651D121C261F003EAD18 /* editcopy.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = editcopy.png; sourceTree = ""; }; - 65B3651E121C261F003EAD18 /* editcut.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = editcut.png; sourceTree = ""; }; - 65B3651F121C261F003EAD18 /* editpaste.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = editpaste.png; sourceTree = ""; }; - 65B36520121C261F003EAD18 /* empty14.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = empty14.png; sourceTree = ""; }; - 65B36521121C261F003EAD18 /* exiticon.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = exiticon.png; sourceTree = ""; }; - 65B36522121C261F003EAD18 /* extension.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = extension.png; sourceTree = ""; }; - 65B36523121C261F003EAD18 /* fancytoolbutton.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = fancytoolbutton.svg; sourceTree = ""; }; - 65B36524121C261F003EAD18 /* filenew.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = filenew.png; sourceTree = ""; }; - 65B36525121C261F003EAD18 /* fileopen.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = fileopen.png; sourceTree = ""; }; - 65B36526121C261F003EAD18 /* filesave.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = filesave.png; sourceTree = ""; }; - 65B36527121C261F003EAD18 /* find.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = find.png; sourceTree = ""; }; - 65B36528121C261F003EAD18 /* findnext.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = findnext.png; sourceTree = ""; }; - 65B36529121C261F003EAD18 /* helpicon.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = helpicon.png; sourceTree = ""; }; - 65B3652A121C261F003EAD18 /* inputfield.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = inputfield.png; sourceTree = ""; }; - 65B3652B121C261F003EAD18 /* inputfield_disabled.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = inputfield_disabled.png; sourceTree = ""; }; - 65B3652C121C261F003EAD18 /* linkicon.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = linkicon.png; sourceTree = ""; }; - 65B3652D121C261F003EAD18 /* locked.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = locked.png; sourceTree = ""; }; - 65B3652E121C261F003EAD18 /* magnifier.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = magnifier.png; sourceTree = ""; }; - 65B3652F121C261F003EAD18 /* minus.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = minus.png; sourceTree = ""; }; - 65B36530121C261F003EAD18 /* mode_Debug.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = mode_Debug.png; sourceTree = ""; }; - 65B36531121C261F003EAD18 /* mode_Edit.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = mode_Edit.png; sourceTree = ""; }; - 65B36532121C261F003EAD18 /* mode_Output.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = mode_Output.png; sourceTree = ""; }; - 65B36533121C261F003EAD18 /* mode_Project.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = mode_Project.png; sourceTree = ""; }; - 65B36534121C261F003EAD18 /* mode_Reference.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = mode_Reference.png; sourceTree = ""; }; - 65B36535121C261F003EAD18 /* next.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = next.png; sourceTree = ""; }; - 65B36536121C261F003EAD18 /* openpilot_logo_128.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = openpilot_logo_128.png; sourceTree = ""; }; - 65B36537121C261F003EAD18 /* openpilot_logo_256.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = openpilot_logo_256.png; sourceTree = ""; }; - 65B36538121C261F003EAD18 /* openpilot_logo_32.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = openpilot_logo_32.png; sourceTree = ""; }; - 65B36539121C261F003EAD18 /* openpilot_logo_64.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = openpilot_logo_64.png; sourceTree = ""; }; - 65B3653A121C261F003EAD18 /* openpiloticon.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = openpiloticon.png; sourceTree = ""; }; - 65B3653B121C261F003EAD18 /* optionsicon.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = optionsicon.png; sourceTree = ""; }; - 65B3653C121C261F003EAD18 /* panel_button.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = panel_button.png; sourceTree = ""; }; - 65B3653D121C261F003EAD18 /* panel_button_checked.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = panel_button_checked.png; sourceTree = ""; }; - 65B3653E121C261F003EAD18 /* panel_button_checked_hover.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = panel_button_checked_hover.png; sourceTree = ""; }; - 65B3653F121C261F003EAD18 /* panel_button_hover.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = panel_button_hover.png; sourceTree = ""; }; - 65B36540121C261F003EAD18 /* panel_button_pressed.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = panel_button_pressed.png; sourceTree = ""; }; - 65B36541121C261F003EAD18 /* pluginicon.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = pluginicon.png; sourceTree = ""; }; - 65B36542121C261F003EAD18 /* plus.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = plus.png; sourceTree = ""; }; - 65B36543121C261F003EAD18 /* prev.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = prev.png; sourceTree = ""; }; - 65B36544121C261F003EAD18 /* pushbutton.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = pushbutton.png; sourceTree = ""; }; - 65B36545121C261F003EAD18 /* pushbutton_hover.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = pushbutton_hover.png; sourceTree = ""; }; - 65B36546121C261F003EAD18 /* pushbutton_pressed.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = pushbutton_pressed.png; sourceTree = ""; }; - 65B36547121C261F003EAD18 /* qtcreator_logo_32.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = qtcreator_logo_32.png; sourceTree = ""; }; - 65B36548121C261F003EAD18 /* qtwatermark.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = qtwatermark.png; sourceTree = ""; }; - 65B36549121C261F003EAD18 /* redo.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = redo.png; sourceTree = ""; }; - 65B3654A121C261F003EAD18 /* replace.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = replace.png; sourceTree = ""; }; - 65B3654B121C261F003EAD18 /* reset.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = reset.png; sourceTree = ""; }; - 65B3654C121C261F003EAD18 /* sidebaricon.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = sidebaricon.png; sourceTree = ""; }; - 65B3654D121C261F003EAD18 /* splitbutton_horizontal.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = splitbutton_horizontal.png; sourceTree = ""; }; - 65B3654E121C261F003EAD18 /* statusbar.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = statusbar.png; sourceTree = ""; }; - 65B3654F121C261F003EAD18 /* undo.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = undo.png; sourceTree = ""; }; - 65B36550121C261F003EAD18 /* unknownfile.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = unknownfile.png; sourceTree = ""; }; - 65B36551121C261F003EAD18 /* unlocked.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = unlocked.png; sourceTree = ""; }; - 65B36552121C261F003EAD18 /* imode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = imode.h; sourceTree = ""; }; - 65B36553121C261F003EAD18 /* ioutputpane.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ioutputpane.h; sourceTree = ""; }; - 65B36554121C261F003EAD18 /* iuavgadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = iuavgadget.cpp; sourceTree = ""; }; - 65B36555121C261F003EAD18 /* iuavgadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = iuavgadget.h; sourceTree = ""; }; - 65B36556121C261F003EAD18 /* iuavgadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = iuavgadgetconfiguration.cpp; sourceTree = ""; }; - 65B36557121C261F003EAD18 /* iuavgadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = iuavgadgetconfiguration.h; sourceTree = ""; }; - 65B36558121C261F003EAD18 /* iuavgadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = iuavgadgetfactory.h; sourceTree = ""; }; - 65B36559121C261F003EAD18 /* iversioncontrol.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = iversioncontrol.h; sourceTree = ""; }; - 65B3655A121C261F003EAD18 /* iview.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = iview.h; sourceTree = ""; }; - 65B3655B121C261F003EAD18 /* mainwindow.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mainwindow.cpp; sourceTree = ""; }; - 65B3655C121C261F003EAD18 /* mainwindow.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mainwindow.h; sourceTree = ""; }; - 65B3655D121C261F003EAD18 /* manhattanstyle.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = manhattanstyle.cpp; sourceTree = ""; }; - 65B3655E121C261F003EAD18 /* manhattanstyle.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = manhattanstyle.h; sourceTree = ""; }; - 65B3655F121C261F003EAD18 /* messagemanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = messagemanager.cpp; sourceTree = ""; }; - 65B36560121C261F003EAD18 /* messagemanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = messagemanager.h; sourceTree = ""; }; - 65B36561121C261F003EAD18 /* messageoutputwindow.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = messageoutputwindow.cpp; sourceTree = ""; }; - 65B36562121C261F003EAD18 /* messageoutputwindow.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = messageoutputwindow.h; sourceTree = ""; }; - 65B36563121C261F003EAD18 /* mimedatabase.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = mimedatabase.cpp; sourceTree = ""; }; - 65B36564121C261F003EAD18 /* mimedatabase.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mimedatabase.h; sourceTree = ""; }; - 65B36565121C261F003EAD18 /* minisplitter.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = minisplitter.cpp; sourceTree = ""; }; - 65B36566121C261F003EAD18 /* minisplitter.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = minisplitter.h; sourceTree = ""; }; - 65B36567121C261F003EAD18 /* modemanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = modemanager.cpp; sourceTree = ""; }; - 65B36568121C261F003EAD18 /* modemanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = modemanager.h; sourceTree = ""; }; - 65B36569121C261F003EAD18 /* outputpane.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = outputpane.h; sourceTree = ""; }; - 65B3656A121C261F003EAD18 /* plugindialog.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plugindialog.cpp; sourceTree = ""; }; - 65B3656B121C261F003EAD18 /* plugindialog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plugindialog.h; sourceTree = ""; }; - 65B3656C121C261F003EAD18 /* rightpane.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = rightpane.cpp; sourceTree = ""; }; - 65B3656D121C261F003EAD18 /* rightpane.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rightpane.h; sourceTree = ""; }; - 65B3656E121C261F003EAD18 /* settingsdatabase.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = settingsdatabase.cpp; sourceTree = ""; }; - 65B3656F121C261F003EAD18 /* settingsdatabase.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = settingsdatabase.h; sourceTree = ""; }; - 65B36570121C261F003EAD18 /* sidebar.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = sidebar.cpp; sourceTree = ""; }; - 65B36571121C261F003EAD18 /* sidebar.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = sidebar.h; sourceTree = ""; }; - 65B36572121C261F003EAD18 /* styleanimator.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = styleanimator.cpp; sourceTree = ""; }; - 65B36573121C261F003EAD18 /* styleanimator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = styleanimator.h; sourceTree = ""; }; - 65B36574121C261F003EAD18 /* tabpositionindicator.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = tabpositionindicator.cpp; sourceTree = ""; }; - 65B36575121C261F003EAD18 /* tabpositionindicator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = tabpositionindicator.h; sourceTree = ""; }; - 65B36576121C261F003EAD18 /* threadmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = threadmanager.cpp; sourceTree = ""; }; - 65B36577121C261F003EAD18 /* threadmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = threadmanager.h; sourceTree = ""; }; - 65B36578121C261F003EAD18 /* uavgadgetdecorator.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavgadgetdecorator.cpp; sourceTree = ""; }; - 65B36579121C261F003EAD18 /* uavgadgetdecorator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavgadgetdecorator.h; sourceTree = ""; }; - 65B3657A121C261F003EAD18 /* uavgadgetinstancemanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavgadgetinstancemanager.cpp; sourceTree = ""; }; - 65B3657B121C261F003EAD18 /* uavgadgetinstancemanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavgadgetinstancemanager.h; sourceTree = ""; }; - 65B3657D121C261F003EAD18 /* uavgadgetmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavgadgetmanager.cpp; sourceTree = ""; }; - 65B3657E121C261F003EAD18 /* uavgadgetmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavgadgetmanager.h; sourceTree = ""; }; - 65B3657F121C261F003EAD18 /* uavgadgetview.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavgadgetview.cpp; sourceTree = ""; }; - 65B36580121C261F003EAD18 /* uavgadgetview.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavgadgetview.h; sourceTree = ""; }; - 65B36581121C261F003EAD18 /* uavgadgetmode.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavgadgetmode.cpp; sourceTree = ""; }; - 65B36582121C261F003EAD18 /* uavgadgetmode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavgadgetmode.h; sourceTree = ""; }; - 65B36583121C261F003EAD18 /* uavgadgetoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = uavgadgetoptionspage.ui; sourceTree = ""; }; - 65B36584121C261F003EAD18 /* uavgadgetoptionspagedecorator.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavgadgetoptionspagedecorator.cpp; sourceTree = ""; }; - 65B36585121C261F003EAD18 /* uavgadgetoptionspagedecorator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavgadgetoptionspagedecorator.h; sourceTree = ""; }; - 65B36586121C261F003EAD18 /* uniqueidmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uniqueidmanager.cpp; sourceTree = ""; }; - 65B36587121C261F003EAD18 /* uniqueidmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uniqueidmanager.h; sourceTree = ""; }; - 65B36588121C261F003EAD18 /* variablemanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = variablemanager.cpp; sourceTree = ""; }; - 65B36589121C261F003EAD18 /* variablemanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = variablemanager.h; sourceTree = ""; }; - 65B3658A121C261F003EAD18 /* versiondialog.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = versiondialog.cpp; sourceTree = ""; }; - 65B3658B121C261F003EAD18 /* versiondialog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = versiondialog.h; sourceTree = ""; }; - 65B3658C121C261F003EAD18 /* viewmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = viewmanager.cpp; sourceTree = ""; }; - 65B3658D121C261F003EAD18 /* viewmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = viewmanager.h; sourceTree = ""; }; - 65B3658E121C261F003EAD18 /* workspacesettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = workspacesettings.cpp; sourceTree = ""; }; - 65B3658F121C261F003EAD18 /* workspacesettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = workspacesettings.h; sourceTree = ""; }; - 65B36590121C261F003EAD18 /* workspacesettings.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = workspacesettings.ui; sourceTree = ""; }; - 65B36592121C261F003EAD18 /* dial.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = dial.pro; sourceTree = ""; }; - 65B36593121C261F003EAD18 /* dial.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = dial.qrc; sourceTree = ""; }; - 65B36594121C261F003EAD18 /* dial_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = dial_dependencies.pri; sourceTree = ""; }; - 65B36595121C261F003EAD18 /* dialgadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = dialgadget.cpp; sourceTree = ""; }; - 65B36596121C261F003EAD18 /* dialgadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = dialgadget.h; sourceTree = ""; }; - 65B36597121C261F003EAD18 /* DialGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = DialGadget.pluginspec; sourceTree = ""; }; - 65B36598121C261F003EAD18 /* dialgadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = dialgadgetconfiguration.cpp; sourceTree = ""; }; - 65B36599121C261F003EAD18 /* dialgadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = dialgadgetconfiguration.h; sourceTree = ""; }; - 65B3659A121C261F003EAD18 /* dialgadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = dialgadgetfactory.cpp; sourceTree = ""; }; - 65B3659B121C261F003EAD18 /* dialgadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = dialgadgetfactory.h; sourceTree = ""; }; - 65B3659C121C261F003EAD18 /* dialgadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = dialgadgetoptionspage.cpp; sourceTree = ""; }; - 65B3659D121C261F003EAD18 /* dialgadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = dialgadgetoptionspage.h; sourceTree = ""; }; - 65B3659E121C261F003EAD18 /* dialgadgetoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = dialgadgetoptionspage.ui; sourceTree = ""; }; - 65B3659F121C261F003EAD18 /* dialgadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = dialgadgetwidget.cpp; sourceTree = ""; }; - 65B365A0121C261F003EAD18 /* dialgadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = dialgadgetwidget.h; sourceTree = ""; }; - 65B365A1121C261F003EAD18 /* dialplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = dialplugin.cpp; sourceTree = ""; }; - 65B365A2121C261F003EAD18 /* dialplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = dialplugin.h; sourceTree = ""; }; - 65B365A4121C261F003EAD18 /* empty.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = empty.svg; sourceTree = ""; }; - 65B365A6121C261F003EAD18 /* DoNothing.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = DoNothing.pluginspec; sourceTree = ""; }; - 65B365A7121C261F003EAD18 /* donothing.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = donothing.pro; sourceTree = ""; }; - 65B365A8121C261F003EAD18 /* donothingplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = donothingplugin.cpp; sourceTree = ""; }; - 65B365A9121C261F003EAD18 /* donothingplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = donothingplugin.h; sourceTree = ""; }; - 65B365AB121C261F003EAD18 /* emptygadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = emptygadget.cpp; sourceTree = ""; }; - 65B365AC121C261F003EAD18 /* emptygadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = emptygadget.h; sourceTree = ""; }; - 65B365AD121C261F003EAD18 /* EmptyGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = EmptyGadget.pluginspec; sourceTree = ""; }; - 65B365AE121C261F003EAD18 /* emptygadget.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = emptygadget.pro; sourceTree = ""; }; - 65B365AF121C261F003EAD18 /* emptygadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = emptygadgetfactory.cpp; sourceTree = ""; }; - 65B365B0121C261F003EAD18 /* emptygadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = emptygadgetfactory.h; sourceTree = ""; }; - 65B365B1121C261F003EAD18 /* emptygadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = emptygadgetwidget.cpp; sourceTree = ""; }; - 65B365B2121C261F003EAD18 /* emptygadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = emptygadgetwidget.h; sourceTree = ""; }; - 65B365B3121C261F003EAD18 /* emptyplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = emptyplugin.cpp; sourceTree = ""; }; - 65B365B4121C261F003EAD18 /* emptyplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = emptyplugin.h; sourceTree = ""; }; - 65B365B6121C261F003EAD18 /* GCSControl.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GCSControl.pluginspec; sourceTree = ""; }; - 65B365B7121C261F003EAD18 /* gcscontrol.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = gcscontrol.pro; sourceTree = ""; }; - 65B365B8121C261F003EAD18 /* gcscontrol.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = gcscontrol.qrc; sourceTree = ""; }; - 65B365B9121C261F003EAD18 /* gcscontrol.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gcscontrol.ui; sourceTree = ""; }; - 65B365BA121C261F003EAD18 /* gcscontrolgadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gcscontrolgadget.cpp; sourceTree = ""; }; - 65B365BB121C261F003EAD18 /* gcscontrolgadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gcscontrolgadget.h; sourceTree = ""; }; - 65B365BC121C261F003EAD18 /* gcscontrolgadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gcscontrolgadgetfactory.cpp; sourceTree = ""; }; - 65B365BD121C261F003EAD18 /* gcscontrolgadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gcscontrolgadgetfactory.h; sourceTree = ""; }; - 65B365BE121C261F003EAD18 /* gcscontrolgadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gcscontrolgadgetwidget.cpp; sourceTree = ""; }; - 65B365BF121C261F003EAD18 /* gcscontrolgadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gcscontrolgadgetwidget.h; sourceTree = ""; }; - 65B365C0121C261F003EAD18 /* gcscontrolplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gcscontrolplugin.cpp; sourceTree = ""; }; - 65B365C1121C261F003EAD18 /* gcscontrolplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gcscontrolplugin.h; sourceTree = ""; }; - 65B365C2121C261F003EAD18 /* gcsonctrolgadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gcsonctrolgadgetwidget.h; sourceTree = ""; }; - 65B365C4121C261F003EAD18 /* joystick.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = joystick.svg; sourceTree = ""; }; - 65B365C5121C261F003EAD18 /* joystickcontrol.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = joystickcontrol.cpp; sourceTree = ""; }; - 65B365C6121C261F003EAD18 /* joystickcontrol.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = joystickcontrol.h; sourceTree = ""; }; - 65B365C8121C261F003EAD18 /* buffer.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = buffer.cpp; sourceTree = ""; }; - 65B365C9121C261F003EAD18 /* buffer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = buffer.h; sourceTree = ""; }; - 65B365CA121C261F003EAD18 /* gpsdisplay.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = gpsdisplay.pro; sourceTree = ""; }; - 65B365CB121C261F003EAD18 /* gpsdisplay_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = gpsdisplay_dependencies.pri; sourceTree = ""; }; - 65B365CC121C261F003EAD18 /* gpsdisplaygadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gpsdisplaygadget.cpp; sourceTree = ""; }; - 65B365CD121C261F003EAD18 /* gpsdisplaygadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpsdisplaygadget.h; sourceTree = ""; }; - 65B365CE121C261F003EAD18 /* GpsDisplayGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = GpsDisplayGadget.pluginspec; sourceTree = ""; }; - 65B365CF121C261F003EAD18 /* gpsdisplaygadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gpsdisplaygadgetconfiguration.cpp; sourceTree = ""; }; - 65B365D0121C261F003EAD18 /* gpsdisplaygadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpsdisplaygadgetconfiguration.h; sourceTree = ""; }; - 65B365D1121C261F003EAD18 /* gpsdisplaygadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gpsdisplaygadgetfactory.cpp; sourceTree = ""; }; - 65B365D2121C261F003EAD18 /* gpsdisplaygadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpsdisplaygadgetfactory.h; sourceTree = ""; }; - 65B365D3121C261F003EAD18 /* gpsdisplaygadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gpsdisplaygadgetoptionspage.cpp; sourceTree = ""; }; - 65B365D4121C261F003EAD18 /* gpsdisplaygadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpsdisplaygadgetoptionspage.h; sourceTree = ""; }; - 65B365D5121C261F003EAD18 /* gpsdisplaygadgetoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gpsdisplaygadgetoptionspage.ui; sourceTree = ""; }; - 65B365D6121C261F003EAD18 /* gpsdisplayplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gpsdisplayplugin.cpp; sourceTree = ""; }; - 65B365D7121C261F003EAD18 /* gpsdisplayplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpsdisplayplugin.h; sourceTree = ""; }; - 65B365D8121C261F003EAD18 /* gpsdisplaythread.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gpsdisplaythread.cpp; sourceTree = ""; }; - 65B365D9121C261F003EAD18 /* gpsdisplaythread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpsdisplaythread.h; sourceTree = ""; }; - 65B365DA121C261F003EAD18 /* gpsdisplaywidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gpsdisplaywidget.cpp; sourceTree = ""; }; - 65B365DB121C261F003EAD18 /* gpsdisplaywidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpsdisplaywidget.h; sourceTree = ""; }; - 65B365DC121C261F003EAD18 /* gpsdisplaywidget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gpsdisplaywidget.ui; sourceTree = ""; }; - 65B365DE121C261F003EAD18 /* flatEarth.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = flatEarth.png; sourceTree = ""; }; - 65B365DF121C261F003EAD18 /* gpsEarth.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gpsEarth.svg; sourceTree = ""; }; - 65B365E0121C261F003EAD18 /* nmeaparser.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = nmeaparser.cpp; sourceTree = ""; }; - 65B365E1121C261F003EAD18 /* nmeaparser.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = nmeaparser.h; sourceTree = ""; }; - 65B365E2121C261F003EAD18 /* widgetresources.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = widgetresources.qrc; sourceTree = ""; }; - 65B365E4121C261F003EAD18 /* flightgearbridge.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = flightgearbridge.cpp; sourceTree = ""; }; - 65B365E5121C2620003EAD18 /* flightgearbridge.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = flightgearbridge.h; sourceTree = ""; }; - 65B365E6121C2620003EAD18 /* hitl.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitl.cpp; sourceTree = ""; }; - 65B365E7121C2620003EAD18 /* hitl.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitl.h; sourceTree = ""; }; - 65B365E8121C2620003EAD18 /* HITL.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = HITL.pluginspec; sourceTree = ""; }; - 65B365E9121C2620003EAD18 /* hitl.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = hitl.pro; sourceTree = ""; }; - 65B365EA121C2620003EAD18 /* hitl_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = hitl_dependencies.pri; sourceTree = ""; }; - 65B365EB121C2620003EAD18 /* hitlconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitlconfiguration.cpp; sourceTree = ""; }; - 65B365EC121C2620003EAD18 /* hitlconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitlconfiguration.h; sourceTree = ""; }; - 65B365ED121C2620003EAD18 /* hitlfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitlfactory.cpp; sourceTree = ""; }; - 65B365EE121C2620003EAD18 /* hitlfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitlfactory.h; sourceTree = ""; }; - 65B365EF121C2620003EAD18 /* hitloptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitloptionspage.cpp; sourceTree = ""; }; - 65B365F0121C2620003EAD18 /* hitloptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitloptionspage.h; sourceTree = ""; }; - 65B365F1121C2620003EAD18 /* hitloptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = hitloptionspage.ui; sourceTree = ""; }; - 65B365F2121C2620003EAD18 /* hitlplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitlplugin.cpp; sourceTree = ""; }; - 65B365F3121C2620003EAD18 /* hitlplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitlplugin.h; sourceTree = ""; }; - 65B365F4121C2620003EAD18 /* hitlresources.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = hitlresources.qrc; sourceTree = ""; }; - 65B365F5121C2620003EAD18 /* hitlwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitlwidget.cpp; sourceTree = ""; }; - 65B365F6121C2620003EAD18 /* hitlwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitlwidget.h; sourceTree = ""; }; - 65B365F7121C2620003EAD18 /* hitlwidget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = hitlwidget.ui; sourceTree = ""; }; - 65B365F8121C2620003EAD18 /* opfgprotocol.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = opfgprotocol.xml; sourceTree = ""; }; - 65B365FA121C2620003EAD18 /* hitlil2.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitlil2.cpp; sourceTree = ""; }; - 65B365FB121C2620003EAD18 /* hitlil2.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitlil2.h; sourceTree = ""; }; - 65B365FC121C2620003EAD18 /* HITLIL2.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = HITLIL2.pluginspec; sourceTree = ""; }; - 65B365FD121C2620003EAD18 /* hitlil2.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = hitlil2.pro; sourceTree = ""; }; - 65B365FE121C2620003EAD18 /* hitlil2_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = hitlil2_dependencies.pri; sourceTree = ""; }; - 65B365FF121C2620003EAD18 /* hitlil2configuration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitlil2configuration.cpp; sourceTree = ""; }; - 65B36600121C2620003EAD18 /* hitlil2configuration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitlil2configuration.h; sourceTree = ""; }; - 65B36601121C2620003EAD18 /* hitlil2factory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitlil2factory.cpp; sourceTree = ""; }; - 65B36602121C2620003EAD18 /* hitlil2factory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitlil2factory.h; sourceTree = ""; }; - 65B36603121C2620003EAD18 /* hitlil2optionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitlil2optionspage.cpp; sourceTree = ""; }; - 65B36604121C2620003EAD18 /* hitlil2optionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitlil2optionspage.h; sourceTree = ""; }; - 65B36605121C2620003EAD18 /* hitlil2optionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = hitlil2optionspage.ui; sourceTree = ""; }; - 65B36606121C2620003EAD18 /* hitlil2plugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitlil2plugin.cpp; sourceTree = ""; }; - 65B36607121C2620003EAD18 /* hitlil2plugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitlil2plugin.h; sourceTree = ""; }; - 65B36608121C2620003EAD18 /* hitlil2widget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = hitlil2widget.cpp; sourceTree = ""; }; - 65B36609121C2620003EAD18 /* hitlil2widget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = hitlil2widget.h; sourceTree = ""; }; - 65B3660A121C2620003EAD18 /* hitlil2widget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = hitlil2widget.ui; sourceTree = ""; }; - 65B3660B121C2620003EAD18 /* il2bridge.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = il2bridge.cpp; sourceTree = ""; }; - 65B3660C121C2620003EAD18 /* il2bridge.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = il2bridge.h; sourceTree = ""; }; - 65B3660E121C2620003EAD18 /* importexport.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = importexport.pro; sourceTree = ""; }; - 65B3660F121C2620003EAD18 /* importexport_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = importexport_dependencies.pri; sourceTree = ""; }; - 65B36610121C2620003EAD18 /* importexport_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = importexport_global.h; sourceTree = ""; }; - 65B36611121C2620003EAD18 /* importexportgadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = importexportgadget.cpp; sourceTree = ""; }; - 65B36612121C2620003EAD18 /* importexportgadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = importexportgadget.h; sourceTree = ""; }; - 65B36613121C2620003EAD18 /* ImportExportGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = ImportExportGadget.pluginspec; sourceTree = ""; }; - 65B36614121C2620003EAD18 /* importexportgadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = importexportgadgetconfiguration.cpp; sourceTree = ""; }; - 65B36615121C2620003EAD18 /* importexportgadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = importexportgadgetconfiguration.h; sourceTree = ""; }; - 65B36616121C2620003EAD18 /* importexportgadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = importexportgadgetfactory.cpp; sourceTree = ""; }; - 65B36617121C2620003EAD18 /* importexportgadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = importexportgadgetfactory.h; sourceTree = ""; }; - 65B36618121C2620003EAD18 /* importexportgadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = importexportgadgetoptionspage.cpp; sourceTree = ""; }; - 65B36619121C2620003EAD18 /* importexportgadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = importexportgadgetoptionspage.h; sourceTree = ""; }; - 65B3661A121C2620003EAD18 /* importexportgadgetoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = importexportgadgetoptionspage.ui; sourceTree = ""; }; - 65B3661B121C2620003EAD18 /* importexportgadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = importexportgadgetwidget.cpp; sourceTree = ""; }; - 65B3661C121C2620003EAD18 /* importexportgadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = importexportgadgetwidget.h; sourceTree = ""; }; - 65B3661D121C2620003EAD18 /* importexportgadgetwidget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = importexportgadgetwidget.ui; sourceTree = ""; }; - 65B3661E121C2620003EAD18 /* importexportplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = importexportplugin.cpp; sourceTree = ""; }; - 65B3661F121C2620003EAD18 /* importexportplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = importexportplugin.h; sourceTree = ""; }; - 65B36621121C2620003EAD18 /* IPconnection.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = IPconnection.pluginspec; sourceTree = ""; }; - 65B36622121C2620003EAD18 /* ipconnection.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = ipconnection.pri; sourceTree = ""; }; - 65B36623121C2620003EAD18 /* ipconnection.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = ipconnection.pro; sourceTree = ""; }; - 65B36624121C2620003EAD18 /* ipconnection_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = ipconnection_dependencies.pri; sourceTree = ""; }; - 65B36625121C2620003EAD18 /* ipconnection_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ipconnection_global.h; sourceTree = ""; }; - 65B36626121C2620003EAD18 /* ipconnectionconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = ipconnectionconfiguration.cpp; sourceTree = ""; }; - 65B36627121C2620003EAD18 /* ipconnectionconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ipconnectionconfiguration.h; sourceTree = ""; }; - 65B36628121C2620003EAD18 /* ipconnectionoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = ipconnectionoptionspage.cpp; sourceTree = ""; }; - 65B36629121C2620003EAD18 /* ipconnectionoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ipconnectionoptionspage.h; sourceTree = ""; }; - 65B3662A121C2620003EAD18 /* ipconnectionoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ipconnectionoptionspage.ui; sourceTree = ""; }; - 65B3662B121C2620003EAD18 /* ipconnectionplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = ipconnectionplugin.cpp; sourceTree = ""; }; - 65B3662C121C2620003EAD18 /* ipconnectionplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ipconnectionplugin.h; sourceTree = ""; }; - 65B3662F121C2620003EAD18 /* empty.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = empty.svg; sourceTree = ""; }; - 65B36630121C2620003EAD18 /* lineardial.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = lineardial.pro; sourceTree = ""; }; - 65B36631121C2620003EAD18 /* lineardial.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = lineardial.qrc; sourceTree = ""; }; - 65B36632121C2620003EAD18 /* lineardial_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = lineardial_dependencies.pri; sourceTree = ""; }; - 65B36633121C2620003EAD18 /* lineardialgadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = lineardialgadget.cpp; sourceTree = ""; }; - 65B36634121C2620003EAD18 /* lineardialgadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = lineardialgadget.h; sourceTree = ""; }; - 65B36635121C2620003EAD18 /* LineardialGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = LineardialGadget.pluginspec; sourceTree = ""; }; - 65B36636121C2620003EAD18 /* lineardialgadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = lineardialgadgetconfiguration.cpp; sourceTree = ""; }; - 65B36637121C2620003EAD18 /* lineardialgadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = lineardialgadgetconfiguration.h; sourceTree = ""; }; - 65B36638121C2620003EAD18 /* lineardialgadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = lineardialgadgetfactory.cpp; sourceTree = ""; }; - 65B36639121C2620003EAD18 /* lineardialgadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = lineardialgadgetfactory.h; sourceTree = ""; }; - 65B3663A121C2620003EAD18 /* lineardialgadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = lineardialgadgetoptionspage.cpp; sourceTree = ""; }; - 65B3663B121C2620003EAD18 /* lineardialgadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = lineardialgadgetoptionspage.h; sourceTree = ""; }; - 65B3663C121C2620003EAD18 /* lineardialgadgetoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = lineardialgadgetoptionspage.ui; sourceTree = ""; }; - 65B3663D121C2620003EAD18 /* lineardialgadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = lineardialgadgetwidget.cpp; sourceTree = ""; }; - 65B3663E121C2620003EAD18 /* lineardialgadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = lineardialgadgetwidget.h; sourceTree = ""; }; - 65B3663F121C2620003EAD18 /* lineardialplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = lineardialplugin.cpp; sourceTree = ""; }; - 65B36640121C2620003EAD18 /* lineardialplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = lineardialplugin.h; sourceTree = ""; }; - 65B36642121C2620003EAD18 /* modelview.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = modelview.pro; sourceTree = ""; }; - 65B36643121C2620003EAD18 /* modelview_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = modelview_dependencies.pri; sourceTree = ""; }; - 65B36644121C2620003EAD18 /* modelviewgadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = modelviewgadget.cpp; sourceTree = ""; }; - 65B36645121C2620003EAD18 /* modelviewgadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = modelviewgadget.h; sourceTree = ""; }; - 65B36646121C2620003EAD18 /* ModelViewGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = ModelViewGadget.pluginspec; sourceTree = ""; }; - 65B36647121C2620003EAD18 /* modelviewgadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = modelviewgadgetconfiguration.cpp; sourceTree = ""; }; - 65B36648121C2620003EAD18 /* modelviewgadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = modelviewgadgetconfiguration.h; sourceTree = ""; }; - 65B36649121C2620003EAD18 /* modelviewgadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = modelviewgadgetfactory.cpp; sourceTree = ""; }; - 65B3664A121C2620003EAD18 /* modelviewgadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = modelviewgadgetfactory.h; sourceTree = ""; }; - 65B3664B121C2620003EAD18 /* modelviewgadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = modelviewgadgetoptionspage.cpp; sourceTree = ""; }; - 65B3664C121C2620003EAD18 /* modelviewgadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = modelviewgadgetoptionspage.h; sourceTree = ""; }; - 65B3664D121C2620003EAD18 /* modelviewgadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = modelviewgadgetwidget.cpp; sourceTree = ""; }; - 65B3664E121C2620003EAD18 /* modelviewgadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = modelviewgadgetwidget.h; sourceTree = ""; }; - 65B3664F121C2620003EAD18 /* modelviewoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = modelviewoptionspage.ui; sourceTree = ""; }; - 65B36650121C2620003EAD18 /* modelviewplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = modelviewplugin.cpp; sourceTree = ""; }; - 65B36651121C2620003EAD18 /* modelviewplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = modelviewplugin.h; sourceTree = ""; }; - 65B36654121C2620003EAD18 /* add.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = add.png; sourceTree = ""; }; - 65B36655121C2620003EAD18 /* delete.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = delete.png; sourceTree = ""; }; - 65B36656121C2620003EAD18 /* modify.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = modify.png; sourceTree = ""; }; - 65B36657121C2620003EAD18 /* play.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = play.png; sourceTree = ""; }; - 65B36658121C2620003EAD18 /* play2.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = play2.png; sourceTree = ""; }; - 65B36659121C2620003EAD18 /* stop.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = stop.png; sourceTree = ""; }; - 65B3665A121C2620003EAD18 /* notify.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = notify.pro; sourceTree = ""; }; - 65B3665B121C2620003EAD18 /* notifyitemdelegate.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = notifyitemdelegate.cpp; sourceTree = ""; }; - 65B3665C121C2620003EAD18 /* notifyitemdelegate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = notifyitemdelegate.h; sourceTree = ""; }; - 65B3665D121C2620003EAD18 /* notifyplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = notifyplugin.cpp; sourceTree = ""; }; - 65B3665E121C2620003EAD18 /* notifyplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = notifyplugin.h; sourceTree = ""; }; - 65B3665F121C2620003EAD18 /* NotifyPlugin.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = NotifyPlugin.pluginspec; sourceTree = ""; }; - 65B36660121C2620003EAD18 /* notifyplugin_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = notifyplugin_dependencies.pri; sourceTree = ""; }; - 65B36661121C2620003EAD18 /* notifypluginconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = notifypluginconfiguration.cpp; sourceTree = ""; }; - 65B36662121C2620003EAD18 /* notifypluginconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = notifypluginconfiguration.h; sourceTree = ""; }; - 65B36663121C2620003EAD18 /* notifypluginfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = notifypluginfactory.cpp; sourceTree = ""; }; - 65B36664121C2620003EAD18 /* notifypluginfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = notifypluginfactory.h; sourceTree = ""; }; - 65B36665121C2620003EAD18 /* notifyplugingadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = notifyplugingadget.h; sourceTree = ""; }; - 65B36666121C2620003EAD18 /* notifypluginoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = notifypluginoptionspage.cpp; sourceTree = ""; }; - 65B36667121C2620003EAD18 /* notifypluginoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = notifypluginoptionspage.h; sourceTree = ""; }; - 65B36668121C2620003EAD18 /* notifypluginoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = notifypluginoptionspage.ui; sourceTree = ""; }; - 65B36669121C2620003EAD18 /* notifytablemodel.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = notifytablemodel.cpp; sourceTree = ""; }; - 65B3666A121C2620003EAD18 /* notifytablemodel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = notifytablemodel.h; sourceTree = ""; }; - 65B3666B121C2620003EAD18 /* res.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = res.qrc; sourceTree = ""; }; - 65B3666E121C2620003EAD18 /* Blank.psd */ = {isa = PBXFileReference; lastKnownFileType = file; path = Blank.psd; sourceTree = ""; }; - 65B3666F121C2620003EAD18 /* Blank_Pressed.psd */ = {isa = PBXFileReference; lastKnownFileType = file; path = Blank_Pressed.psd; sourceTree = ""; }; - 65B36670121C2620003EAD18 /* button_bar.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = button_bar.png; sourceTree = ""; }; - 65B36671121C2620003EAD18 /* circle.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = circle.png; sourceTree = ""; }; - 65B36672121C2620003EAD18 /* combobox_down_arrow.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = combobox_down_arrow.png; sourceTree = ""; }; - 65B36673121C2620003EAD18 /* gcs.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = gcs.png; sourceTree = ""; }; - 65B36674121C2620003EAD18 /* go.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = go.png; sourceTree = ""; }; - 65B36675121C2620003EAD18 /* hold.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = hold.png; sourceTree = ""; }; - 65B36676121C2620003EAD18 /* home.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = home.png; sourceTree = ""; }; - 65B36677121C2620003EAD18 /* hover.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = hover.png; sourceTree = ""; }; - 65B36678121C2620003EAD18 /* left_but.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = left_but.png; sourceTree = ""; }; - 65B36679121C2620003EAD18 /* minus.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = minus.png; sourceTree = ""; }; - 65B3667A121C2620003EAD18 /* minus2.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = minus2.png; sourceTree = ""; }; - 65B3667B121C2620003EAD18 /* next_waypoint.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = next_waypoint.png; sourceTree = ""; }; - 65B3667C121C2620003EAD18 /* ok.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = ok.png; sourceTree = ""; }; - 65B3667D121C2620003EAD18 /* pause.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = pause.png; sourceTree = ""; }; - 65B3667E121C2620003EAD18 /* plus.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = plus.png; sourceTree = ""; }; - 65B3667F121C2620003EAD18 /* plus2.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = plus2.png; sourceTree = ""; }; - 65B36680121C2620003EAD18 /* prev_waypoint.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = prev_waypoint.png; sourceTree = ""; }; - 65B36681121C2620003EAD18 /* right_but.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = right_but.png; sourceTree = ""; }; - 65B36682121C2620003EAD18 /* stop.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = stop.png; sourceTree = ""; }; - 65B36683121C2620003EAD18 /* uav.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = uav.png; sourceTree = ""; }; - 65B36684121C2620003EAD18 /* uav_heading.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = uav_heading.png; sourceTree = ""; }; - 65B36685121C2620003EAD18 /* uav_trail.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = uav_trail.png; sourceTree = ""; }; - 65B36686121C2620003EAD18 /* uav_trail_clear.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = uav_trail_clear.png; sourceTree = ""; }; - 65B36687121C2620003EAD18 /* waypoint.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = waypoint.png; sourceTree = ""; }; - 65B36688121C2620003EAD18 /* waypoint_marker1.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = waypoint_marker1.png; sourceTree = ""; }; - 65B36689121C2620003EAD18 /* waypoint_marker2.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = waypoint_marker2.png; sourceTree = ""; }; - 65B3668A121C2620003EAD18 /* opmap.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = opmap.pro; sourceTree = ""; }; - 65B3668B121C2620003EAD18 /* opmap.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = opmap.qrc; sourceTree = ""; }; - 65B3668C121C2620003EAD18 /* opmap_edit_waypoint_dialog.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmap_edit_waypoint_dialog.cpp; sourceTree = ""; }; - 65B3668D121C2620003EAD18 /* opmap_edit_waypoint_dialog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmap_edit_waypoint_dialog.h; sourceTree = ""; }; - 65B3668E121C2620003EAD18 /* opmap_edit_waypoint_dialog.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = opmap_edit_waypoint_dialog.ui; sourceTree = ""; }; - 65B3668F121C2620003EAD18 /* opmap_overlay_widget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmap_overlay_widget.cpp; sourceTree = ""; }; - 65B36690121C2620003EAD18 /* opmap_overlay_widget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmap_overlay_widget.h; sourceTree = ""; }; - 65B36691121C2620003EAD18 /* opmap_overlay_widget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = opmap_overlay_widget.ui; sourceTree = ""; }; - 65B36692121C2620003EAD18 /* opmap_statusbar_widget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmap_statusbar_widget.cpp; sourceTree = ""; }; - 65B36693121C2620003EAD18 /* opmap_statusbar_widget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmap_statusbar_widget.h; sourceTree = ""; }; - 65B36694121C2620003EAD18 /* opmap_statusbar_widget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = opmap_statusbar_widget.ui; sourceTree = ""; }; - 65B36695121C2620003EAD18 /* opmap_waypointeditor_dialog.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmap_waypointeditor_dialog.cpp; sourceTree = ""; }; - 65B36696121C2620003EAD18 /* opmap_waypointeditor_dialog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmap_waypointeditor_dialog.h; sourceTree = ""; }; - 65B36697121C2620003EAD18 /* opmap_waypointeditor_dialog.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = opmap_waypointeditor_dialog.ui; sourceTree = ""; }; - 65B36698121C2620003EAD18 /* opmap_widget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = opmap_widget.ui; sourceTree = ""; }; - 65B36699121C2620003EAD18 /* opmap_zoom_slider_widget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmap_zoom_slider_widget.cpp; sourceTree = ""; }; - 65B3669A121C2620003EAD18 /* opmap_zoom_slider_widget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmap_zoom_slider_widget.h; sourceTree = ""; }; - 65B3669B121C2620003EAD18 /* opmap_zoom_slider_widget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = opmap_zoom_slider_widget.ui; sourceTree = ""; }; - 65B3669C121C2620003EAD18 /* opmapgadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmapgadget.cpp; sourceTree = ""; }; - 65B3669D121C2620003EAD18 /* opmapgadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmapgadget.h; sourceTree = ""; }; - 65B3669E121C2620003EAD18 /* OPMapGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = OPMapGadget.pluginspec; sourceTree = ""; }; - 65B3669F121C2620003EAD18 /* opmapgadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmapgadgetconfiguration.cpp; sourceTree = ""; }; - 65B366A0121C2620003EAD18 /* opmapgadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmapgadgetconfiguration.h; sourceTree = ""; }; - 65B366A1121C2620003EAD18 /* opmapgadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmapgadgetfactory.cpp; sourceTree = ""; }; - 65B366A2121C2620003EAD18 /* opmapgadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmapgadgetfactory.h; sourceTree = ""; }; - 65B366A3121C2620003EAD18 /* opmapgadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmapgadgetoptionspage.cpp; sourceTree = ""; }; - 65B366A4121C2620003EAD18 /* opmapgadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmapgadgetoptionspage.h; sourceTree = ""; }; - 65B366A5121C2620003EAD18 /* opmapgadgetoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = opmapgadgetoptionspage.ui; sourceTree = ""; }; - 65B366A6121C2620003EAD18 /* opmapgadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmapgadgetwidget.cpp; sourceTree = ""; }; - 65B366A7121C2620003EAD18 /* opmapgadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmapgadgetwidget.h; sourceTree = ""; }; - 65B366A8121C2620003EAD18 /* opmapplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = opmapplugin.cpp; sourceTree = ""; }; - 65B366A9121C2620003EAD18 /* opmapplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = opmapplugin.h; sourceTree = ""; }; - 65B366AC121C2620003EAD18 /* pfd-default.svg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = "pfd-default.svg"; sourceTree = ""; }; - 65B366AD121C2620003EAD18 /* pfd.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pfd.pro; sourceTree = ""; }; - 65B366AE121C2620003EAD18 /* pfd.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pfd.qrc; sourceTree = ""; }; - 65B366AF121C2620003EAD18 /* pfd_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pfd_dependencies.pri; sourceTree = ""; }; - 65B366B0121C2620003EAD18 /* pfdgadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pfdgadget.cpp; sourceTree = ""; }; - 65B366B1121C2620003EAD18 /* pfdgadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pfdgadget.h; sourceTree = ""; }; - 65B366B2121C2620003EAD18 /* PFDGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = PFDGadget.pluginspec; sourceTree = ""; }; - 65B366B3121C2620003EAD18 /* pfdgadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pfdgadgetconfiguration.cpp; sourceTree = ""; }; - 65B366B4121C2620003EAD18 /* pfdgadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pfdgadgetconfiguration.h; sourceTree = ""; }; - 65B366B5121C2620003EAD18 /* pfdgadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pfdgadgetfactory.cpp; sourceTree = ""; }; - 65B366B6121C2620003EAD18 /* pfdgadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pfdgadgetfactory.h; sourceTree = ""; }; - 65B366B7121C2620003EAD18 /* pfdgadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pfdgadgetoptionspage.cpp; sourceTree = ""; }; - 65B366B8121C2620003EAD18 /* pfdgadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pfdgadgetoptionspage.h; sourceTree = ""; }; - 65B366B9121C2620003EAD18 /* pfdgadgetoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = pfdgadgetoptionspage.ui; sourceTree = ""; }; - 65B366BA121C2620003EAD18 /* pfdgadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pfdgadgetwidget.cpp; sourceTree = ""; }; - 65B366BB121C2620003EAD18 /* pfdgadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pfdgadgetwidget.h; sourceTree = ""; }; - 65B366BC121C2620003EAD18 /* pfdplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pfdplugin.cpp; sourceTree = ""; }; - 65B366BD121C2620003EAD18 /* pfdplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pfdplugin.h; sourceTree = ""; }; - 65B366BE121C2620003EAD18 /* plugins.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = plugins.pro; sourceTree = ""; }; - 65B366C0121C2620003EAD18 /* pjrc_rawhid.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pjrc_rawhid.h; sourceTree = ""; }; - 65B366C1121C2620003EAD18 /* pjrc_rawhid_mac.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pjrc_rawhid_mac.cpp; sourceTree = ""; }; - 65B366C2121C2620003EAD18 /* pjrc_rawhid_unix.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pjrc_rawhid_unix.cpp; sourceTree = ""; }; - 65B366C3121C2620003EAD18 /* pjrc_rawhid_win.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = pjrc_rawhid_win.cpp; sourceTree = ""; }; - 65B366C4121C2620003EAD18 /* rawhid.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = rawhid.cpp; sourceTree = ""; }; - 65B366C5121C2620003EAD18 /* rawhid.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rawhid.h; sourceTree = ""; }; - 65B366C6121C2620003EAD18 /* RawHID.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = RawHID.pluginspec; sourceTree = ""; }; - 65B366C7121C2620003EAD18 /* rawhid.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = rawhid.pri; sourceTree = ""; }; - 65B366C8121C2620003EAD18 /* rawhid.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = rawhid.pro; sourceTree = ""; }; - 65B366C9121C2620003EAD18 /* rawhid_const.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rawhid_const.h; sourceTree = ""; }; - 65B366CA121C2620003EAD18 /* rawhid_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = rawhid_dependencies.pri; sourceTree = ""; }; - 65B366CB121C2620003EAD18 /* rawhid_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rawhid_global.h; sourceTree = ""; }; - 65B366CC121C2620003EAD18 /* rawhidplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = rawhidplugin.cpp; sourceTree = ""; }; - 65B366CD121C2620003EAD18 /* rawhidplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rawhidplugin.h; sourceTree = ""; }; - 65B366CF121C2620003EAD18 /* plotdata.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plotdata.cpp; sourceTree = ""; }; - 65B366D0121C2620003EAD18 /* plotdata.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plotdata.h; sourceTree = ""; }; - 65B366D1121C2620003EAD18 /* scope.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = scope.pro; sourceTree = ""; }; - 65B366D2121C2620003EAD18 /* scopegadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = scopegadget.cpp; sourceTree = ""; }; - 65B366D3121C2620003EAD18 /* scopegadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = scopegadget.h; sourceTree = ""; }; - 65B366D4121C2620003EAD18 /* ScopeGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = ScopeGadget.pluginspec; sourceTree = ""; }; - 65B366D5121C2620003EAD18 /* scopegadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = scopegadgetconfiguration.cpp; sourceTree = ""; }; - 65B366D6121C2620003EAD18 /* scopegadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = scopegadgetconfiguration.h; sourceTree = ""; }; - 65B366D7121C2620003EAD18 /* scopegadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = scopegadgetfactory.cpp; sourceTree = ""; }; - 65B366D8121C2620003EAD18 /* scopegadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = scopegadgetfactory.h; sourceTree = ""; }; - 65B366D9121C2620003EAD18 /* scopegadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = scopegadgetoptionspage.cpp; sourceTree = ""; }; - 65B366DA121C2620003EAD18 /* scopegadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = scopegadgetoptionspage.h; sourceTree = ""; }; - 65B366DB121C2620003EAD18 /* scopegadgetoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = scopegadgetoptionspage.ui; sourceTree = ""; }; - 65B366DC121C2620003EAD18 /* scopegadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = scopegadgetwidget.cpp; sourceTree = ""; }; - 65B366DD121C2620003EAD18 /* scopegadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = scopegadgetwidget.h; sourceTree = ""; }; - 65B366DE121C2620003EAD18 /* scopeplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = scopeplugin.cpp; sourceTree = ""; }; - 65B366DF121C2620003EAD18 /* scopeplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = scopeplugin.h; sourceTree = ""; }; - 65B366E1121C2620003EAD18 /* Serial.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = Serial.pluginspec; sourceTree = ""; }; - 65B366E2121C2620003EAD18 /* serial.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = serial.pri; sourceTree = ""; }; - 65B366E3121C2620003EAD18 /* serial_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = serial_dependencies.pri; sourceTree = ""; }; - 65B366E4121C2620003EAD18 /* serial_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = serial_global.h; sourceTree = ""; }; - 65B366E5121C2620003EAD18 /* serialconnection.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = serialconnection.pro; sourceTree = ""; }; - 65B366E6121C2620003EAD18 /* serialplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = serialplugin.cpp; sourceTree = ""; }; - 65B366E7121C2620003EAD18 /* serialplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = serialplugin.h; sourceTree = ""; }; - 65B366E9121C2620003EAD18 /* systemhealth.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = systemhealth.pro; sourceTree = ""; }; - 65B366EA121C2620003EAD18 /* systemhealth_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = systemhealth_dependencies.pri; sourceTree = ""; }; - 65B366EB121C2620003EAD18 /* systemhealthgadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = systemhealthgadget.cpp; sourceTree = ""; }; - 65B366EC121C2620003EAD18 /* systemhealthgadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = systemhealthgadget.h; sourceTree = ""; }; - 65B366ED121C2620003EAD18 /* SystemHealthGadget.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = SystemHealthGadget.pluginspec; sourceTree = ""; }; - 65B366EE121C2620003EAD18 /* systemhealthgadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = systemhealthgadgetconfiguration.cpp; sourceTree = ""; }; - 65B366EF121C2620003EAD18 /* systemhealthgadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = systemhealthgadgetconfiguration.h; sourceTree = ""; }; - 65B366F0121C2620003EAD18 /* systemhealthgadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = systemhealthgadgetfactory.cpp; sourceTree = ""; }; - 65B366F1121C2620003EAD18 /* systemhealthgadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = systemhealthgadgetfactory.h; sourceTree = ""; }; - 65B366F2121C2620003EAD18 /* systemhealthgadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = systemhealthgadgetoptionspage.cpp; sourceTree = ""; }; - 65B366F3121C2620003EAD18 /* systemhealthgadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = systemhealthgadgetoptionspage.h; sourceTree = ""; }; - 65B366F4121C2620003EAD18 /* systemhealthgadgetoptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = systemhealthgadgetoptionspage.ui; sourceTree = ""; }; - 65B366F5121C2620003EAD18 /* systemhealthgadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = systemhealthgadgetwidget.cpp; sourceTree = ""; }; - 65B366F6121C2620003EAD18 /* systemhealthgadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = systemhealthgadgetwidget.h; sourceTree = ""; }; - 65B366F7121C2620003EAD18 /* systemhealthplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = systemhealthplugin.cpp; sourceTree = ""; }; - 65B366F8121C2620003EAD18 /* systemhealthplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = systemhealthplugin.h; sourceTree = ""; }; - 65B366FA121C2620003EAD18 /* browseritemdelegate.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = browseritemdelegate.cpp; sourceTree = ""; }; - 65B366FB121C2620003EAD18 /* browseritemdelegate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = browseritemdelegate.h; sourceTree = ""; }; - 65B366FC121C2620003EAD18 /* browserplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = browserplugin.cpp; sourceTree = ""; }; - 65B366FD121C2620003EAD18 /* browserplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = browserplugin.h; sourceTree = ""; }; - 65B366FE121C2620003EAD18 /* fieldtreeitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = fieldtreeitem.cpp; sourceTree = ""; }; - 65B366FF121C2620003EAD18 /* fieldtreeitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fieldtreeitem.h; sourceTree = ""; }; - 65B36700121C2620003EAD18 /* treeitem.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = treeitem.cpp; sourceTree = ""; }; - 65B36701121C2620003EAD18 /* treeitem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = treeitem.h; sourceTree = ""; }; - 65B36702121C2620003EAD18 /* uavobjectbrowser.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectbrowser.cpp; sourceTree = ""; }; - 65B36703121C2620003EAD18 /* uavobjectbrowser.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectbrowser.h; sourceTree = ""; }; - 65B36704121C2620003EAD18 /* UAVObjectBrowser.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = UAVObjectBrowser.pluginspec; sourceTree = ""; }; - 65B36705121C2620003EAD18 /* uavobjectbrowser.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavobjectbrowser.pro; sourceTree = ""; }; - 65B36706121C2620003EAD18 /* uavobjectbrowser.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = uavobjectbrowser.ui; sourceTree = ""; }; - 65B36707121C2620003EAD18 /* uavobjectbrowser_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavobjectbrowser_dependencies.pri; sourceTree = ""; }; - 65B36708121C2620003EAD18 /* uavobjectbrowserconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectbrowserconfiguration.cpp; sourceTree = ""; }; - 65B36709121C2620003EAD18 /* uavobjectbrowserconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectbrowserconfiguration.h; sourceTree = ""; }; - 65B3670A121C2620003EAD18 /* uavobjectbrowserfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectbrowserfactory.cpp; sourceTree = ""; }; - 65B3670B121C2620003EAD18 /* uavobjectbrowserfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectbrowserfactory.h; sourceTree = ""; }; - 65B3670C121C2620003EAD18 /* uavobjectbrowseroptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectbrowseroptionspage.cpp; sourceTree = ""; }; - 65B3670D121C2620003EAD18 /* uavobjectbrowseroptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectbrowseroptionspage.h; sourceTree = ""; }; - 65B3670E121C2620003EAD18 /* uavobjectbrowseroptionspage.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = uavobjectbrowseroptionspage.ui; sourceTree = ""; }; - 65B3670F121C2620003EAD18 /* uavobjectbrowserwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectbrowserwidget.cpp; sourceTree = ""; }; - 65B36710121C2620003EAD18 /* uavobjectbrowserwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectbrowserwidget.h; sourceTree = ""; }; - 65B36711121C2620003EAD18 /* uavobjecttreemodel.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjecttreemodel.cpp; sourceTree = ""; }; - 65B36712121C2620003EAD18 /* uavobjecttreemodel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjecttreemodel.h; sourceTree = ""; }; - 65B36714121C2620003EAD18 /* actuatorcommand.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = actuatorcommand.cpp; sourceTree = ""; }; - 65B36715121C2620003EAD18 /* actuatorcommand.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = actuatorcommand.h; sourceTree = ""; }; - 65B36716121C2620003EAD18 /* actuatorcommand.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = actuatorcommand.py; sourceTree = ""; }; - 65B36717121C2620003EAD18 /* actuatordesired.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = actuatordesired.cpp; sourceTree = ""; }; - 65B36718121C2620003EAD18 /* actuatordesired.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = actuatordesired.h; sourceTree = ""; }; - 65B36719121C2620003EAD18 /* actuatordesired.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = actuatordesired.py; sourceTree = ""; }; - 65B3671A121C2620003EAD18 /* actuatorsettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = actuatorsettings.cpp; sourceTree = ""; }; - 65B3671B121C2620003EAD18 /* actuatorsettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = actuatorsettings.h; sourceTree = ""; }; - 65B3671C121C2620003EAD18 /* actuatorsettings.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = actuatorsettings.py; sourceTree = ""; }; - 65B3671D121C2620003EAD18 /* ahrsstatus.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = ahrsstatus.cpp; sourceTree = ""; }; - 65B3671E121C2620003EAD18 /* ahrsstatus.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrsstatus.h; sourceTree = ""; }; - 65B3671F121C2620003EAD18 /* ahrsstatus.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = ahrsstatus.py; sourceTree = ""; }; - 65B36720121C2620003EAD18 /* altitudeactual.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = altitudeactual.cpp; sourceTree = ""; }; - 65B36721121C2620003EAD18 /* altitudeactual.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = altitudeactual.h; sourceTree = ""; }; - 65B36722121C2620003EAD18 /* altitudeactual.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = altitudeactual.py; sourceTree = ""; }; - 65B36723121C2620003EAD18 /* attitudeactual.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = attitudeactual.cpp; sourceTree = ""; }; - 65B36724121C2620003EAD18 /* attitudeactual.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = attitudeactual.h; sourceTree = ""; }; - 65B36725121C2620003EAD18 /* attitudeactual.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = attitudeactual.py; sourceTree = ""; }; - 65B36726121C2620003EAD18 /* attitudedesired.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = attitudedesired.cpp; sourceTree = ""; }; - 65B36727121C2620003EAD18 /* attitudedesired.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = attitudedesired.h; sourceTree = ""; }; - 65B36728121C2620003EAD18 /* attitudedesired.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = attitudedesired.py; sourceTree = ""; }; - 65B36729121C2620003EAD18 /* attituderaw.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = attituderaw.cpp; sourceTree = ""; }; - 65B3672A121C2620003EAD18 /* attituderaw.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = attituderaw.h; sourceTree = ""; }; - 65B3672B121C2620003EAD18 /* attituderaw.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = attituderaw.py; sourceTree = ""; }; - 65B3672C121C2620003EAD18 /* attitudesettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = attitudesettings.cpp; sourceTree = ""; }; - 65B3672D121C2620003EAD18 /* attitudesettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = attitudesettings.h; sourceTree = ""; }; - 65B3672E121C2620003EAD18 /* attitudesettings.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = attitudesettings.py; sourceTree = ""; }; - 65B3672F121C2620003EAD18 /* exampleobject1.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = exampleobject1.cpp; sourceTree = ""; }; - 65B36730121C2620003EAD18 /* exampleobject1.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = exampleobject1.h; sourceTree = ""; }; - 65B36731121C2620003EAD18 /* exampleobject1.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = exampleobject1.py; sourceTree = ""; }; - 65B36732121C2620003EAD18 /* exampleobject2.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = exampleobject2.cpp; sourceTree = ""; }; - 65B36733121C2620003EAD18 /* exampleobject2.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = exampleobject2.h; sourceTree = ""; }; - 65B36734121C2620003EAD18 /* exampleobject2.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = exampleobject2.py; sourceTree = ""; }; - 65B36735121C2620003EAD18 /* examplesettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = examplesettings.cpp; sourceTree = ""; }; - 65B36736121C2620003EAD18 /* examplesettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = examplesettings.h; sourceTree = ""; }; - 65B36737121C2620003EAD18 /* examplesettings.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = examplesettings.py; sourceTree = ""; }; - 65B36738121C2620003EAD18 /* flightbatterystate.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = flightbatterystate.cpp; sourceTree = ""; }; - 65B36739121C2620003EAD18 /* flightbatterystate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = flightbatterystate.h; sourceTree = ""; }; - 65B3673A121C2620003EAD18 /* flightbatterystate.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = flightbatterystate.py; sourceTree = ""; }; - 65B3673B121C2620003EAD18 /* flightsituationactual.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = flightsituationactual.cpp; sourceTree = ""; }; - 65B3673C121C2620003EAD18 /* flightsituationactual.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = flightsituationactual.h; sourceTree = ""; }; - 65B3673D121C2620003EAD18 /* flightsituationactual.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = flightsituationactual.py; sourceTree = ""; }; - 65B3673E121C2620003EAD18 /* flighttelemetrystats.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = flighttelemetrystats.cpp; sourceTree = ""; }; - 65B3673F121C2620003EAD18 /* flighttelemetrystats.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = flighttelemetrystats.h; sourceTree = ""; }; - 65B36740121C2620003EAD18 /* flighttelemetrystats.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = flighttelemetrystats.py; sourceTree = ""; }; - 65B36741121C2620003EAD18 /* gcstelemetrystats.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = gcstelemetrystats.cpp; sourceTree = ""; }; - 65B36742121C2620003EAD18 /* gcstelemetrystats.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gcstelemetrystats.h; sourceTree = ""; }; - 65B36743121C2620003EAD18 /* gcstelemetrystats.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = gcstelemetrystats.py; sourceTree = ""; }; - 65B36744121C2620003EAD18 /* manualcontrolcommand.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = manualcontrolcommand.cpp; sourceTree = ""; }; - 65B36745121C2620003EAD18 /* manualcontrolcommand.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = manualcontrolcommand.h; sourceTree = ""; }; - 65B36746121C2620003EAD18 /* manualcontrolcommand.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = manualcontrolcommand.py; sourceTree = ""; }; - 65B36747121C2620003EAD18 /* manualcontrolsettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = manualcontrolsettings.cpp; sourceTree = ""; }; - 65B36748121C2620003EAD18 /* manualcontrolsettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = manualcontrolsettings.h; sourceTree = ""; }; - 65B36749121C2620003EAD18 /* manualcontrolsettings.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = manualcontrolsettings.py; sourceTree = ""; }; - 65B3674A121C2620003EAD18 /* navigationdesired.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = navigationdesired.cpp; sourceTree = ""; }; - 65B3674B121C2620003EAD18 /* navigationdesired.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = navigationdesired.h; sourceTree = ""; }; - 65B3674C121C2620003EAD18 /* navigationdesired.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = navigationdesired.py; sourceTree = ""; }; - 65B3674D121C2620003EAD18 /* navigationsettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = navigationsettings.cpp; sourceTree = ""; }; - 65B3674E121C2620003EAD18 /* navigationsettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = navigationsettings.h; sourceTree = ""; }; - 65B3674F121C2620003EAD18 /* navigationsettings.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = navigationsettings.py; sourceTree = ""; }; - 65B36750121C2620003EAD18 /* objectpersistence.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = objectpersistence.cpp; sourceTree = ""; }; - 65B36751121C2620003EAD18 /* objectpersistence.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = objectpersistence.h; sourceTree = ""; }; - 65B36752121C2620003EAD18 /* objectpersistence.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = objectpersistence.py; sourceTree = ""; }; - 65B36753121C2620003EAD18 /* positionactual.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = positionactual.cpp; sourceTree = ""; }; - 65B36754121C2620003EAD18 /* positionactual.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = positionactual.h; sourceTree = ""; }; - 65B36755121C2620003EAD18 /* positionactual.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = positionactual.py; sourceTree = ""; }; - 65B36756121C2620003EAD18 /* stabilizationsettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = stabilizationsettings.cpp; sourceTree = ""; }; - 65B36757121C2620003EAD18 /* stabilizationsettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stabilizationsettings.h; sourceTree = ""; }; - 65B36758121C2620003EAD18 /* stabilizationsettings.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = stabilizationsettings.py; sourceTree = ""; }; - 65B36759121C2620003EAD18 /* systemalarms.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = systemalarms.cpp; sourceTree = ""; }; - 65B3675A121C2620003EAD18 /* systemalarms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = systemalarms.h; sourceTree = ""; }; - 65B3675B121C2620003EAD18 /* systemalarms.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = systemalarms.py; sourceTree = ""; }; - 65B3675C121C2620003EAD18 /* systemsettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = systemsettings.cpp; sourceTree = ""; }; - 65B3675D121C2620003EAD18 /* systemsettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = systemsettings.h; sourceTree = ""; }; - 65B3675E121C2620003EAD18 /* systemsettings.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = systemsettings.py; sourceTree = ""; }; - 65B3675F121C2620003EAD18 /* systemstats.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = systemstats.cpp; sourceTree = ""; }; - 65B36760121C2620003EAD18 /* systemstats.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = systemstats.h; sourceTree = ""; }; - 65B36761121C2620003EAD18 /* systemstats.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = systemstats.py; sourceTree = ""; }; - 65B36762121C2620003EAD18 /* telemetrysettings.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = telemetrysettings.cpp; sourceTree = ""; }; - 65B36763121C2620003EAD18 /* telemetrysettings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = telemetrysettings.h; sourceTree = ""; }; - 65B36764121C2620003EAD18 /* telemetrysettings.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = telemetrysettings.py; sourceTree = ""; }; - 65B36766121C2620003EAD18 /* main.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cpp; sourceTree = ""; }; - 65B36767121C2620003EAD18 /* uavobjectstest.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectstest.cpp; sourceTree = ""; }; - 65B36768121C2620003EAD18 /* uavobjectstest.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectstest.h; sourceTree = ""; }; - 65B36769121C2620003EAD18 /* uavobjectstest.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavobjectstest.pro; sourceTree = ""; }; - 65B3676A121C2620003EAD18 /* uavdataobject.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavdataobject.cpp; sourceTree = ""; }; - 65B3676B121C2620003EAD18 /* uavdataobject.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavdataobject.h; sourceTree = ""; }; - 65B3676C121C2620003EAD18 /* uavmetaobject.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavmetaobject.cpp; sourceTree = ""; }; - 65B3676D121C2620003EAD18 /* uavmetaobject.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavmetaobject.h; sourceTree = ""; }; - 65B3676E121C2620003EAD18 /* uavobject.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobject.cpp; sourceTree = ""; }; - 65B3676F121C2620003EAD18 /* uavobject.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobject.h; sourceTree = ""; }; - 65B36770121C2620003EAD18 /* uavobject.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = uavobject.py; sourceTree = ""; }; - 65B36771121C2620003EAD18 /* uavobjectfield.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectfield.cpp; sourceTree = ""; }; - 65B36772121C2620003EAD18 /* uavobjectfield.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectfield.h; sourceTree = ""; }; - 65B36773121C2620003EAD18 /* uavobjectmanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectmanager.cpp; sourceTree = ""; }; - 65B36774121C2620003EAD18 /* uavobjectmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectmanager.h; sourceTree = ""; }; - 65B36775121C2620003EAD18 /* UAVObjects.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = UAVObjects.pluginspec; sourceTree = ""; }; - 65B36776121C2620003EAD18 /* uavobjects.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavobjects.pri; sourceTree = ""; }; - 65B36777121C2620003EAD18 /* uavobjects.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavobjects.pro; sourceTree = ""; }; - 65B36778121C2620003EAD18 /* uavobjects_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavobjects_dependencies.pri; sourceTree = ""; }; - 65B36779121C2620003EAD18 /* uavobjects_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjects_global.h; sourceTree = ""; }; - 65B3677A121C2620003EAD18 /* uavobjectsinit.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectsinit.cpp; sourceTree = ""; }; - 65B3677B121C2620003EAD18 /* uavobjectsinit.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectsinit.h; sourceTree = ""; }; - 65B3677C121C2620003EAD18 /* uavobjectsinittemplate.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectsinittemplate.cpp; sourceTree = ""; }; - 65B3677D121C2620003EAD18 /* uavobjectsplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjectsplugin.cpp; sourceTree = ""; }; - 65B3677E121C2620003EAD18 /* uavobjectsplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectsplugin.h; sourceTree = ""; }; - 65B3677F121C2620003EAD18 /* uavobjecttemplate.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavobjecttemplate.cpp; sourceTree = ""; }; - 65B36780121C2620003EAD18 /* uavobjecttemplate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjecttemplate.h; sourceTree = ""; }; - 65B36781121C2620003EAD18 /* uavobjecttemplate.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = uavobjecttemplate.py; sourceTree = ""; }; - 65B36783121C2620003EAD18 /* telemetry.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = telemetry.cpp; sourceTree = ""; }; - 65B36784121C2620003EAD18 /* telemetry.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = telemetry.h; sourceTree = ""; }; - 65B36785121C2620003EAD18 /* telemetrymanager.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = telemetrymanager.cpp; sourceTree = ""; }; - 65B36786121C2620003EAD18 /* telemetrymanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = telemetrymanager.h; sourceTree = ""; }; - 65B36787121C2620003EAD18 /* telemetrymonitor.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = telemetrymonitor.cpp; sourceTree = ""; }; - 65B36788121C2620003EAD18 /* telemetrymonitor.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = telemetrymonitor.h; sourceTree = ""; }; - 65B36789121C2620003EAD18 /* uavtalk.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavtalk.cpp; sourceTree = ""; }; - 65B3678A121C2620003EAD18 /* uavtalk.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavtalk.h; sourceTree = ""; }; - 65B3678B121C2620003EAD18 /* UAVTalk.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = UAVTalk.pluginspec; sourceTree = ""; }; - 65B3678C121C2620003EAD18 /* uavtalk.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavtalk.pri; sourceTree = ""; }; - 65B3678D121C2620003EAD18 /* uavtalk.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavtalk.pro; sourceTree = ""; }; - 65B3678E121C2620003EAD18 /* uavtalk_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavtalk_dependencies.pri; sourceTree = ""; }; - 65B3678F121C2620003EAD18 /* uavtalk_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavtalk_global.h; sourceTree = ""; }; - 65B36790121C2620003EAD18 /* uavtalkplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uavtalkplugin.cpp; sourceTree = ""; }; - 65B36791121C2620003EAD18 /* uavtalkplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavtalkplugin.h; sourceTree = ""; }; - 65B36793121C2620003EAD18 /* Uploader.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = Uploader.pluginspec; sourceTree = ""; }; - 65B36794121C2620003EAD18 /* uploader.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uploader.pro; sourceTree = ""; }; - 65B36795121C2620003EAD18 /* uploadergadget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uploadergadget.cpp; sourceTree = ""; }; - 65B36796121C2620003EAD18 /* uploadergadget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uploadergadget.h; sourceTree = ""; }; - 65B36797121C2620003EAD18 /* uploadergadgetconfiguration.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uploadergadgetconfiguration.cpp; sourceTree = ""; }; - 65B36798121C2620003EAD18 /* uploadergadgetconfiguration.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uploadergadgetconfiguration.h; sourceTree = ""; }; - 65B36799121C2620003EAD18 /* uploadergadgetfactory.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uploadergadgetfactory.cpp; sourceTree = ""; }; - 65B3679A121C2620003EAD18 /* uploadergadgetfactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uploadergadgetfactory.h; sourceTree = ""; }; - 65B3679B121C2620003EAD18 /* uploadergadgetoptionspage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uploadergadgetoptionspage.cpp; sourceTree = ""; }; - 65B3679C121C2620003EAD18 /* uploadergadgetoptionspage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uploadergadgetoptionspage.h; sourceTree = ""; }; - 65B3679D121C2620003EAD18 /* uploadergadgetwidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uploadergadgetwidget.cpp; sourceTree = ""; }; - 65B3679E121C2620003EAD18 /* uploadergadgetwidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uploadergadgetwidget.h; sourceTree = ""; }; - 65B3679F121C2620003EAD18 /* uploaderplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = uploaderplugin.cpp; sourceTree = ""; }; - 65B367A0121C2620003EAD18 /* uploaderplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uploaderplugin.h; sourceTree = ""; }; - 65B367A2121C2620003EAD18 /* communitywelcomepage.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = communitywelcomepage.cpp; sourceTree = ""; }; - 65B367A3121C2620003EAD18 /* communitywelcomepage.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = communitywelcomepage.h; sourceTree = ""; }; - 65B367A4121C2620003EAD18 /* communitywelcomepagewidget.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = communitywelcomepagewidget.cpp; sourceTree = ""; }; - 65B367A5121C2620003EAD18 /* communitywelcomepagewidget.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = communitywelcomepagewidget.h; sourceTree = ""; }; - 65B367A6121C2620003EAD18 /* communitywelcomepagewidget.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = communitywelcomepagewidget.ui; sourceTree = ""; }; - 65B367A8121C2620003EAD18 /* arrow-left.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = "arrow-left.png"; sourceTree = ""; }; - 65B367A9121C2620003EAD18 /* arrow-right.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = "arrow-right.png"; sourceTree = ""; }; - 65B367AA121C2620003EAD18 /* background_center_frame.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = background_center_frame.png; sourceTree = ""; }; - 65B367AB121C2620003EAD18 /* btn_26.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = btn_26.png; sourceTree = ""; }; - 65B367AC121C2620003EAD18 /* btn_26_hover.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = btn_26_hover.png; sourceTree = ""; }; - 65B367AD121C2620003EAD18 /* btn_26_pressed.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = btn_26_pressed.png; sourceTree = ""; }; - 65B367AE121C2620003EAD18 /* btn_27.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = btn_27.png; sourceTree = ""; }; - 65B367AF121C2620003EAD18 /* btn_27_hover.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = btn_27_hover.png; sourceTree = ""; }; - 65B367B0121C2620003EAD18 /* center_frame_header.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = center_frame_header.png; sourceTree = ""; }; - 65B367B1121C2620003EAD18 /* combobox_arrow.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = combobox_arrow.png; sourceTree = ""; }; - 65B367B2121C2620003EAD18 /* feedback-bar-background.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = "feedback-bar-background.png"; sourceTree = ""; }; - 65B367B3121C2620003EAD18 /* feedback_arrow.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = feedback_arrow.png; sourceTree = ""; }; - 65B367B4121C2620003EAD18 /* feedback_arrow_hover.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = feedback_arrow_hover.png; sourceTree = ""; }; - 65B367B5121C2620003EAD18 /* list_bullet_arrow.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = list_bullet_arrow.png; sourceTree = ""; }; - 65B367B6121C2620003EAD18 /* mode_project.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = mode_project.png; sourceTree = ""; }; - 65B367B7121C2620003EAD18 /* nokia_logo.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = nokia_logo.png; sourceTree = ""; }; - 65B367B8121C2620003EAD18 /* product_logo.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = product_logo.png; sourceTree = ""; }; - 65B367B9121C2620003EAD18 /* qt_logo.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = qt_logo.png; sourceTree = ""; }; - 65B367BA121C2620003EAD18 /* rc_combined.png */ = {isa = PBXFileReference; lastKnownFileType = image.png; path = rc_combined.png; sourceTree = ""; }; - 65B367BB121C2620003EAD18 /* rssfetcher.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = rssfetcher.cpp; sourceTree = ""; }; - 65B367BC121C2620003EAD18 /* rssfetcher.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rssfetcher.h; sourceTree = ""; }; - 65B367BD121C2620003EAD18 /* Welcome.pluginspec */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = Welcome.pluginspec; sourceTree = ""; }; - 65B367BE121C2620003EAD18 /* welcome.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = welcome.pri; sourceTree = ""; }; - 65B367BF121C2620003EAD18 /* welcome.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = welcome.pro; sourceTree = ""; }; - 65B367C0121C2620003EAD18 /* welcome.qrc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = welcome.qrc; sourceTree = ""; }; - 65B367C1121C2620003EAD18 /* welcome_dependencies.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = welcome_dependencies.pri; sourceTree = ""; }; - 65B367C2121C2620003EAD18 /* welcome_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = welcome_global.h; sourceTree = ""; }; - 65B367C3121C2620003EAD18 /* welcomemode.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = welcomemode.cpp; sourceTree = ""; }; - 65B367C4121C2620003EAD18 /* welcomemode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = welcomemode.h; sourceTree = ""; }; - 65B367C5121C2620003EAD18 /* welcomemode.ui */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = welcomemode.ui; sourceTree = ""; }; - 65B367C6121C2620003EAD18 /* welcomeplugin.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = welcomeplugin.cpp; sourceTree = ""; }; - 65B367C7121C2620003EAD18 /* welcomeplugin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = welcomeplugin.h; sourceTree = ""; }; - 65B367C8121C2620003EAD18 /* rpath.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = rpath.pri; sourceTree = ""; }; - 65B367CA121C2620003EAD18 /* namespace_global.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = namespace_global.h; sourceTree = ""; }; - 65B367CC121C2620003EAD18 /* namespace.patch */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = namespace.patch; sourceTree = ""; }; - 65B367CD121C2620003EAD18 /* qtlockedfile.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qtlockedfile.cpp; sourceTree = ""; }; - 65B367CE121C2620003EAD18 /* qtlockedfile.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qtlockedfile.h; sourceTree = ""; }; - 65B367CF121C2620003EAD18 /* qtlockedfile.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qtlockedfile.pri; sourceTree = ""; }; - 65B367D0121C2620003EAD18 /* qtlockedfile_unix.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qtlockedfile_unix.cpp; sourceTree = ""; }; - 65B367D1121C2620003EAD18 /* qtlockedfile_win.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qtlockedfile_win.cpp; sourceTree = ""; }; - 65B367D2121C2620003EAD18 /* README.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = README.txt; sourceTree = ""; }; - 65B367D4121C2620003EAD18 /* namespace.patch */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = namespace.patch; sourceTree = ""; }; - 65B367D5121C2620003EAD18 /* qtlocalpeer.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qtlocalpeer.cpp; sourceTree = ""; }; - 65B367D6121C2620003EAD18 /* qtlocalpeer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qtlocalpeer.h; sourceTree = ""; }; - 65B367D7121C2620003EAD18 /* qtsingleapplication.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qtsingleapplication.cpp; sourceTree = ""; }; - 65B367D8121C2620003EAD18 /* qtsingleapplication.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qtsingleapplication.h; sourceTree = ""; }; - 65B367D9121C2620003EAD18 /* qtsingleapplication.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qtsingleapplication.pri; sourceTree = ""; }; - 65B367DA121C2620003EAD18 /* qtsinglecoreapplication.cpp */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = qtsinglecoreapplication.cpp; sourceTree = ""; }; - 65B367DB121C2620003EAD18 /* qtsinglecoreapplication.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = qtsinglecoreapplication.h; sourceTree = ""; }; - 65B367DC121C2620003EAD18 /* qtsinglecoreapplication.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = qtsinglecoreapplication.pri; sourceTree = ""; }; - 65B367DD121C2620003EAD18 /* README.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = README.txt; sourceTree = ""; }; - 65B367DF121C2620003EAD18 /* interface_wrap_helpers.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = interface_wrap_helpers.h; sourceTree = ""; }; - 65B367E0121C2620003EAD18 /* README */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = README; sourceTree = ""; }; - 65B367E1121C2620003EAD18 /* scriptwrapper.pri */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = scriptwrapper.pri; sourceTree = ""; }; - 65B367E2121C2620003EAD18 /* wrap_helpers.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = wrap_helpers.h; sourceTree = ""; }; - 65B367E4121C2620003EAD18 /* actuatorcommand.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = actuatorcommand.xml; sourceTree = ""; }; - 65B367E5121C2620003EAD18 /* actuatordesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = actuatordesired.xml; sourceTree = ""; }; - 65B367E6121C2620003EAD18 /* actuatorsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = actuatorsettings.xml; sourceTree = ""; }; - 65B367E7121C2620003EAD18 /* ahrsstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrsstatus.xml; sourceTree = ""; }; - 65B367E9121C2620003EAD18 /* attitudeactual.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitudeactual.xml; sourceTree = ""; }; - 65B367EA121C2620003EAD18 /* attitudedesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitudedesired.xml; sourceTree = ""; }; - 65B367EB121C2620003EAD18 /* attituderaw.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attituderaw.xml; sourceTree = ""; }; - 65B367F0121C2620003EAD18 /* flightbatterystate.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightbatterystate.xml; sourceTree = ""; }; - 65B367F2121C2620003EAD18 /* flighttelemetrystats.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flighttelemetrystats.xml; sourceTree = ""; }; - 65B367F3121C2620003EAD18 /* gcstelemetrystats.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gcstelemetrystats.xml; sourceTree = ""; }; - 65B367F4121C2620003EAD18 /* manualcontrolcommand.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = manualcontrolcommand.xml; sourceTree = ""; }; - 65B367F5121C2620003EAD18 /* manualcontrolsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = manualcontrolsettings.xml; sourceTree = ""; }; - 65B367F8121C2620003EAD18 /* objectpersistence.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = objectpersistence.xml; sourceTree = ""; }; - 65B367F9121C2620003EAD18 /* positionactual.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = positionactual.xml; sourceTree = ""; }; - 65B367FA121C2620003EAD18 /* stabilizationsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = stabilizationsettings.xml; sourceTree = ""; }; - 65B367FB121C2620003EAD18 /* systemalarms.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = systemalarms.xml; sourceTree = ""; }; - 65B367FC121C2620003EAD18 /* systemsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = systemsettings.xml; sourceTree = ""; }; - 65B367FD121C2620003EAD18 /* systemstats.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = systemstats.xml; sourceTree = ""; }; - 65B367FE121C2620003EAD18 /* telemetrysettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = telemetrysettings.xml; sourceTree = ""; }; - 65B367FF121C2620003EAD18 /* src.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = src.pro; sourceTree = ""; }; - 65B7E6AE120DF1E2000C1123 /* ahrs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs.c; path = ../../AHRS/ahrs.c; sourceTree = SOURCE_ROOT; }; - 65B7E6B0120DF1E2000C1123 /* ahrs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs.h; sourceTree = ""; }; - 65B7E6B1120DF1E2000C1123 /* ahrs_fsm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_fsm.h; sourceTree = ""; }; - 65B7E6B4120DF1E2000C1123 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; - 65B7E6B6120DF1E2000C1123 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; name = Makefile; path = ../../AHRS/Makefile; sourceTree = SOURCE_ROOT; }; - 65B7E6B7120DF1E2000C1123 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_board.c; path = ../../AHRS/pios_board.c; sourceTree = SOURCE_ROOT; }; - 65C35E5012EFB2F3004811C2 /* actuatorcommand.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = actuatorcommand.xml; sourceTree = ""; }; - 65C35E5112EFB2F3004811C2 /* actuatordesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = actuatordesired.xml; sourceTree = ""; }; - 65C35E5212EFB2F3004811C2 /* actuatorsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = actuatorsettings.xml; sourceTree = ""; }; - 65C35E5312EFB2F3004811C2 /* ahrscalibration.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrscalibration.xml; sourceTree = ""; }; - 65C35E5412EFB2F3004811C2 /* ahrssettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrssettings.xml; sourceTree = ""; }; - 65C35E5512EFB2F3004811C2 /* ahrsstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrsstatus.xml; sourceTree = ""; }; - 65C35E5612EFB2F3004811C2 /* attitudeactual.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitudeactual.xml; sourceTree = ""; }; - 65C35E5812EFB2F3004811C2 /* attituderaw.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attituderaw.xml; sourceTree = ""; }; - 65C35E5912EFB2F3004811C2 /* baroaltitude.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = baroaltitude.xml; sourceTree = ""; }; - 65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightbatterystate.xml; sourceTree = ""; }; - 65C35E5D12EFB2F3004811C2 /* flightplancontrol.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightplancontrol.xml; sourceTree = ""; }; - 65C35E5E12EFB2F3004811C2 /* flightplansettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightplansettings.xml; sourceTree = ""; }; - 65C35E5F12EFB2F3004811C2 /* flightplanstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightplanstatus.xml; sourceTree = ""; }; - 65C35E6012EFB2F3004811C2 /* flighttelemetrystats.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flighttelemetrystats.xml; sourceTree = ""; }; - 65C35E6112EFB2F3004811C2 /* gcstelemetrystats.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gcstelemetrystats.xml; sourceTree = ""; }; - 65C35E6212EFB2F3004811C2 /* gpsposition.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gpsposition.xml; sourceTree = ""; }; - 65C35E6312EFB2F3004811C2 /* gpssatellites.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gpssatellites.xml; sourceTree = ""; }; - 65C35E6412EFB2F3004811C2 /* gpstime.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gpstime.xml; sourceTree = ""; }; - 65C35E6512EFB2F3004811C2 /* guidancesettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = guidancesettings.xml; sourceTree = ""; }; - 65C35E6612EFB2F3004811C2 /* homelocation.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = homelocation.xml; sourceTree = ""; }; - 65C35E6712EFB2F3004811C2 /* i2cstats.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = i2cstats.xml; sourceTree = ""; }; - 65C35E6812EFB2F3004811C2 /* manualcontrolcommand.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = manualcontrolcommand.xml; sourceTree = ""; }; - 65C35E6912EFB2F3004811C2 /* manualcontrolsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = manualcontrolsettings.xml; sourceTree = ""; }; - 65C35E6A12EFB2F3004811C2 /* mixersettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixersettings.xml; sourceTree = ""; }; - 65C35E6B12EFB2F3004811C2 /* mixerstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixerstatus.xml; sourceTree = ""; }; - 65C35E6C12EFB2F3004811C2 /* nedaccel.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = nedaccel.xml; sourceTree = ""; }; - 65C35E6D12EFB2F3004811C2 /* objectpersistence.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = objectpersistence.xml; sourceTree = ""; }; - 65C35E6E12EFB2F3004811C2 /* positionactual.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = positionactual.xml; sourceTree = ""; }; - 65C35E6F12EFB2F3004811C2 /* positiondesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = positiondesired.xml; sourceTree = ""; }; - 65C35E7012EFB2F3004811C2 /* ratedesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ratedesired.xml; sourceTree = ""; }; - 65C35E7112EFB2F3004811C2 /* stabilizationsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = stabilizationsettings.xml; sourceTree = ""; }; - 65C35E7212EFB2F3004811C2 /* systemalarms.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = systemalarms.xml; sourceTree = ""; }; - 65C35E7312EFB2F3004811C2 /* systemsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = systemsettings.xml; sourceTree = ""; }; - 65C35E7412EFB2F3004811C2 /* systemstats.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = systemstats.xml; sourceTree = ""; }; - 65C35E7512EFB2F3004811C2 /* taskinfo.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = taskinfo.xml; sourceTree = ""; }; - 65C35E7612EFB2F3004811C2 /* telemetrysettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = telemetrysettings.xml; sourceTree = ""; }; - 65C35E7712EFB2F3004811C2 /* velocityactual.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = velocityactual.xml; sourceTree = ""; }; - 65C35E7812EFB2F3004811C2 /* velocitydesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = velocitydesired.xml; sourceTree = ""; }; - 65C35E7912EFB2F3004811C2 /* watchdogstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = watchdogstatus.xml; sourceTree = ""; }; - 65C35E9E12F0A834004811C2 /* uavobjecttemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjecttemplate.c; sourceTree = ""; }; - 65C35E9F12F0A834004811C2 /* uavobjectsinittemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectsinittemplate.c; sourceTree = ""; }; - 65C35EA112F0A834004811C2 /* uavobjectmanager.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectmanager.c; sourceTree = ""; }; - 65C35EA312F0A834004811C2 /* eventdispatcher.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = eventdispatcher.h; sourceTree = ""; }; - 65C35EA412F0A834004811C2 /* uavobjectmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectmanager.h; sourceTree = ""; }; - 65C35EA512F0A834004811C2 /* uavobjectsinit.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectsinit.h; sourceTree = ""; }; - 65C35EA612F0A834004811C2 /* uavobjecttemplate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjecttemplate.h; sourceTree = ""; }; - 65C35EA712F0A834004811C2 /* utlist.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = utlist.h; sourceTree = ""; }; - 65C35EA812F0A834004811C2 /* eventdispatcher.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = eventdispatcher.c; sourceTree = ""; }; - 65C35F6612F0DC2D004811C2 /* attitude.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = attitude.c; sourceTree = ""; }; - 65C35F6812F0DC2D004811C2 /* attitude.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = attitude.h; sourceTree = ""; }; - 65C9903C13A871B90082BD60 /* camerastab.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = camerastab.c; sourceTree = ""; }; - 65C9903E13A871B90082BD60 /* camerastab.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = camerastab.h; sourceTree = ""; }; - 65D2CA841248F9A400B1E7D6 /* mixersettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixersettings.xml; sourceTree = ""; }; - 65D2CA851248F9A400B1E7D6 /* mixerstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixerstatus.xml; sourceTree = ""; }; - 65DEA79113F2143B00095B06 /* cameradesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = cameradesired.xml; sourceTree = ""; }; - 65E410AE12F65AEA00725888 /* attitudesettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitudesettings.xml; sourceTree = ""; }; - 65E6D80713E3A4D0002A557A /* hwsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = hwsettings.xml; sourceTree = ""; }; - 65E6DF7112E02E8E00058553 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65E6DF7312E02E8E00058553 /* alarms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = alarms.c; sourceTree = ""; }; - 65E6DF7412E02E8E00058553 /* coptercontrol.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = coptercontrol.c; sourceTree = ""; }; - 65E6DF7612E02E8E00058553 /* alarms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = alarms.h; sourceTree = ""; }; - 65E6DF7712E02E8E00058553 /* FreeRTOSConfig.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = FreeRTOSConfig.h; sourceTree = ""; }; - 65E6DF7812E02E8E00058553 /* op_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_config.h; sourceTree = ""; }; - 65E6DF7912E02E8E00058553 /* openpilot.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = openpilot.h; sourceTree = ""; }; - 65E6DF7A12E02E8E00058553 /* pios_board_posix.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_board_posix.h; sourceTree = ""; }; - 65E6DF7B12E02E8E00058553 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; - 65E6DF7C12E02E8E00058553 /* pios_config_posix.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config_posix.h; sourceTree = ""; }; - 65E6DF7D12E02E8E00058553 /* taskmonitor.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = taskmonitor.h; sourceTree = ""; }; - 65E6DF7E12E02E8E00058553 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; - 65E6DF7F12E02E8E00058553 /* pios_board_posix.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board_posix.c; sourceTree = ""; }; - 65E6DF8012E02E8E00058553 /* taskmonitor.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = taskmonitor.c; sourceTree = ""; }; - 65E6DF9112E0313E00058553 /* aes.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = aes.c; sourceTree = ""; }; - 65E6E04412E0313F00058553 /* crc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = crc.c; sourceTree = ""; }; - 65E6E04512E0313F00058553 /* gpio_in.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = gpio_in.c; sourceTree = ""; }; - 65E6E04712E0313F00058553 /* aes.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = aes.h; sourceTree = ""; }; - 65E6E04812E0313F00058553 /* crc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = crc.h; sourceTree = ""; }; - 65E6E04912E0313F00058553 /* gpio_in.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpio_in.h; sourceTree = ""; }; - 65E6E04A12E0313F00058553 /* main.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = main.h; sourceTree = ""; }; - 65E6E04B12E0313F00058553 /* packet_handler.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = packet_handler.h; sourceTree = ""; }; - 65E6E04C12E0313F00058553 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; - 65E6E04D12E0313F00058553 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = ""; }; - 65E6E04E12E0313F00058553 /* pios_usb_hid_desc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_desc.h; sourceTree = ""; }; - 65E6E04F12E0313F00058553 /* rfm22b.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rfm22b.h; sourceTree = ""; }; - 65E6E05012E0313F00058553 /* saved_settings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = saved_settings.h; sourceTree = ""; }; - 65E6E05112E0313F00058553 /* stopwatch.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stopwatch.h; sourceTree = ""; }; - 65E6E05212E0313F00058553 /* transparent_comms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = transparent_comms.h; sourceTree = ""; }; - 65E6E05312E0313F00058553 /* uavtalk_comms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavtalk_comms.h; sourceTree = ""; }; - 65E6E05412E0313F00058553 /* usb_conf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = usb_conf.h; sourceTree = ""; }; - 65E6E05512E0313F00058553 /* watchdog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = watchdog.h; sourceTree = ""; }; - 65E6E05612E0313F00058553 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; - 65E6E05712E0313F00058553 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65E6E05812E0313F00058553 /* packet_handler.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = packet_handler.c; sourceTree = ""; }; - 65E6E05912E0313F00058553 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; - 65E6E05A12E0313F00058553 /* pios_usb_hid_desc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb_hid_desc.c; sourceTree = ""; }; - 65E6E05B12E0313F00058553 /* rfm22b.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = rfm22b.c; sourceTree = ""; }; - 65E6E05C12E0313F00058553 /* saved_settings.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = saved_settings.c; sourceTree = ""; }; - 65E6E05D12E0313F00058553 /* stopwatch.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stopwatch.c; sourceTree = ""; }; - 65E6E05E12E0313F00058553 /* transparent_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = transparent_comms.c; sourceTree = ""; }; - 65E6E05F12E0313F00058553 /* uavtalk_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavtalk_comms.c; sourceTree = ""; }; - 65E6E06012E0313F00058553 /* watchdog.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = watchdog.c; sourceTree = ""; }; - 65E6E06112E031E300058553 /* STM32103CB_CC_Rev1.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM32103CB_CC_Rev1.h; sourceTree = ""; }; - 65E6E06212E031E300058553 /* STM32103CB_PIPXTREME_Rev1.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM32103CB_PIPXTREME_Rev1.h; sourceTree = ""; }; - 65E6E09912E037C800058553 /* pios_adc_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_adc_priv.h; sourceTree = ""; }; - 65E8C743139A6D0900E1F979 /* pios_crc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_crc.c; sourceTree = ""; }; - 65E8C745139A6D1A00E1F979 /* pios_crc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_crc.h; sourceTree = ""; }; - 65E8C788139AA2A800E1F979 /* accessorydesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = accessorydesired.xml; sourceTree = ""; }; - 65E8EF1F11EEA61E00BBF654 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; name = Makefile; path = ../../OpenPilot/Makefile; sourceTree = SOURCE_ROOT; }; - 65E8EF2011EEA61E00BBF654 /* Makefile.posix */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = Makefile.posix; path = ../../OpenPilot/Makefile.posix; sourceTree = SOURCE_ROOT; }; - 65E8EF5C11EEA61E00BBF654 /* alarms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = alarms.c; path = ../../OpenPilot/System/alarms.c; sourceTree = SOURCE_ROOT; }; - 65E8EF5E11EEA61E00BBF654 /* alarms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = alarms.h; path = ../../OpenPilot/System/inc/alarms.h; sourceTree = SOURCE_ROOT; }; - 65E8EF5F11EEA61E00BBF654 /* op_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = op_config.h; path = ../../OpenPilot/System/inc/op_config.h; sourceTree = SOURCE_ROOT; }; - 65E8EF6011EEA61E00BBF654 /* openpilot.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = openpilot.h; path = ../../OpenPilot/System/inc/openpilot.h; sourceTree = SOURCE_ROOT; }; - 65E8EF6111EEA61E00BBF654 /* pios_board.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_board.h; path = ../../OpenPilot/System/inc/pios_board.h; sourceTree = SOURCE_ROOT; }; - 65E8EF6211EEA61E00BBF654 /* pios_board_posix.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_board_posix.h; path = ../../OpenPilot/System/inc/pios_board_posix.h; sourceTree = SOURCE_ROOT; }; - 65E8EF6311EEA61E00BBF654 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_config.h; path = ../../OpenPilot/System/inc/pios_config.h; sourceTree = SOURCE_ROOT; }; - 65E8EF6411EEA61E00BBF654 /* pios_config_posix.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_config_posix.h; path = ../../OpenPilot/System/inc/pios_config_posix.h; sourceTree = SOURCE_ROOT; }; - 65E8EF6511EEA61E00BBF654 /* openpilot.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = openpilot.c; path = ../../OpenPilot/System/openpilot.c; sourceTree = SOURCE_ROOT; }; - 65E8EF6611EEA61E00BBF654 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_board.c; path = ../../OpenPilot/System/pios_board.c; sourceTree = SOURCE_ROOT; }; - 65E8EF6711EEA61E00BBF654 /* pios_board_posix.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_board_posix.c; path = ../../OpenPilot/System/pios_board_posix.c; sourceTree = SOURCE_ROOT; }; - 65E8EF6911EEA61E00BBF654 /* test_BMP085.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = test_BMP085.c; path = ../../OpenPilot/Tests/test_BMP085.c; sourceTree = SOURCE_ROOT; }; - 65E8EF6A11EEA61E00BBF654 /* test_common.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = test_common.c; path = ../../OpenPilot/Tests/test_common.c; sourceTree = SOURCE_ROOT; }; - 65E8EF6B11EEA61E00BBF654 /* test_cpuload.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = test_cpuload.c; path = ../../OpenPilot/Tests/test_cpuload.c; sourceTree = SOURCE_ROOT; }; - 65E8EF6C11EEA61E00BBF654 /* test_i2c_PCF8570.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = test_i2c_PCF8570.c; path = ../../OpenPilot/Tests/test_i2c_PCF8570.c; sourceTree = SOURCE_ROOT; }; - 65E8EF6D11EEA61E00BBF654 /* test_uavobjects.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = test_uavobjects.c; path = ../../OpenPilot/Tests/test_uavobjects.c; sourceTree = SOURCE_ROOT; }; - 65E8F03111EFF25C00BBF654 /* pios_bmp085.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_bmp085.c; path = ../../PiOS/Common/pios_bmp085.c; sourceTree = SOURCE_ROOT; }; - 65E8F03211EFF25C00BBF654 /* pios_com.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_com.c; path = ../../PiOS/Common/pios_com.c; sourceTree = SOURCE_ROOT; }; - 65E8F03311EFF25C00BBF654 /* pios_hmc5843.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_hmc5843.c; path = ../../PiOS/Common/pios_hmc5843.c; sourceTree = SOURCE_ROOT; }; - 65E8F03411EFF25C00BBF654 /* pios_opahrs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_opahrs.c; path = ../../PiOS/Common/pios_opahrs.c; sourceTree = SOURCE_ROOT; }; - 65E8F03511EFF25C00BBF654 /* pios_opahrs_proto.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_opahrs_proto.c; path = ../../PiOS/Common/pios_opahrs_proto.c; sourceTree = SOURCE_ROOT; }; - 65E8F03611EFF25C00BBF654 /* pios_sdcard.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_sdcard.c; path = ../../PiOS/Common/pios_sdcard.c; sourceTree = SOURCE_ROOT; }; - 65E8F03711EFF25C00BBF654 /* printf-stdarg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = "printf-stdarg.c"; path = "../../PiOS/Common/printf-stdarg.c"; sourceTree = SOURCE_ROOT; }; - 65E8F03A11EFF25C00BBF654 /* pios_adc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_adc.h; path = ../../PiOS/inc/pios_adc.h; sourceTree = SOURCE_ROOT; }; - 65E8F03B11EFF25C00BBF654 /* pios_bmp085.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_bmp085.h; path = ../../PiOS/inc/pios_bmp085.h; sourceTree = SOURCE_ROOT; }; - 65E8F03C11EFF25C00BBF654 /* pios_com.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_com.h; path = ../../PiOS/inc/pios_com.h; sourceTree = SOURCE_ROOT; }; - 65E8F03D11EFF25C00BBF654 /* pios_com_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_com_priv.h; path = ../../PiOS/inc/pios_com_priv.h; sourceTree = SOURCE_ROOT; }; - 65E8F03E11EFF25C00BBF654 /* pios_debug.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_debug.h; path = ../../PiOS/inc/pios_debug.h; sourceTree = SOURCE_ROOT; }; - 65E8F03F11EFF25C00BBF654 /* pios_delay.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_delay.h; path = ../../PiOS/inc/pios_delay.h; sourceTree = SOURCE_ROOT; }; - 65E8F04011EFF25C00BBF654 /* pios_exti.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_exti.h; path = ../../PiOS/inc/pios_exti.h; sourceTree = SOURCE_ROOT; }; - 65E8F04111EFF25C00BBF654 /* pios_gpio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_gpio.h; path = ../../PiOS/inc/pios_gpio.h; sourceTree = SOURCE_ROOT; }; - 65E8F04211EFF25C00BBF654 /* pios_hmc5843.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_hmc5843.h; path = ../../PiOS/inc/pios_hmc5843.h; sourceTree = SOURCE_ROOT; }; - 65E8F04311EFF25C00BBF654 /* pios_i2c.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_i2c.h; path = ../../PiOS/inc/pios_i2c.h; sourceTree = SOURCE_ROOT; }; - 65E8F04411EFF25C00BBF654 /* pios_irq.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_irq.h; path = ../../PiOS/inc/pios_irq.h; sourceTree = SOURCE_ROOT; }; - 65E8F04511EFF25C00BBF654 /* pios_led.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_led.h; path = ../../PiOS/inc/pios_led.h; sourceTree = SOURCE_ROOT; }; - 65E8F04611EFF25C00BBF654 /* pios_opahrs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_opahrs.h; path = ../../PiOS/inc/pios_opahrs.h; sourceTree = SOURCE_ROOT; }; - 65E8F04711EFF25C00BBF654 /* pios_opahrs_proto.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_opahrs_proto.h; path = ../../PiOS/inc/pios_opahrs_proto.h; sourceTree = SOURCE_ROOT; }; - 65E8F04811EFF25C00BBF654 /* pios_ppm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_ppm.h; path = ../../PiOS/inc/pios_ppm.h; sourceTree = SOURCE_ROOT; }; - 65E8F04911EFF25C00BBF654 /* pios_pwm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_pwm.h; path = ../../PiOS/inc/pios_pwm.h; sourceTree = SOURCE_ROOT; }; - 65E8F04A11EFF25C00BBF654 /* pios_sdcard.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_sdcard.h; path = ../../PiOS/inc/pios_sdcard.h; sourceTree = SOURCE_ROOT; }; - 65E8F04B11EFF25C00BBF654 /* pios_servo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_servo.h; path = ../../PiOS/inc/pios_servo.h; sourceTree = SOURCE_ROOT; }; - 65E8F04C11EFF25C00BBF654 /* pios_dsm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_dsm.h; path = ../../PiOS/inc/pios_dsm.h; sourceTree = SOURCE_ROOT; }; - 65E8F04D11EFF25C00BBF654 /* pios_spi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_spi.h; path = ../../PiOS/inc/pios_spi.h; sourceTree = SOURCE_ROOT; }; - 65E8F04E11EFF25C00BBF654 /* pios_spi_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_spi_priv.h; path = ../../PiOS/inc/pios_spi_priv.h; sourceTree = SOURCE_ROOT; }; - 65E8F04F11EFF25C00BBF654 /* pios_stm32.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_stm32.h; path = ../../PiOS/inc/pios_stm32.h; sourceTree = SOURCE_ROOT; }; - 65E8F05011EFF25C00BBF654 /* pios_sys.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_sys.h; path = ../../PiOS/inc/pios_sys.h; sourceTree = SOURCE_ROOT; }; - 65E8F05111EFF25C00BBF654 /* pios_usart.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_usart.h; path = ../../PiOS/inc/pios_usart.h; sourceTree = SOURCE_ROOT; }; - 65E8F05211EFF25C00BBF654 /* pios_usart_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_usart_priv.h; path = ../../PiOS/inc/pios_usart_priv.h; sourceTree = SOURCE_ROOT; }; - 65E8F05311EFF25C00BBF654 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_usb.h; path = ../../PiOS/inc/pios_usb.h; sourceTree = SOURCE_ROOT; }; - 65E8F05511EFF25C00BBF654 /* pios_usb_hid.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_usb_hid.h; path = ../../PiOS/inc/pios_usb_hid.h; sourceTree = SOURCE_ROOT; }; - 65E8F05611EFF25C00BBF654 /* stm32f10x_conf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_conf.h; path = ../../PiOS/inc/stm32f10x_conf.h; sourceTree = SOURCE_ROOT; }; - 65E8F05711EFF25C00BBF654 /* pios.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios.h; path = ../../PiOS/pios.h; sourceTree = SOURCE_ROOT; }; - 65E8F05D11EFF25C00BBF654 /* core_cm3.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = core_cm3.c; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/core_cm3.c; sourceTree = SOURCE_ROOT; }; - 65E8F05E11EFF25C00BBF654 /* core_cm3.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = core_cm3.h; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/core_cm3.h; sourceTree = SOURCE_ROOT; }; - 65E8F06111EFF25C00BBF654 /* startup_stm32f10x_cl.s */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_cl.s; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_cl.s; sourceTree = SOURCE_ROOT; }; - 65E8F06211EFF25C00BBF654 /* startup_stm32f10x_hd.s */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_hd.s; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_hd.s; sourceTree = SOURCE_ROOT; }; - 65E8F06311EFF25C00BBF654 /* startup_stm32f10x_ld.s */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_ld.s; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_ld.s; sourceTree = SOURCE_ROOT; }; - 65E8F06411EFF25C00BBF654 /* startup_stm32f10x_md.s */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_md.s; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_md.s; sourceTree = SOURCE_ROOT; }; - 65E8F06511EFF25C00BBF654 /* stm32f10x.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x.h; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/stm32f10x.h; sourceTree = SOURCE_ROOT; }; - 65E8F06611EFF25C00BBF654 /* system_stm32f10x.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = system_stm32f10x.c; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/system_stm32f10x.c; sourceTree = SOURCE_ROOT; }; - 65E8F06711EFF25C00BBF654 /* system_stm32f10x.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = system_stm32f10x.h; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/system_stm32f10x.h; sourceTree = SOURCE_ROOT; }; - 65E8F06911EFF25C00BBF654 /* CMSIS_Core.htm */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.html.documentation; name = CMSIS_Core.htm; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/Documentation/CMSIS_Core.htm; sourceTree = SOURCE_ROOT; }; - 65E8F06A11EFF25C00BBF654 /* License.doc */ = {isa = PBXFileReference; lastKnownFileType = file; name = License.doc; path = ../../PiOS/STM32F10x/Libraries/CMSIS/License.doc; sourceTree = SOURCE_ROOT; }; - 65E8F06C11EFF25C00BBF654 /* dfs_sdcard.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = dfs_sdcard.c; path = ../../PiOS/STM32F10x/Libraries/dosfs/dfs_sdcard.c; sourceTree = SOURCE_ROOT; }; - 65E8F06D11EFF25C00BBF654 /* dosfs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = dosfs.c; path = ../../PiOS/STM32F10x/Libraries/dosfs/dosfs.c; sourceTree = SOURCE_ROOT; }; - 65E8F06E11EFF25C00BBF654 /* dosfs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = dosfs.h; path = ../../PiOS/STM32F10x/Libraries/dosfs/dosfs.h; sourceTree = SOURCE_ROOT; }; - 65E8F06F11EFF25C00BBF654 /* README.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = README.txt; path = ../../PiOS/STM32F10x/Libraries/dosfs/README.txt; sourceTree = SOURCE_ROOT; }; - 65E8F07011EFF25C00BBF654 /* README_1st.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = README_1st.txt; path = ../../PiOS/STM32F10x/Libraries/dosfs/README_1st.txt; sourceTree = SOURCE_ROOT; }; - 65E8F07311EFF25C00BBF654 /* croutine.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = croutine.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/croutine.c; sourceTree = SOURCE_ROOT; }; - 65E8F07511EFF25C00BBF654 /* croutine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = croutine.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h; sourceTree = SOURCE_ROOT; }; - 65E8F07611EFF25C00BBF654 /* FreeRTOS.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = FreeRTOS.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h; sourceTree = SOURCE_ROOT; }; - 65E8F07711EFF25C00BBF654 /* list.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = list.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h; sourceTree = SOURCE_ROOT; }; - 65E8F07811EFF25C00BBF654 /* mpu_wrappers.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = mpu_wrappers.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h; sourceTree = SOURCE_ROOT; }; - 65E8F07911EFF25C00BBF654 /* portable.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = portable.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h; sourceTree = SOURCE_ROOT; }; - 65E8F07A11EFF25C00BBF654 /* projdefs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = projdefs.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h; sourceTree = SOURCE_ROOT; }; - 65E8F07B11EFF25C00BBF654 /* queue.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = queue.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h; sourceTree = SOURCE_ROOT; }; - 65E8F07C11EFF25C00BBF654 /* semphr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = semphr.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h; sourceTree = SOURCE_ROOT; }; - 65E8F07D11EFF25C00BBF654 /* StackMacros.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = StackMacros.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h; sourceTree = SOURCE_ROOT; }; - 65E8F07E11EFF25C00BBF654 /* task.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = task.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h; sourceTree = SOURCE_ROOT; }; - 65E8F07F11EFF25C00BBF654 /* list.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = list.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c; sourceTree = SOURCE_ROOT; }; - 65E8F08311EFF25C00BBF654 /* port.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = port.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c; sourceTree = SOURCE_ROOT; }; - 65E8F08411EFF25C00BBF654 /* portmacro.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = portmacro.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h; sourceTree = SOURCE_ROOT; }; - 65E8F08611EFF25C00BBF654 /* heap_1.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = heap_1.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_1.c; sourceTree = SOURCE_ROOT; }; - 65E8F08711EFF25C00BBF654 /* heap_2.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = heap_2.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_2.c; sourceTree = SOURCE_ROOT; }; - 65E8F08811EFF25C00BBF654 /* heap_3.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = heap_3.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c; sourceTree = SOURCE_ROOT; }; - 65E8F08911EFF25C00BBF654 /* readme.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = readme.txt; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/readme.txt; sourceTree = SOURCE_ROOT; }; - 65E8F08A11EFF25C00BBF654 /* queue.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = queue.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c; sourceTree = SOURCE_ROOT; }; - 65E8F08B11EFF25C00BBF654 /* readme.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = readme.txt; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/readme.txt; sourceTree = SOURCE_ROOT; }; - 65E8F08C11EFF25C00BBF654 /* tasks.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = tasks.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c; sourceTree = SOURCE_ROOT; }; - 65E8F08E11EFF25C00BBF654 /* msd.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd.c; sourceTree = SOURCE_ROOT; }; - 65E8F08F11EFF25C00BBF654 /* msd.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = msd.h; path = ../../PiOS/STM32F10x/Libraries/msd/msd.h; sourceTree = SOURCE_ROOT; }; - 65E8F09011EFF25C00BBF654 /* msd_bot.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd_bot.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd_bot.c; sourceTree = SOURCE_ROOT; }; - 65E8F09111EFF25C00BBF654 /* msd_bot.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = msd_bot.h; path = ../../PiOS/STM32F10x/Libraries/msd/msd_bot.h; sourceTree = SOURCE_ROOT; }; - 65E8F09211EFF25C00BBF654 /* msd_desc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd_desc.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd_desc.c; sourceTree = SOURCE_ROOT; }; - 65E8F09311EFF25C00BBF654 /* msd_desc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = msd_desc.h; path = ../../PiOS/STM32F10x/Libraries/msd/msd_desc.h; sourceTree = SOURCE_ROOT; }; - 65E8F09411EFF25C00BBF654 /* msd_memory.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd_memory.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd_memory.c; sourceTree = SOURCE_ROOT; }; - 65E8F09511EFF25C00BBF654 /* msd_memory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = msd_memory.h; path = ../../PiOS/STM32F10x/Libraries/msd/msd_memory.h; sourceTree = SOURCE_ROOT; }; - 65E8F09611EFF25C00BBF654 /* msd_scsi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd_scsi.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd_scsi.c; sourceTree = SOURCE_ROOT; }; - 65E8F09711EFF25C00BBF654 /* msd_scsi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = msd_scsi.h; path = ../../PiOS/STM32F10x/Libraries/msd/msd_scsi.h; sourceTree = SOURCE_ROOT; }; - 65E8F09811EFF25C00BBF654 /* msd_scsi_data.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd_scsi_data.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd_scsi_data.c; sourceTree = SOURCE_ROOT; }; - 65E8F09B11EFF25C00BBF654 /* usb_core.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_core.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_core.h"; sourceTree = SOURCE_ROOT; }; - 65E8F09C11EFF25C00BBF654 /* usb_def.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_def.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_def.h"; sourceTree = SOURCE_ROOT; }; - 65E8F09D11EFF25C00BBF654 /* usb_init.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_init.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_init.h"; sourceTree = SOURCE_ROOT; }; - 65E8F09E11EFF25C00BBF654 /* usb_int.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_int.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_int.h"; sourceTree = SOURCE_ROOT; }; - 65E8F09F11EFF25C00BBF654 /* usb_lib.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_lib.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_lib.h"; sourceTree = SOURCE_ROOT; }; - 65E8F0A011EFF25C00BBF654 /* usb_mem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_mem.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_mem.h"; sourceTree = SOURCE_ROOT; }; - 65E8F0A111EFF25C00BBF654 /* usb_regs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_regs.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_regs.h"; sourceTree = SOURCE_ROOT; }; - 65E8F0A211EFF25C00BBF654 /* usb_type.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_type.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_type.h"; sourceTree = SOURCE_ROOT; }; - 65E8F0A411EFF25C00BBF654 /* usb_core.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = usb_core.c; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_core.c"; sourceTree = SOURCE_ROOT; }; - 65E8F0A511EFF25C00BBF654 /* usb_init.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = usb_init.c; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_init.c"; sourceTree = SOURCE_ROOT; }; - 65E8F0A611EFF25C00BBF654 /* usb_int.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = usb_int.c; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_int.c"; sourceTree = SOURCE_ROOT; }; - 65E8F0A711EFF25C00BBF654 /* usb_mem.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = usb_mem.c; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_mem.c"; sourceTree = SOURCE_ROOT; }; - 65E8F0A811EFF25C00BBF654 /* usb_regs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = usb_regs.c; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_regs.c"; sourceTree = SOURCE_ROOT; }; - 65E8F0AB11EFF25C00BBF654 /* misc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = misc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/misc.h; sourceTree = SOURCE_ROOT; }; - 65E8F0AC11EFF25C00BBF654 /* stm32f10x_adc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_adc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h; sourceTree = SOURCE_ROOT; }; - 65E8F0AD11EFF25C00BBF654 /* stm32f10x_bkp.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_bkp.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h; sourceTree = SOURCE_ROOT; }; - 65E8F0AE11EFF25C00BBF654 /* stm32f10x_can.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_can.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h; sourceTree = SOURCE_ROOT; }; - 65E8F0AF11EFF25C00BBF654 /* stm32f10x_crc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_crc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h; sourceTree = SOURCE_ROOT; }; - 65E8F0B011EFF25C00BBF654 /* stm32f10x_dac.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_dac.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h; sourceTree = SOURCE_ROOT; }; - 65E8F0B111EFF25C00BBF654 /* stm32f10x_dbgmcu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_dbgmcu.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h; sourceTree = SOURCE_ROOT; }; - 65E8F0B211EFF25C00BBF654 /* stm32f10x_dma.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_dma.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h; sourceTree = SOURCE_ROOT; }; - 65E8F0B311EFF25C00BBF654 /* stm32f10x_exti.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_exti.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h; sourceTree = SOURCE_ROOT; }; - 65E8F0B411EFF25C00BBF654 /* stm32f10x_flash.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_flash.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h; sourceTree = SOURCE_ROOT; }; - 65E8F0B511EFF25C00BBF654 /* stm32f10x_fsmc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_fsmc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h; sourceTree = SOURCE_ROOT; }; - 65E8F0B611EFF25C00BBF654 /* stm32f10x_gpio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_gpio.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h; sourceTree = SOURCE_ROOT; }; - 65E8F0B711EFF25C00BBF654 /* stm32f10x_i2c.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_i2c.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h; sourceTree = SOURCE_ROOT; }; - 65E8F0B811EFF25C00BBF654 /* stm32f10x_iwdg.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_iwdg.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h; sourceTree = SOURCE_ROOT; }; - 65E8F0B911EFF25C00BBF654 /* stm32f10x_pwr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_pwr.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h; sourceTree = SOURCE_ROOT; }; - 65E8F0BA11EFF25C00BBF654 /* stm32f10x_rcc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_rcc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h; sourceTree = SOURCE_ROOT; }; - 65E8F0BB11EFF25C00BBF654 /* stm32f10x_rtc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_rtc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h; sourceTree = SOURCE_ROOT; }; - 65E8F0BC11EFF25C00BBF654 /* stm32f10x_sdio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_sdio.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h; sourceTree = SOURCE_ROOT; }; - 65E8F0BD11EFF25C00BBF654 /* stm32f10x_spi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_spi.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h; sourceTree = SOURCE_ROOT; }; - 65E8F0BE11EFF25C00BBF654 /* stm32f10x_tim.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_tim.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h; sourceTree = SOURCE_ROOT; }; - 65E8F0BF11EFF25C00BBF654 /* stm32f10x_usart.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_usart.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h; sourceTree = SOURCE_ROOT; }; - 65E8F0C011EFF25C00BBF654 /* stm32f10x_wwdg.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_wwdg.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h; sourceTree = SOURCE_ROOT; }; - 65E8F0C211EFF25C00BBF654 /* misc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = misc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/misc.c; sourceTree = SOURCE_ROOT; }; - 65E8F0C311EFF25C00BBF654 /* stm32f10x_adc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_adc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c; sourceTree = SOURCE_ROOT; }; - 65E8F0C411EFF25C00BBF654 /* stm32f10x_bkp.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_bkp.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c; sourceTree = SOURCE_ROOT; }; - 65E8F0C511EFF25C00BBF654 /* stm32f10x_can.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_can.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c; sourceTree = SOURCE_ROOT; }; - 65E8F0C611EFF25C00BBF654 /* stm32f10x_crc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_crc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c; sourceTree = SOURCE_ROOT; }; - 65E8F0C711EFF25C00BBF654 /* stm32f10x_dac.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_dac.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c; sourceTree = SOURCE_ROOT; }; - 65E8F0C811EFF25C00BBF654 /* stm32f10x_dbgmcu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_dbgmcu.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c; sourceTree = SOURCE_ROOT; }; - 65E8F0C911EFF25C00BBF654 /* stm32f10x_dma.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_dma.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c; sourceTree = SOURCE_ROOT; }; - 65E8F0CA11EFF25C00BBF654 /* stm32f10x_exti.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_exti.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c; sourceTree = SOURCE_ROOT; }; - 65E8F0CB11EFF25C00BBF654 /* stm32f10x_flash.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_flash.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c; sourceTree = SOURCE_ROOT; }; - 65E8F0CC11EFF25C00BBF654 /* stm32f10x_fsmc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_fsmc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c; sourceTree = SOURCE_ROOT; }; - 65E8F0CD11EFF25C00BBF654 /* stm32f10x_gpio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_gpio.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c; sourceTree = SOURCE_ROOT; }; - 65E8F0CE11EFF25C00BBF654 /* stm32f10x_i2c.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_i2c.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c; sourceTree = SOURCE_ROOT; }; - 65E8F0CF11EFF25C00BBF654 /* stm32f10x_iwdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_iwdg.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c; sourceTree = SOURCE_ROOT; }; - 65E8F0D011EFF25C00BBF654 /* stm32f10x_pwr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_pwr.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c; sourceTree = SOURCE_ROOT; }; - 65E8F0D111EFF25C00BBF654 /* stm32f10x_rcc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_rcc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c; sourceTree = SOURCE_ROOT; }; - 65E8F0D211EFF25C00BBF654 /* stm32f10x_rtc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_rtc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c; sourceTree = SOURCE_ROOT; }; - 65E8F0D311EFF25C00BBF654 /* stm32f10x_sdio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_sdio.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c; sourceTree = SOURCE_ROOT; }; - 65E8F0D411EFF25C00BBF654 /* stm32f10x_spi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_spi.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c; sourceTree = SOURCE_ROOT; }; - 65E8F0D511EFF25C00BBF654 /* stm32f10x_tim.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_tim.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c; sourceTree = SOURCE_ROOT; }; - 65E8F0D611EFF25C00BBF654 /* stm32f10x_usart.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_usart.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c; sourceTree = SOURCE_ROOT; }; - 65E8F0D711EFF25C00BBF654 /* stm32f10x_wwdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_wwdg.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c; sourceTree = SOURCE_ROOT; }; - 65E8F0D811EFF25C00BBF654 /* link_stm32f10x_HD.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_stm32f10x_HD.ld; path = ../../PiOS/STM32F10x/link_stm32f10x_HD.ld; sourceTree = SOURCE_ROOT; }; - 65E8F0DB11EFF25C00BBF654 /* link_stm32f10x_MD.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_stm32f10x_MD.ld; path = ../../PiOS/STM32F10x/link_stm32f10x_MD.ld; sourceTree = SOURCE_ROOT; }; - 65E8F0DC11EFF25C00BBF654 /* pios_adc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_adc.c; path = ../../PiOS/STM32F10x/pios_adc.c; sourceTree = SOURCE_ROOT; }; - 65E8F0DD11EFF25C00BBF654 /* pios_debug.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_debug.c; path = ../../PiOS/STM32F10x/pios_debug.c; sourceTree = SOURCE_ROOT; }; - 65E8F0DE11EFF25C00BBF654 /* pios_delay.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_delay.c; path = ../../PiOS/STM32F10x/pios_delay.c; sourceTree = SOURCE_ROOT; }; - 65E8F0DF11EFF25C00BBF654 /* pios_exti.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_exti.c; path = ../../PiOS/STM32F10x/pios_exti.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E011EFF25C00BBF654 /* pios_gpio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_gpio.c; path = ../../PiOS/STM32F10x/pios_gpio.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E111EFF25C00BBF654 /* pios_i2c.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_i2c.c; path = ../../PiOS/STM32F10x/pios_i2c.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E211EFF25C00BBF654 /* pios_irq.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_irq.c; path = ../../PiOS/STM32F10x/pios_irq.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E311EFF25C00BBF654 /* pios_led.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_led.c; path = ../../PiOS/STM32F10x/pios_led.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E411EFF25C00BBF654 /* pios_ppm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_ppm.c; path = ../../PiOS/STM32F10x/pios_ppm.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E511EFF25C00BBF654 /* pios_pwm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_pwm.c; path = ../../PiOS/STM32F10x/pios_pwm.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E611EFF25C00BBF654 /* pios_servo.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_servo.c; path = ../../PiOS/STM32F10x/pios_servo.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E711EFF25C00BBF654 /* pios_dsm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_dsm.c; path = ../../PiOS/STM32F10x/pios_dsm.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E811EFF25C00BBF654 /* pios_spi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_spi.c; path = ../../PiOS/STM32F10x/pios_spi.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E911EFF25C00BBF654 /* pios_sys.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_sys.c; path = ../../PiOS/STM32F10x/pios_sys.c; sourceTree = SOURCE_ROOT; }; - 65E8F0EA11EFF25C00BBF654 /* pios_usart.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_usart.c; path = ../../PiOS/STM32F10x/pios_usart.c; sourceTree = SOURCE_ROOT; }; - 65E8F0ED11EFF25C00BBF654 /* pios_usb_hid.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_usb_hid.c; path = ../../PiOS/STM32F10x/pios_usb_hid.c; sourceTree = SOURCE_ROOT; }; - 65E8F0EE11EFF25C00BBF654 /* startup_stm32f10x_HD.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_HD.S; path = ../../PiOS/STM32F10x/startup_stm32f10x_HD.S; sourceTree = SOURCE_ROOT; }; - 65E8F0F111EFF25C00BBF654 /* startup_stm32f10x_MD.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_MD.S; path = ../../PiOS/STM32F10x/startup_stm32f10x_MD.S; sourceTree = SOURCE_ROOT; }; - 65EA2E171273C55200636061 /* ratedesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ratedesired.xml; sourceTree = ""; }; - 65F93C3912EE09280047DB36 /* aes.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = aes.c; sourceTree = ""; }; - 65F93C3B12EE09280047DB36 /* aes.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = aes.lst; sourceTree = ""; }; - 65F93C3C12EE09280047DB36 /* aes.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = aes.o; sourceTree = ""; }; - 65F93C3D12EE09280047DB36 /* buffer.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = buffer.lst; sourceTree = ""; }; - 65F93C3E12EE09280047DB36 /* buffer.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = buffer.o; sourceTree = ""; }; - 65F93C3F12EE09280047DB36 /* core_cm3.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = core_cm3.lst; sourceTree = ""; }; - 65F93C4012EE09280047DB36 /* core_cm3.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = core_cm3.o; sourceTree = ""; }; - 65F93C4112EE09280047DB36 /* crc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = crc.lst; sourceTree = ""; }; - 65F93C4212EE09280047DB36 /* crc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = crc.o; sourceTree = ""; }; - 65F93C4412EE09280047DB36 /* aes.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = aes.o.d; sourceTree = ""; }; - 65F93C4512EE09280047DB36 /* buffer.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = buffer.o.d; sourceTree = ""; }; - 65F93C4612EE09280047DB36 /* core_cm3.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = core_cm3.o.d; sourceTree = ""; }; - 65F93C4712EE09280047DB36 /* crc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = crc.o.d; sourceTree = ""; }; - 65F93C4812EE09280047DB36 /* fifo_buffer.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = fifo_buffer.o.d; sourceTree = ""; }; - 65F93C4912EE09280047DB36 /* gpio_in.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = gpio_in.o.d; sourceTree = ""; }; - 65F93C4A12EE09280047DB36 /* main.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = main.o.d; sourceTree = ""; }; - 65F93C4B12EE09280047DB36 /* misc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = misc.o.d; sourceTree = ""; }; - 65F93C4C12EE09280047DB36 /* packet_handler.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = packet_handler.o.d; sourceTree = ""; }; - 65F93C4D12EE09280047DB36 /* pios_adc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_adc.o.d; sourceTree = ""; }; - 65F93C4E12EE09280047DB36 /* pios_board.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_board.o.d; sourceTree = ""; }; - 65F93C4F12EE09280047DB36 /* pios_com.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_com.o.d; sourceTree = ""; }; - 65F93C5012EE09280047DB36 /* pios_delay.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_delay.o.d; sourceTree = ""; }; - 65F93C5112EE09280047DB36 /* pios_gpio.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_gpio.o.d; sourceTree = ""; }; - 65F93C5212EE09280047DB36 /* pios_irq.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_irq.o.d; sourceTree = ""; }; - 65F93C5312EE09280047DB36 /* pios_led.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_led.o.d; sourceTree = ""; }; - 65F93C5412EE09280047DB36 /* pios_spi.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_spi.o.d; sourceTree = ""; }; - 65F93C5512EE09280047DB36 /* pios_sys.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_sys.o.d; sourceTree = ""; }; - 65F93C5612EE09280047DB36 /* pios_usart.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usart.o.d; sourceTree = ""; }; - 65F93C5712EE09280047DB36 /* pios_usb_hid.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usb_hid.o.d; sourceTree = ""; }; - 65F93C5812EE09280047DB36 /* pios_usb_hid_desc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usb_hid_desc.o.d; sourceTree = ""; }; - 65F93C5912EE09280047DB36 /* pios_usb_hid_istr.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usb_hid_istr.o.d; sourceTree = ""; }; - 65F93C5A12EE09280047DB36 /* pios_usb_hid_prop.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usb_hid_prop.o.d; sourceTree = ""; }; - 65F93C5B12EE09280047DB36 /* pios_usb_hid_pwr.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usb_hid_pwr.o.d; sourceTree = ""; }; - 65F93C5C12EE09280047DB36 /* pios_wdg.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_wdg.o.d; sourceTree = ""; }; - 65F93C5D12EE09280047DB36 /* printf-stdarg.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = "printf-stdarg.o.d"; sourceTree = ""; }; - 65F93C5E12EE09280047DB36 /* rfm22b.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = rfm22b.o.d; sourceTree = ""; }; - 65F93C5F12EE09280047DB36 /* saved_settings.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = saved_settings.o.d; sourceTree = ""; }; - 65F93C6012EE09280047DB36 /* stm32f10x_adc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_adc.o.d; sourceTree = ""; }; - 65F93C6112EE09280047DB36 /* stm32f10x_bkp.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_bkp.o.d; sourceTree = ""; }; - 65F93C6212EE09280047DB36 /* stm32f10x_crc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_crc.o.d; sourceTree = ""; }; - 65F93C6312EE09280047DB36 /* stm32f10x_dac.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_dac.o.d; sourceTree = ""; }; - 65F93C6412EE09280047DB36 /* stm32f10x_dbgmcu.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_dbgmcu.o.d; sourceTree = ""; }; - 65F93C6512EE09280047DB36 /* stm32f10x_dma.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_dma.o.d; sourceTree = ""; }; - 65F93C6612EE09280047DB36 /* stm32f10x_exti.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_exti.o.d; sourceTree = ""; }; - 65F93C6712EE09280047DB36 /* stm32f10x_flash.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_flash.o.d; sourceTree = ""; }; - 65F93C6812EE09280047DB36 /* stm32f10x_gpio.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_gpio.o.d; sourceTree = ""; }; - 65F93C6912EE09280047DB36 /* stm32f10x_i2c.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_i2c.o.d; sourceTree = ""; }; - 65F93C6A12EE09280047DB36 /* stm32f10x_iwdg.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_iwdg.o.d; sourceTree = ""; }; - 65F93C6B12EE09280047DB36 /* stm32f10x_pwr.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_pwr.o.d; sourceTree = ""; }; - 65F93C6C12EE09280047DB36 /* stm32f10x_rcc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_rcc.o.d; sourceTree = ""; }; - 65F93C6D12EE09280047DB36 /* stm32f10x_rtc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_rtc.o.d; sourceTree = ""; }; - 65F93C6E12EE09280047DB36 /* stm32f10x_spi.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_spi.o.d; sourceTree = ""; }; - 65F93C6F12EE09280047DB36 /* stm32f10x_tim.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_tim.o.d; sourceTree = ""; }; - 65F93C7012EE09280047DB36 /* stm32f10x_usart.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_usart.o.d; sourceTree = ""; }; - 65F93C7112EE09280047DB36 /* stopwatch.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stopwatch.o.d; sourceTree = ""; }; - 65F93C7212EE09280047DB36 /* system_stm32f10x.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = system_stm32f10x.o.d; sourceTree = ""; }; - 65F93C7312EE09280047DB36 /* transparent_comms.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = transparent_comms.o.d; sourceTree = ""; }; - 65F93C7412EE09280047DB36 /* uavtalk_comms.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = uavtalk_comms.o.d; sourceTree = ""; }; - 65F93C7512EE09280047DB36 /* usb_core.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_core.o.d; sourceTree = ""; }; - 65F93C7612EE09280047DB36 /* usb_init.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_init.o.d; sourceTree = ""; }; - 65F93C7712EE09280047DB36 /* usb_int.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_int.o.d; sourceTree = ""; }; - 65F93C7812EE09280047DB36 /* usb_mem.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_mem.o.d; sourceTree = ""; }; - 65F93C7912EE09280047DB36 /* usb_regs.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_regs.o.d; sourceTree = ""; }; - 65F93C7A12EE09280047DB36 /* usb_sil.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_sil.o.d; sourceTree = ""; }; - 65F93C7B12EE09280047DB36 /* watchdog.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = watchdog.o.d; sourceTree = ""; }; - 65F93C7C12EE09280047DB36 /* fifo_buffer.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = fifo_buffer.lst; sourceTree = ""; }; - 65F93C7D12EE09280047DB36 /* fifo_buffer.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = fifo_buffer.o; sourceTree = ""; }; - 65F93C7E12EE09280047DB36 /* gpio_in.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = gpio_in.lst; sourceTree = ""; }; - 65F93C7F12EE09280047DB36 /* gpio_in.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = gpio_in.o; sourceTree = ""; }; - 65F93C8012EE09280047DB36 /* main.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = main.lst; sourceTree = ""; }; - 65F93C8112EE09280047DB36 /* main.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = main.o; sourceTree = ""; }; - 65F93C8212EE09280047DB36 /* misc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = misc.lst; sourceTree = ""; }; - 65F93C8312EE09280047DB36 /* misc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = misc.o; sourceTree = ""; }; - 65F93C8412EE09290047DB36 /* packet_handler.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = packet_handler.lst; sourceTree = ""; }; - 65F93C8512EE09290047DB36 /* packet_handler.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = packet_handler.o; sourceTree = ""; }; - 65F93C8612EE09290047DB36 /* pios_adc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_adc.lst; sourceTree = ""; }; - 65F93C8712EE09290047DB36 /* pios_adc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_adc.o; sourceTree = ""; }; - 65F93C8812EE09290047DB36 /* pios_board.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_board.lst; sourceTree = ""; }; - 65F93C8912EE09290047DB36 /* pios_board.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_board.o; sourceTree = ""; }; - 65F93C8A12EE09290047DB36 /* pios_com.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_com.lst; sourceTree = ""; }; - 65F93C8B12EE09290047DB36 /* pios_com.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_com.o; sourceTree = ""; }; - 65F93C8C12EE09290047DB36 /* pios_delay.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_delay.lst; sourceTree = ""; }; - 65F93C8D12EE09290047DB36 /* pios_delay.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_delay.o; sourceTree = ""; }; - 65F93C8E12EE09290047DB36 /* pios_gpio.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_gpio.lst; sourceTree = ""; }; - 65F93C8F12EE09290047DB36 /* pios_gpio.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_gpio.o; sourceTree = ""; }; - 65F93C9012EE09290047DB36 /* pios_irq.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_irq.lst; sourceTree = ""; }; - 65F93C9112EE09290047DB36 /* pios_irq.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_irq.o; sourceTree = ""; }; - 65F93C9212EE09290047DB36 /* pios_led.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_led.lst; sourceTree = ""; }; - 65F93C9312EE09290047DB36 /* pios_led.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_led.o; sourceTree = ""; }; - 65F93C9412EE09290047DB36 /* pios_spi.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_spi.lst; sourceTree = ""; }; - 65F93C9512EE09290047DB36 /* pios_spi.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_spi.o; sourceTree = ""; }; - 65F93C9612EE09290047DB36 /* pios_sys.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_sys.lst; sourceTree = ""; }; - 65F93C9712EE09290047DB36 /* pios_sys.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_sys.o; sourceTree = ""; }; - 65F93C9812EE09290047DB36 /* pios_usart.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usart.lst; sourceTree = ""; }; - 65F93C9912EE09290047DB36 /* pios_usart.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usart.o; sourceTree = ""; }; - 65F93C9A12EE09290047DB36 /* pios_usb_hid.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usb_hid.lst; sourceTree = ""; }; - 65F93C9B12EE09290047DB36 /* pios_usb_hid.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usb_hid.o; sourceTree = ""; }; - 65F93C9C12EE09290047DB36 /* pios_usb_hid_desc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usb_hid_desc.lst; sourceTree = ""; }; - 65F93C9D12EE09290047DB36 /* pios_usb_hid_desc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usb_hid_desc.o; sourceTree = ""; }; - 65F93C9E12EE09290047DB36 /* pios_usb_hid_istr.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usb_hid_istr.lst; sourceTree = ""; }; - 65F93C9F12EE09290047DB36 /* pios_usb_hid_istr.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usb_hid_istr.o; sourceTree = ""; }; - 65F93CA012EE09290047DB36 /* pios_usb_hid_prop.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usb_hid_prop.lst; sourceTree = ""; }; - 65F93CA112EE09290047DB36 /* pios_usb_hid_prop.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usb_hid_prop.o; sourceTree = ""; }; - 65F93CA212EE09290047DB36 /* pios_usb_hid_pwr.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usb_hid_pwr.lst; sourceTree = ""; }; - 65F93CA312EE09290047DB36 /* pios_usb_hid_pwr.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usb_hid_pwr.o; sourceTree = ""; }; - 65F93CA412EE09290047DB36 /* pios_wdg.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_wdg.lst; sourceTree = ""; }; - 65F93CA512EE09290047DB36 /* pios_wdg.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_wdg.o; sourceTree = ""; }; - 65F93CA612EE09290047DB36 /* PipXtreme.bin */ = {isa = PBXFileReference; lastKnownFileType = archive.macbinary; path = PipXtreme.bin; sourceTree = ""; }; - 65F93CA712EE09290047DB36 /* PipXtreme.elf */ = {isa = PBXFileReference; lastKnownFileType = file; path = PipXtreme.elf; sourceTree = ""; }; - 65F93CA812EE09290047DB36 /* PipXtreme.hex */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = PipXtreme.hex; sourceTree = ""; }; - 65F93CA912EE09290047DB36 /* PipXtreme.lss */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = PipXtreme.lss; sourceTree = ""; }; - 65F93CAA12EE09290047DB36 /* PipXtreme.map */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = PipXtreme.map; sourceTree = ""; }; - 65F93CAB12EE09290047DB36 /* PipXtreme.sym */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = PipXtreme.sym; sourceTree = ""; }; - 65F93CAC12EE09290047DB36 /* printf-stdarg.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "printf-stdarg.lst"; sourceTree = ""; }; - 65F93CAD12EE09290047DB36 /* printf-stdarg.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = "printf-stdarg.o"; sourceTree = ""; }; - 65F93CAE12EE09290047DB36 /* rfm22b.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = rfm22b.lst; sourceTree = ""; }; - 65F93CAF12EE09290047DB36 /* rfm22b.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = rfm22b.o; sourceTree = ""; }; - 65F93CB012EE09290047DB36 /* saved_settings.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = saved_settings.lst; sourceTree = ""; }; - 65F93CB112EE09290047DB36 /* saved_settings.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = saved_settings.o; sourceTree = ""; }; - 65F93CB212EE09290047DB36 /* startup_stm32f10x_MD.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = startup_stm32f10x_MD.lst; sourceTree = ""; }; - 65F93CB312EE09290047DB36 /* startup_stm32f10x_MD.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = startup_stm32f10x_MD.o; sourceTree = ""; }; - 65F93CB412EE09290047DB36 /* stm32f10x_adc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_adc.lst; sourceTree = ""; }; - 65F93CB512EE09290047DB36 /* stm32f10x_adc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_adc.o; sourceTree = ""; }; - 65F93CB612EE09290047DB36 /* stm32f10x_bkp.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_bkp.lst; sourceTree = ""; }; - 65F93CB712EE09290047DB36 /* stm32f10x_bkp.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_bkp.o; sourceTree = ""; }; - 65F93CB812EE09290047DB36 /* stm32f10x_crc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_crc.lst; sourceTree = ""; }; - 65F93CB912EE09290047DB36 /* stm32f10x_crc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_crc.o; sourceTree = ""; }; - 65F93CBA12EE09290047DB36 /* stm32f10x_dac.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_dac.lst; sourceTree = ""; }; - 65F93CBB12EE09290047DB36 /* stm32f10x_dac.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_dac.o; sourceTree = ""; }; - 65F93CBC12EE09290047DB36 /* stm32f10x_dbgmcu.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_dbgmcu.lst; sourceTree = ""; }; - 65F93CBD12EE09290047DB36 /* stm32f10x_dbgmcu.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_dbgmcu.o; sourceTree = ""; }; - 65F93CBE12EE09290047DB36 /* stm32f10x_dma.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_dma.lst; sourceTree = ""; }; - 65F93CBF12EE09290047DB36 /* stm32f10x_dma.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_dma.o; sourceTree = ""; }; - 65F93CC012EE09290047DB36 /* stm32f10x_exti.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_exti.lst; sourceTree = ""; }; - 65F93CC112EE09290047DB36 /* stm32f10x_exti.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_exti.o; sourceTree = ""; }; - 65F93CC212EE09290047DB36 /* stm32f10x_flash.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_flash.lst; sourceTree = ""; }; - 65F93CC312EE09290047DB36 /* stm32f10x_flash.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_flash.o; sourceTree = ""; }; - 65F93CC412EE09290047DB36 /* stm32f10x_gpio.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_gpio.lst; sourceTree = ""; }; - 65F93CC512EE09290047DB36 /* stm32f10x_gpio.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_gpio.o; sourceTree = ""; }; - 65F93CC612EE09290047DB36 /* stm32f10x_i2c.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_i2c.lst; sourceTree = ""; }; - 65F93CC712EE09290047DB36 /* stm32f10x_i2c.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_i2c.o; sourceTree = ""; }; - 65F93CC812EE09290047DB36 /* stm32f10x_iwdg.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_iwdg.lst; sourceTree = ""; }; - 65F93CC912EE09290047DB36 /* stm32f10x_iwdg.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_iwdg.o; sourceTree = ""; }; - 65F93CCA12EE09290047DB36 /* stm32f10x_pwr.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_pwr.lst; sourceTree = ""; }; - 65F93CCB12EE09290047DB36 /* stm32f10x_pwr.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_pwr.o; sourceTree = ""; }; - 65F93CCC12EE09290047DB36 /* stm32f10x_rcc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_rcc.lst; sourceTree = ""; }; - 65F93CCD12EE09290047DB36 /* stm32f10x_rcc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_rcc.o; sourceTree = ""; }; - 65F93CCE12EE09290047DB36 /* stm32f10x_rtc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_rtc.lst; sourceTree = ""; }; - 65F93CCF12EE09290047DB36 /* stm32f10x_rtc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_rtc.o; sourceTree = ""; }; - 65F93CD012EE09290047DB36 /* stm32f10x_spi.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_spi.lst; sourceTree = ""; }; - 65F93CD112EE09290047DB36 /* stm32f10x_spi.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_spi.o; sourceTree = ""; }; - 65F93CD212EE09290047DB36 /* stm32f10x_tim.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_tim.lst; sourceTree = ""; }; - 65F93CD312EE09290047DB36 /* stm32f10x_tim.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_tim.o; sourceTree = ""; }; - 65F93CD412EE09290047DB36 /* stm32f10x_usart.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_usart.lst; sourceTree = ""; }; - 65F93CD512EE09290047DB36 /* stm32f10x_usart.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_usart.o; sourceTree = ""; }; - 65F93CD612EE09290047DB36 /* stopwatch.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stopwatch.lst; sourceTree = ""; }; - 65F93CD712EE09290047DB36 /* stopwatch.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stopwatch.o; sourceTree = ""; }; - 65F93CD812EE09290047DB36 /* system_stm32f10x.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = system_stm32f10x.lst; sourceTree = ""; }; - 65F93CD912EE09290047DB36 /* system_stm32f10x.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = system_stm32f10x.o; sourceTree = ""; }; - 65F93CDA12EE09290047DB36 /* transparent_comms.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = transparent_comms.lst; sourceTree = ""; }; - 65F93CDB12EE09290047DB36 /* transparent_comms.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = transparent_comms.o; sourceTree = ""; }; - 65F93CDC12EE09290047DB36 /* uavtalk_comms.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavtalk_comms.lst; sourceTree = ""; }; - 65F93CDD12EE09290047DB36 /* uavtalk_comms.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = uavtalk_comms.o; sourceTree = ""; }; - 65F93CDE12EE09290047DB36 /* usb_core.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_core.lst; sourceTree = ""; }; - 65F93CDF12EE09290047DB36 /* usb_core.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_core.o; sourceTree = ""; }; - 65F93CE012EE09290047DB36 /* usb_init.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_init.lst; sourceTree = ""; }; - 65F93CE112EE09290047DB36 /* usb_init.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_init.o; sourceTree = ""; }; - 65F93CE212EE09290047DB36 /* usb_int.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_int.lst; sourceTree = ""; }; - 65F93CE312EE09290047DB36 /* usb_int.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_int.o; sourceTree = ""; }; - 65F93CE412EE09290047DB36 /* usb_mem.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_mem.lst; sourceTree = ""; }; - 65F93CE512EE09290047DB36 /* usb_mem.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_mem.o; sourceTree = ""; }; - 65F93CE612EE09290047DB36 /* usb_regs.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_regs.lst; sourceTree = ""; }; - 65F93CE712EE09290047DB36 /* usb_regs.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_regs.o; sourceTree = ""; }; - 65F93CE812EE09290047DB36 /* usb_sil.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_sil.lst; sourceTree = ""; }; - 65F93CE912EE09290047DB36 /* usb_sil.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_sil.o; sourceTree = ""; }; - 65F93CEA12EE09290047DB36 /* watchdog.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = watchdog.lst; sourceTree = ""; }; - 65F93CEB12EE09290047DB36 /* watchdog.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = watchdog.o; sourceTree = ""; }; - 65F93CEC12EE09290047DB36 /* crc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = crc.c; sourceTree = ""; }; - 65F93CED12EE09290047DB36 /* gpio_in.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = gpio_in.c; sourceTree = ""; }; - 65F93CEF12EE09290047DB36 /* aes.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = aes.h; sourceTree = ""; }; - 65F93CF012EE09290047DB36 /* crc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = crc.h; sourceTree = ""; }; - 65F93CF112EE09290047DB36 /* gpio_in.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpio_in.h; sourceTree = ""; }; - 65F93CF212EE09290047DB36 /* main.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = main.h; sourceTree = ""; }; - 65F93CF312EE09290047DB36 /* packet_handler.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = packet_handler.h; sourceTree = ""; }; - 65F93CF412EE09290047DB36 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; - 65F93CF512EE09290047DB36 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = ""; }; - 65F93CF612EE09290047DB36 /* pios_usb_hid_desc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_desc.h; sourceTree = ""; }; - 65F93CF712EE09290047DB36 /* rfm22b.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rfm22b.h; sourceTree = ""; }; - 65F93CF812EE09290047DB36 /* saved_settings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = saved_settings.h; sourceTree = ""; }; - 65F93CF912EE09290047DB36 /* stopwatch.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stopwatch.h; sourceTree = ""; }; - 65F93CFA12EE09290047DB36 /* transparent_comms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = transparent_comms.h; sourceTree = ""; }; - 65F93CFB12EE09290047DB36 /* uavtalk_comms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavtalk_comms.h; sourceTree = ""; }; - 65F93CFC12EE09290047DB36 /* usb_conf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = usb_conf.h; sourceTree = ""; }; - 65F93CFD12EE09290047DB36 /* watchdog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = watchdog.h; sourceTree = ""; }; - 65F93CFE12EE09290047DB36 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; - 65F93CFF12EE09290047DB36 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65F93D0012EE09290047DB36 /* packet_handler.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = packet_handler.c; sourceTree = ""; }; - 65F93D0112EE09290047DB36 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; - 65F93D0212EE09290047DB36 /* pios_usb_hid_desc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb_hid_desc.c; sourceTree = ""; }; - 65F93D0312EE09290047DB36 /* rfm22b.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = rfm22b.c; sourceTree = ""; }; - 65F93D0412EE09290047DB36 /* saved_settings.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = saved_settings.c; sourceTree = ""; }; - 65F93D0512EE09290047DB36 /* stopwatch.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stopwatch.c; sourceTree = ""; }; - 65F93D0612EE09290047DB36 /* transparent_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = transparent_comms.c; sourceTree = ""; }; - 65F93D0712EE09290047DB36 /* uavtalk_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavtalk_comms.c; sourceTree = ""; }; - 65F93D0812EE09290047DB36 /* watchdog.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = watchdog.c; sourceTree = ""; }; - 65FAA03F133B669400F6F5CD /* GTOP_BIN.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = GTOP_BIN.c; sourceTree = ""; }; - 65FAB8CF147FFD76000FF8B2 /* receiveractivity.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = receiveractivity.xml; sourceTree = ""; }; - 65FBE14412E7C98100176B5A /* pios_servo_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_servo_priv.h; sourceTree = ""; }; - 65FC66AA123F30F100B04F74 /* ahrs_timer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_timer.c; path = ../../AHRS/ahrs_timer.c; sourceTree = SOURCE_ROOT; }; - 65FC66AB123F312A00B04F74 /* ahrs_timer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_timer.h; sourceTree = ""; }; - 65FF4BB513791C3300146BE4 /* ahrs_slave_test.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_slave_test.c; sourceTree = ""; }; - 65FF4BB613791C3300146BE4 /* ahrs_spi_program.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program.c; sourceTree = ""; }; - 65FF4BB713791C3300146BE4 /* ahrs_spi_program_master.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program_master.c; sourceTree = ""; }; - 65FF4BB813791C3300146BE4 /* ahrs_spi_program_slave.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program_slave.c; sourceTree = ""; }; - 65FF4BB913791C3300146BE4 /* bl_fsm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = bl_fsm.c; sourceTree = ""; }; - 65FF4BBB13791C3300146BE4 /* ahrs_bl.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_bl.h; sourceTree = ""; }; - 65FF4BBC13791C3300146BE4 /* ahrs_spi_program.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program.h; sourceTree = ""; }; - 65FF4BBD13791C3300146BE4 /* ahrs_spi_program_master.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program_master.h; sourceTree = ""; }; - 65FF4BBE13791C3300146BE4 /* ahrs_spi_program_slave.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program_slave.h; sourceTree = ""; }; - 65FF4BBF13791C3300146BE4 /* bl_fsm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = bl_fsm.h; sourceTree = ""; }; - 65FF4BC013791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; - 65FF4BC113791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; - 65FF4BC213791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65FF4BC313791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; - 65FF4BC613791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; - 65FF4BC713791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; - 65FF4BC813791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65FF4BC913791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; - 65FF4BCA13791C3300146BE4 /* test.bin */ = {isa = PBXFileReference; lastKnownFileType = archive.macbinary; path = test.bin; sourceTree = ""; }; - 65FF4BCD13791C3300146BE4 /* common.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = common.h; sourceTree = ""; }; - 65FF4BCE13791C3300146BE4 /* op_dfu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_dfu.h; sourceTree = ""; }; - 65FF4BCF13791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; - 65FF4BD013791C3300146BE4 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = ""; }; - 65FF4BD113791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; - 65FF4BD213791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65FF4BD313791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = ""; }; - 65FF4BD413791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; - 65FF4BD713791C3300146BE4 /* common.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = common.h; sourceTree = ""; }; - 65FF4BD813791C3300146BE4 /* op_dfu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_dfu.h; sourceTree = ""; }; - 65FF4BD913791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; - 65FF4BDA13791C3300146BE4 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = ""; }; - 65FF4BDB13791C3300146BE4 /* ssp.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ssp.h; sourceTree = ""; }; - 65FF4BDC13791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; - 65FF4BDD13791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65FF4BDE13791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = ""; }; - 65FF4BDF13791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; - 65FF4BE013791C3300146BE4 /* ssp.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ssp.c; sourceTree = ""; }; - 65FF4BE113791C3300146BE4 /* ssp_timer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ssp_timer.c; sourceTree = ""; }; - 65FF4BE413791C3300146BE4 /* common.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = common.h; sourceTree = ""; }; - 65FF4BE513791C3300146BE4 /* op_dfu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_dfu.h; sourceTree = ""; }; - 65FF4BE613791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; - 65FF4BE713791C3300146BE4 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = ""; }; - 65FF4BE813791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; - 65FF4BE913791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; - 65FF4BEA13791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = ""; }; - 65FF4BEB13791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; - 65FF4D5E137EDEC100146BE4 /* pios_flashfs_objlist.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_flashfs_objlist.c; sourceTree = ""; }; - 65FF4D61137EFA4F00146BE4 /* pios_flashfs_objlist.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_flashfs_objlist.h; sourceTree = ""; }; + 65904F1814632C1700FD9482 /* firmware-defs.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "firmware-defs.mk"; sourceTree = ""; }; + 65904F2214632C1700FD9482 /* board-info.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "board-info.mk"; sourceTree = ""; }; + 65904F2314632C1700FD9482 /* board-info.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "board-info.mk"; sourceTree = ""; }; + 65904F2414632C1700FD9482 /* board-info.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "board-info.mk"; sourceTree = ""; }; + 65904F2514632C1700FD9482 /* board-info.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "board-info.mk"; sourceTree = ""; }; + 65904F2614632C1700FD9482 /* board-info.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "board-info.mk"; sourceTree = ""; }; + 65904F2714632C1700FD9482 /* board-info.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "board-info.mk"; sourceTree = ""; }; + 65904F2814632C1700FD9482 /* version-info.py */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.python; path = "version-info.py"; sourceTree = ""; }; + 65904F2914632C1700FD9482 /* firmwareinfotemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = firmwareinfotemplate.c; sourceTree = ""; }; + 65904F2A14632C1700FD9482 /* gcsversioninfotemplate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gcsversioninfotemplate.h; sourceTree = ""; }; + 65904F2D14632C1700FD9482 /* README.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = README.txt; sourceTree = ""; }; + 65904F2E14632C1700FD9482 /* shell_script.reg */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = shell_script.reg; sourceTree = ""; }; + 65904F2F14632C1700FD9482 /* install */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.sh; path = install; sourceTree = ""; }; + 65904F3014632C1700FD9482 /* make */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.sh; path = make; sourceTree = ""; }; + 65904F3114632C1700FD9482 /* make.sh */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.sh; path = make.sh; sourceTree = ""; }; + 65904F3214632C1700FD9482 /* sh.cmd */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = sh.cmd; sourceTree = ""; }; + 65904F34146362F300FD9482 /* board-info.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "board-info.mk"; sourceTree = ""; }; + 65E466BC14E244020075459C /* uavobjectdefinition */ = {isa = PBXFileReference; lastKnownFileType = folder; path = uavobjectdefinition; sourceTree = ""; }; /* End PBXFileReference section */ /* Begin PBXGroup section */ 08FB7794FE84155DC02AAC07 /* OpenPilotOSX */ = { isa = PBXGroup; children = ( + 4354B66314FED9FE004BA3B4 /* flight */, + 65904F1614632C1700FD9482 /* make */, 65C35E4E12EFB2F3004811C2 /* shared */, 65173C9F12EBFD1700D6A7CB /* Makefile */, - 657CEEB5121DBC49007A1FBE /* flight */, - 65B35D7D121C261E003EAD18 /* ground */, ); name = OpenPilotOSX; sourceTree = ""; }; - 1AB674ADFE9D54B511CA2CBB /* Products */ = { + 65904F1614632C1700FD9482 /* make */ = { isa = PBXGroup; children = ( + 65904F1714632C1700FD9482 /* boards */, + 65904F1814632C1700FD9482 /* firmware-defs.mk */, + 65904F1914632C1700FD9482 /* scripts */, + 65904F1A14632C1700FD9482 /* templates */, + 65904F1B14632C1700FD9482 /* winx86 */, ); - name = Products; + name = make; + path = OpenPilotOSX.xcodeproj/../../../../make; sourceTree = ""; }; - 650D8E1F12DFE16400D05CC9 /* Modules */ = { + 65904F1714632C1700FD9482 /* boards */ = { isa = PBXGroup; children = ( - 650D8E2012DFE16400D05CC9 /* Actuator */, - 650D8E2412DFE16400D05CC9 /* AHRSComms */, - 650D8E2812DFE16400D05CC9 /* Altitude */, - 65C35F6512F0DC2D004811C2 /* Attitude */, - 650D8E2E12DFE16400D05CC9 /* Battery */, - 65C9903B13A871B90082BD60 /* CameraStab */, - 650D8E3212DFE16400D05CC9 /* Example */, - 650D8E3B12DFE16400D05CC9 /* FirmwareIAP */, - 650D8E3F12DFE16400D05CC9 /* FlightPlan */, - 650D8E4712DFE16400D05CC9 /* GPS */, - 650D8E4D12DFE16400D05CC9 /* Guidance */, - 650D8E5112DFE16400D05CC9 /* ManualControl */, - 650D8E5512DFE16400D05CC9 /* MK */, - 650D8E5A12DFE16400D05CC9 /* Osd */, - 650D8E5D12DFE16400D05CC9 /* Stabilization */, - 650D8E6112DFE16400D05CC9 /* System */, - 650D8E6512DFE16400D05CC9 /* Telemetry */, + 65904F33146362F300FD9482 /* revolution */, + 65904F1C14632C1700FD9482 /* ahrs */, + 65904F1D14632C1700FD9482 /* coptercontrol */, + 65904F1E14632C1700FD9482 /* esc */, + 65904F1F14632C1700FD9482 /* ins */, + 65904F2014632C1700FD9482 /* openpilot */, + 65904F2114632C1700FD9482 /* pipxtreme */, ); - name = Modules; - path = ../../Modules; - sourceTree = SOURCE_ROOT; - }; - 650D8E2012DFE16400D05CC9 /* Actuator */ = { - isa = PBXGroup; - children = ( - 650D8E2112DFE16400D05CC9 /* actuator.c */, - 650D8E2212DFE16400D05CC9 /* inc */, - ); - path = Actuator; + path = boards; sourceTree = ""; }; - 650D8E2212DFE16400D05CC9 /* inc */ = { + 65904F1914632C1700FD9482 /* scripts */ = { isa = PBXGroup; children = ( - 650D8E2312DFE16400D05CC9 /* actuator.h */, + 65904F2814632C1700FD9482 /* version-info.py */, ); - path = inc; + path = scripts; sourceTree = ""; }; - 650D8E2412DFE16400D05CC9 /* AHRSComms */ = { + 65904F1A14632C1700FD9482 /* templates */ = { isa = PBXGroup; children = ( - 650D8E2512DFE16400D05CC9 /* ahrs_comms.c */, - 650D8E2612DFE16400D05CC9 /* inc */, + 65904F2914632C1700FD9482 /* firmwareinfotemplate.c */, + 65904F2A14632C1700FD9482 /* gcsversioninfotemplate.h */, ); - path = AHRSComms; + path = templates; sourceTree = ""; }; - 650D8E2612DFE16400D05CC9 /* inc */ = { + 65904F1B14632C1700FD9482 /* winx86 */ = { isa = PBXGroup; children = ( - 650D8E2712DFE16400D05CC9 /* ahrs_comms.h */, + 65904F2B14632C1700FD9482 /* bin */, + 65904F2C14632C1700FD9482 /* cmd */, + 65904F2D14632C1700FD9482 /* README.txt */, + 65904F2E14632C1700FD9482 /* shell_script.reg */, ); - path = inc; + path = winx86; sourceTree = ""; }; - 650D8E2812DFE16400D05CC9 /* Altitude */ = { + 65904F1C14632C1700FD9482 /* ahrs */ = { isa = PBXGroup; children = ( - 650D8E2912DFE16400D05CC9 /* altitude.c */, - 650D8E2A12DFE16400D05CC9 /* inc */, + 65904F2214632C1700FD9482 /* board-info.mk */, ); - path = Altitude; + path = ahrs; sourceTree = ""; }; - 650D8E2A12DFE16400D05CC9 /* inc */ = { + 65904F1D14632C1700FD9482 /* coptercontrol */ = { isa = PBXGroup; children = ( - 650D8E2B12DFE16400D05CC9 /* altitude.h */, + 65904F2314632C1700FD9482 /* board-info.mk */, ); - path = inc; + path = coptercontrol; sourceTree = ""; }; - 650D8E2E12DFE16400D05CC9 /* Battery */ = { + 65904F1E14632C1700FD9482 /* esc */ = { isa = PBXGroup; children = ( - 650D8E2F12DFE16400D05CC9 /* battery.c */, - 650D8E3012DFE16400D05CC9 /* inc */, + 65904F2414632C1700FD9482 /* board-info.mk */, ); - path = Battery; + path = esc; sourceTree = ""; }; - 650D8E3012DFE16400D05CC9 /* inc */ = { + 65904F1F14632C1700FD9482 /* ins */ = { isa = PBXGroup; children = ( - 650D8E3112DFE16400D05CC9 /* battery.h */, + 65904F2514632C1700FD9482 /* board-info.mk */, ); - path = inc; + path = ins; sourceTree = ""; }; - 650D8E3212DFE16400D05CC9 /* Example */ = { + 65904F2014632C1700FD9482 /* openpilot */ = { isa = PBXGroup; children = ( - 650D8E3312DFE16400D05CC9 /* example.c */, - 650D8E3412DFE16400D05CC9 /* examplemodevent.c */, - 650D8E3512DFE16400D05CC9 /* examplemodperiodic.c */, - 650D8E3612DFE16400D05CC9 /* examplemodthread.c */, - 650D8E3712DFE16400D05CC9 /* inc */, + 65904F2614632C1700FD9482 /* board-info.mk */, ); - path = Example; + path = openpilot; sourceTree = ""; }; - 650D8E3712DFE16400D05CC9 /* inc */ = { + 65904F2114632C1700FD9482 /* pipxtreme */ = { isa = PBXGroup; children = ( - 650D8E3812DFE16400D05CC9 /* examplemodevent.h */, - 650D8E3912DFE16400D05CC9 /* examplemodperiodic.h */, - 650D8E3A12DFE16400D05CC9 /* examplemodthread.h */, + 65904F2714632C1700FD9482 /* board-info.mk */, ); - path = inc; + path = pipxtreme; sourceTree = ""; }; - 650D8E3B12DFE16400D05CC9 /* FirmwareIAP */ = { + 65904F2B14632C1700FD9482 /* bin */ = { isa = PBXGroup; children = ( - 650D8E3C12DFE16400D05CC9 /* firmwareiap.c */, - 650D8E3D12DFE16400D05CC9 /* inc */, - ); - path = FirmwareIAP; - sourceTree = ""; - }; - 650D8E3D12DFE16400D05CC9 /* inc */ = { - isa = PBXGroup; - children = ( - 650D8E3E12DFE16400D05CC9 /* firmwareiap.h */, - ); - path = inc; - sourceTree = ""; - }; - 650D8E3F12DFE16400D05CC9 /* FlightPlan */ = { - isa = PBXGroup; - children = ( - 650D8E4012DFE16400D05CC9 /* flightplan.c */, - 650D8E4112DFE16400D05CC9 /* flightplans */, - 650D8E4312DFE16400D05CC9 /* inc */, - 650D8E4512DFE16400D05CC9 /* lib */, - ); - path = FlightPlan; - sourceTree = ""; - }; - 650D8E4112DFE16400D05CC9 /* flightplans */ = { - isa = PBXGroup; - children = ( - 650D8E4212DFE16400D05CC9 /* test.py */, - ); - path = flightplans; - sourceTree = ""; - }; - 650D8E4312DFE16400D05CC9 /* inc */ = { - isa = PBXGroup; - children = ( - 650D8E4412DFE16400D05CC9 /* flightplan.h */, - ); - path = inc; - sourceTree = ""; - }; - 650D8E4512DFE16400D05CC9 /* lib */ = { - isa = PBXGroup; - children = ( - 650D8E4612DFE16400D05CC9 /* uavobjects.py */, - ); - path = lib; - sourceTree = ""; - }; - 650D8E4712DFE16400D05CC9 /* GPS */ = { - isa = PBXGroup; - children = ( - 65FAA03F133B669400F6F5CD /* GTOP_BIN.c */, - 650D8E4812DFE16400D05CC9 /* GPS.c */, - 650D8E4912DFE16400D05CC9 /* inc */, - 650D8E4C12DFE16400D05CC9 /* NMEA.c */, - ); - path = GPS; - sourceTree = ""; - }; - 650D8E4912DFE16400D05CC9 /* inc */ = { - isa = PBXGroup; - children = ( - 650D8E4A12DFE16400D05CC9 /* GPS.h */, - 650D8E4B12DFE16400D05CC9 /* NMEA.h */, - ); - path = inc; - sourceTree = ""; - }; - 650D8E4D12DFE16400D05CC9 /* Guidance */ = { - isa = PBXGroup; - children = ( - 650D8E4E12DFE16400D05CC9 /* guidance.c */, - 650D8E4F12DFE16400D05CC9 /* inc */, - ); - path = Guidance; - sourceTree = ""; - }; - 650D8E4F12DFE16400D05CC9 /* inc */ = { - isa = PBXGroup; - children = ( - 650D8E5012DFE16400D05CC9 /* guidance.h */, - ); - path = inc; - sourceTree = ""; - }; - 650D8E5112DFE16400D05CC9 /* ManualControl */ = { - isa = PBXGroup; - children = ( - 650D8E5212DFE16400D05CC9 /* inc */, - 650D8E5412DFE16400D05CC9 /* manualcontrol.c */, - ); - path = ManualControl; - sourceTree = ""; - }; - 650D8E5212DFE16400D05CC9 /* inc */ = { - isa = PBXGroup; - children = ( - 650D8E5312DFE16400D05CC9 /* manualcontrol.h */, - ); - path = inc; - sourceTree = ""; - }; - 650D8E5512DFE16400D05CC9 /* MK */ = { - isa = PBXGroup; - children = ( - 650D8E5612DFE16400D05CC9 /* MKSerial */, - ); - path = MK; - sourceTree = ""; - }; - 650D8E5612DFE16400D05CC9 /* MKSerial */ = { - isa = PBXGroup; - children = ( - 650D8E5712DFE16400D05CC9 /* inc */, - 650D8E5912DFE16400D05CC9 /* MKSerial.c */, - ); - path = MKSerial; - sourceTree = ""; - }; - 650D8E5712DFE16400D05CC9 /* inc */ = { - isa = PBXGroup; - children = ( - 650D8E5812DFE16400D05CC9 /* MkSerial.h */, - ); - path = inc; - sourceTree = ""; - }; - 650D8E5A12DFE16400D05CC9 /* Osd */ = { - isa = PBXGroup; - children = ( - 650D8E5B12DFE16400D05CC9 /* OsdEtStd */, - ); - path = Osd; - sourceTree = ""; - }; - 650D8E5B12DFE16400D05CC9 /* OsdEtStd */ = { - isa = PBXGroup; - children = ( - 650D8E5C12DFE16400D05CC9 /* OsdEtStd.c */, - ); - path = OsdEtStd; - sourceTree = ""; - }; - 650D8E5D12DFE16400D05CC9 /* Stabilization */ = { - isa = PBXGroup; - children = ( - 650D8E5E12DFE16400D05CC9 /* inc */, - 650D8E6012DFE16400D05CC9 /* stabilization.c */, - ); - path = Stabilization; - sourceTree = ""; - }; - 650D8E5E12DFE16400D05CC9 /* inc */ = { - isa = PBXGroup; - children = ( - 650D8E5F12DFE16400D05CC9 /* stabilization.h */, - ); - path = inc; - sourceTree = ""; - }; - 650D8E6112DFE16400D05CC9 /* System */ = { - isa = PBXGroup; - children = ( - 650D8E6212DFE16400D05CC9 /* inc */, - 650D8E6412DFE16400D05CC9 /* systemmod.c */, - ); - path = System; - sourceTree = ""; - }; - 650D8E6212DFE16400D05CC9 /* inc */ = { - isa = PBXGroup; - children = ( - 650D8E6312DFE16400D05CC9 /* systemmod.h */, - ); - path = inc; - sourceTree = ""; - }; - 650D8E6512DFE16400D05CC9 /* Telemetry */ = { - isa = PBXGroup; - children = ( - 650D8E6612DFE16400D05CC9 /* inc */, - 650D8E6812DFE16400D05CC9 /* telemetry.c */, - ); - path = Telemetry; - sourceTree = ""; - }; - 650D8E6612DFE16400D05CC9 /* inc */ = { - isa = PBXGroup; - children = ( - 650D8E6712DFE16400D05CC9 /* telemetry.h */, - ); - path = inc; - sourceTree = ""; - }; - 650D8E6A12DFE17500D05CC9 /* UAVObjects */ = { - isa = PBXGroup; - children = ( - 65C35E9E12F0A834004811C2 /* uavobjecttemplate.c */, - 65C35E9F12F0A834004811C2 /* uavobjectsinittemplate.c */, - 65C35EA112F0A834004811C2 /* uavobjectmanager.c */, - 65C35EA212F0A834004811C2 /* inc */, - 65C35EA812F0A834004811C2 /* eventdispatcher.c */, - ); - name = UAVObjects; - path = ../../UAVObjects; - sourceTree = SOURCE_ROOT; - }; - 650D8ECF12DFE17500D05CC9 /* UAVTalk */ = { - isa = PBXGroup; - children = ( - 650D8ED012DFE17500D05CC9 /* inc */, - 650D8ED212DFE17500D05CC9 /* uavtalk.c */, - ); - name = UAVTalk; - path = ../../UAVTalk; - sourceTree = SOURCE_ROOT; - }; - 650D8ED012DFE17500D05CC9 /* inc */ = { - isa = PBXGroup; - children = ( - 650D8ED112DFE17500D05CC9 /* uavtalk.h */, - ); - path = inc; - sourceTree = ""; - }; - 65632DF41251650300469B77 /* Boards */ = { - isa = PBXGroup; - children = ( - 65632DF51251650300469B77 /* pios_board.h */, - 65632DF71251650300469B77 /* STM3210E_OP.h */, - 65632DF61251650300469B77 /* STM32103CB_AHRS.h */, - 65E6E06112E031E300058553 /* STM32103CB_CC_Rev1.h */, - 65E6E06212E031E300058553 /* STM32103CB_PIPXTREME_Rev1.h */, - ); - path = Boards; - sourceTree = ""; - }; - 657CEEB5121DBC49007A1FBE /* flight */ = { - isa = PBXGroup; - children = ( - 65FF4BB313791C3300146BE4 /* Bootloaders */, - 65F93B9012EE09280047DB36 /* PipXtreme */, - 65B7E6AC120DF1CD000C1123 /* AHRS */, - 65E6DF7012E02E8E00058553 /* CopterControl */, - 65E8EF1E11EEA61E00BBF654 /* OpenPilot */, - 650D8E1F12DFE16400D05CC9 /* Modules */, - 657CEEB6121DBC63007A1FBE /* Libraries */, - 65E8F02F11EFF25C00BBF654 /* PiOS */, - 65E6DF9012E0313E00058553 /* PipXtreme */, - 650D8E6A12DFE17500D05CC9 /* UAVObjects */, - 650D8ECF12DFE17500D05CC9 /* UAVTalk */, - C6A0FF2B0290797F04C91782 /* Documentation */, - 1AB674ADFE9D54B511CA2CBB /* Products */, - ); - name = flight; - sourceTree = ""; - }; - 657CEEB6121DBC63007A1FBE /* Libraries */ = { - isa = PBXGroup; - children = ( - 6549E0D21279B3C800C5476F /* fifo_buffer.c */, - 651913371256C5240039C0A3 /* ahrs_comm_objects.c */, - 651913381256C5240039C0A3 /* ahrs_spi_comm.c */, - 657CEEB7121DBC63007A1FBE /* CoordinateConversions.c */, - 657CEEB8121DBC63007A1FBE /* inc */, - 657CEEBB121DBC63007A1FBE /* WorldMagModel.c */, - ); - name = Libraries; - path = ../../Libraries; - sourceTree = SOURCE_ROOT; - }; - 657CEEB8121DBC63007A1FBE /* inc */ = { - isa = PBXGroup; - children = ( - 6549E0D31279B3CF00C5476F /* fifo_buffer.h */, - 6519133A1256C52B0039C0A3 /* ahrs_comm_objects.h */, - 6519133B1256C52B0039C0A3 /* ahrs_spi_comm.h */, - 657CF024121F49CD007A1FBE /* WMMInternal.h */, - 657CEEB9121DBC63007A1FBE /* CoordinateConversions.h */, - 657CEEBA121DBC63007A1FBE /* WorldMagModel.h */, - ); - path = inc; - sourceTree = ""; - }; - 65B35D7D121C261E003EAD18 /* ground */ = { - isa = PBXGroup; - children = ( - 65B35D7E121C261E003EAD18 /* bin */, - 65B35D81121C261E003EAD18 /* openpilotgcs.pri */, - 65B35D82121C261E003EAD18 /* openpilotgcs.pro */, - 65B35D83121C261E003EAD18 /* openpilotgcs.pro.user */, - 65B35D84121C261E003EAD18 /* share */, - 65B35E1E121C261E003EAD18 /* src */, - ); - name = ground; - path = ../../../ground; - sourceTree = SOURCE_ROOT; - }; - 65B35D7E121C261E003EAD18 /* bin */ = { - isa = PBXGroup; - children = ( - 65B35D7F121C261E003EAD18 /* bin.pro */, - 65B35D80121C261E003EAD18 /* openpilotgcs */, + 65904F2F14632C1700FD9482 /* install */, + 65904F3014632C1700FD9482 /* make */, ); path = bin; sourceTree = ""; }; - 65B35D84121C261E003EAD18 /* share */ = { + 65904F2C14632C1700FD9482 /* cmd */ = { isa = PBXGroup; children = ( - 65B35D85121C261E003EAD18 /* openpilotgcs */, - 65B35E1D121C261E003EAD18 /* share.pro */, + 65904F3114632C1700FD9482 /* make.sh */, + 65904F3214632C1700FD9482 /* sh.cmd */, ); - path = share; + path = cmd; sourceTree = ""; }; - 65B35D85121C261E003EAD18 /* openpilotgcs */ = { + 65904F33146362F300FD9482 /* revolution */ = { isa = PBXGroup; children = ( - 65B35D86121C261E003EAD18 /* diagrams */, - 65B35D89121C261E003EAD18 /* dials */, - 65B35D9C121C261E003EAD18 /* mapicons */, - 65B35D9F121C261E003EAD18 /* models */, - 65B35DA7121C261E003EAD18 /* pfd */, - 65B35DAA121C261E003EAD18 /* sounds */, - 65B35E14121C261E003EAD18 /* translations */, + 65904F34146362F300FD9482 /* board-info.mk */, ); - path = openpilotgcs; + path = revolution; sourceTree = ""; }; - 65B35D86121C261E003EAD18 /* diagrams */ = { - isa = PBXGroup; - children = ( - 65B35D87121C261E003EAD18 /* default */, - ); - path = diagrams; - sourceTree = ""; - }; - 65B35D87121C261E003EAD18 /* default */ = { - isa = PBXGroup; - children = ( - 65B35D88121C261E003EAD18 /* system-health.svg */, - ); - path = default; - sourceTree = ""; - }; - 65B35D89121C261E003EAD18 /* dials */ = { - isa = PBXGroup; - children = ( - 65B35D8A121C261E003EAD18 /* default */, - 65B35D98121C261E003EAD18 /* deluxe */, - ); - path = dials; - sourceTree = ""; - }; - 65B35D8A121C261E003EAD18 /* default */ = { - isa = PBXGroup; - children = ( - 65B35D8B121C261E003EAD18 /* altimeter.svg */, - 65B35D8C121C261E003EAD18 /* attitude.svg */, - 65B35D8D121C261E003EAD18 /* compass.svg */, - 65B35D8E121C261E003EAD18 /* flightmode-status.svg */, - 65B35D8F121C261E003EAD18 /* gps-signal.svg */, - 65B35D90121C261E003EAD18 /* gps-status.svg */, - 65B35D91121C261E003EAD18 /* lineardial-horizontal.svg */, - 65B35D92121C261E003EAD18 /* lineardial-vertical.svg */, - 65B35D93121C261E003EAD18 /* Readme.txt */, - 65B35D94121C261E003EAD18 /* speed.svg */, - 65B35D95121C261E003EAD18 /* textonly.svg */, - 65B35D96121C261E003EAD18 /* thermometer.svg */, - 65B35D97121C261E003EAD18 /* vsi.svg */, - ); - path = default; - sourceTree = ""; - }; - 65B35D98121C261E003EAD18 /* deluxe */ = { - isa = PBXGroup; - children = ( - 65B35D99121C261E003EAD18 /* altimeter.svg */, - 65B35D9A121C261E003EAD18 /* speed.svg */, - 65B35D9B121C261E003EAD18 /* vsi.svg */, - ); - path = deluxe; - sourceTree = ""; - }; - 65B35D9C121C261E003EAD18 /* mapicons */ = { - isa = PBXGroup; - children = ( - 65B35D9D121C261E003EAD18 /* easystar.png */, - 65B35D9E121C261E003EAD18 /* quad.png */, - ); - path = mapicons; - sourceTree = ""; - }; - 65B35D9F121C261E003EAD18 /* models */ = { - isa = PBXGroup; - children = ( - 65B35DA0121C261E003EAD18 /* Easystar */, - ); - path = models; - sourceTree = ""; - }; - 65B35DA0121C261E003EAD18 /* Easystar */ = { - isa = PBXGroup; - children = ( - 65B35DA1121C261E003EAD18 /* EasyS.jpg */, - 65B35DA2121C261E003EAD18 /* EasyStar.3ds */, - 65B35DA3121C261E003EAD18 /* V1White.jpg */, - 65B35DA4121C261E003EAD18 /* V2White.jpg */, - 65B35DA5121C261E003EAD18 /* White.jpg */, - 65B35DA6121C261E003EAD18 /* wing.jpg */, - ); - path = Easystar; - sourceTree = ""; - }; - 65B35DA7121C261E003EAD18 /* pfd */ = { - isa = PBXGroup; - children = ( - 65B35DA8121C261E003EAD18 /* default */, - ); - path = pfd; - sourceTree = ""; - }; - 65B35DA8121C261E003EAD18 /* default */ = { - isa = PBXGroup; - children = ( - 65B35DA9121C261E003EAD18 /* pfd.svg */, - ); - path = default; - sourceTree = ""; - }; - 65B35DAA121C261E003EAD18 /* sounds */ = { - isa = PBXGroup; - children = ( - 65B35DAB121C261E003EAD18 /* Complete sound set.txt */, - 65B35DAC121C261E003EAD18 /* default */, - 65B35E13121C261E003EAD18 /* License.txt */, - ); - path = sounds; - sourceTree = ""; - }; - 65B35DAC121C261E003EAD18 /* default */ = { - isa = PBXGroup; - children = ( - 65B35DAD121C261E003EAD18 /* 0.wav */, - 65B35DAE121C261E003EAD18 /* 1.wav */, - 65B35DAF121C261E003EAD18 /* 10.wav */, - 65B35DB0121C261E003EAD18 /* 100.wav */, - 65B35DB1121C261E003EAD18 /* 1000.wav */, - 65B35DB2121C261E003EAD18 /* 11.wav */, - 65B35DB3121C261E003EAD18 /* 12.wav */, - 65B35DB4121C261E003EAD18 /* 13.wav */, - 65B35DB5121C261E003EAD18 /* 14.wav */, - 65B35DB6121C261E003EAD18 /* 15.wav */, - 65B35DB7121C261E003EAD18 /* 16.wav */, - 65B35DB8121C261E003EAD18 /* 17.wav */, - 65B35DB9121C261E003EAD18 /* 18.wav */, - 65B35DBA121C261E003EAD18 /* 19.wav */, - 65B35DBB121C261E003EAD18 /* 2.wav */, - 65B35DBC121C261E003EAD18 /* 20.wav */, - 65B35DBD121C261E003EAD18 /* 3.wav */, - 65B35DBE121C261E003EAD18 /* 30.wav */, - 65B35DBF121C261E003EAD18 /* 4.wav */, - 65B35DC0121C261E003EAD18 /* 40.wav */, - 65B35DC1121C261E003EAD18 /* 5.wav */, - 65B35DC2121C261E003EAD18 /* 50.wav */, - 65B35DC3121C261E003EAD18 /* 6.wav */, - 65B35DC4121C261E003EAD18 /* 60.wav */, - 65B35DC5121C261E003EAD18 /* 7.wav */, - 65B35DC6121C261E003EAD18 /* 70.wav */, - 65B35DC7121C261E003EAD18 /* 8.wav */, - 65B35DC8121C261E003EAD18 /* 80.wav */, - 65B35DC9121C261E003EAD18 /* 9.wav */, - 65B35DCA121C261E003EAD18 /* 90.wav */, - 65B35DCB121C261E003EAD18 /* aborted.wav */, - 65B35DCC121C261E003EAD18 /* active.wav */, - 65B35DCD121C261E003EAD18 /* alarmsound.wav */, - 65B35DCE121C261E003EAD18 /* alert.wav */, - 65B35DCF121C261E003EAD18 /* altitude.wav */, - 65B35DD0121C261E003EAD18 /* amps.wav */, - 65B35DD1121C261E003EAD18 /* aquired.wav */, - 65B35DD2121C261E003EAD18 /* auto flight.wav */, - 65B35DD3121C261E003EAD18 /* battery.wav */, - 65B35DD4121C261E003EAD18 /* beepsound.wav */, - 65B35DD5121C261E003EAD18 /* camera.wav */, - 65B35DD6121C261E003EAD18 /* cancelled.wav */, - 65B35DD7121C261E003EAD18 /* changed.wav */, - 65B35DD8121C261E003EAD18 /* circle position.wav */, - 65B35DD9121C261E003EAD18 /* cleared.wav */, - 65B35DDA121C261E003EAD18 /* complete.wav */, - 65B35DDB121C261E003EAD18 /* connected.wav */, - 65B35DDC121C261E003EAD18 /* connection.wav */, - 65B35DDD121C261E003EAD18 /* control.wav */, - 65B35DDE121C261E003EAD18 /* disabled.wav */, - 65B35DDF121C261E003EAD18 /* disconnected.wav */, - 65B35DE0121C261E003EAD18 /* feet.wav */, - 65B35DE1121C261E003EAD18 /* figure eight.wav */, - 65B35DE2121C261E003EAD18 /* flight.wav */, - 65B35DE3121C261E003EAD18 /* geofence.wav */, - 65B35DE4121C261E003EAD18 /* gps.wav */, - 65B35DE5121C261E003EAD18 /* ground station.wav */, - 65B35DE6121C261E003EAD18 /* heading.wav */, - 65B35DE7121C261E003EAD18 /* height.wav */, - 65B35DE8121C261E003EAD18 /* high.wav */, - 65B35DE9121C261E003EAD18 /* hippodrome.wav */, - 65B35DEA121C261E003EAD18 /* hold position.wav */, - 65B35DEB121C261E003EAD18 /* home location.wav */, - 65B35DEC121C261E003EAD18 /* initialised.wav */, - 65B35DED121C261E003EAD18 /* initiated.wav */, - 65B35DEE121C261E003EAD18 /* KPH.wav */, - 65B35DEF121C261E003EAD18 /* landing.wav */, - 65B35DF0121C261E003EAD18 /* launch.wav */, - 65B35DF1121C261E003EAD18 /* left.wav */, - 65B35DF2121C261E003EAD18 /* logging.wav */, - 65B35DF3121C261E003EAD18 /* lost.wav */, - 65B35DF4121C261E003EAD18 /* low altitude.wav */, - 65B35DF5121C261E003EAD18 /* low battery.wav */, - 65B35DF6121C261E003EAD18 /* low gps quality.wav */, - 65B35DF7121C261E003EAD18 /* manual flight.wav */, - 65B35DF8121C261E003EAD18 /* maximum.wav */, - 65B35DF9121C261E003EAD18 /* meters.wav */, - 65B35DFA121C261E003EAD18 /* minimum.wav */, - 65B35DFB121C261E003EAD18 /* mode.wav */, - 65B35DFC121C261E003EAD18 /* MPH.wav */, - 65B35DFD121C261E003EAD18 /* navigation.wav */, - 65B35DFE121C261E003EAD18 /* openpilot.wav */, - 65B35DFF121C261E003EAD18 /* point.wav */, - 65B35E00121C261E003EAD18 /* range.wav */, - 65B35E01121C261E003EAD18 /* reached.wav */, - 65B35E02121C261E003EAD18 /* ready for flight.wav */, - 65B35E03121C261E003EAD18 /* return home.wav */, - 65B35E04121C261E003EAD18 /* right.wav */, - 65B35E05121C261E003EAD18 /* set.wav */, - 65B35E06121C261E003EAD18 /* speed.wav */, - 65B35E07121C261E003EAD18 /* stabilization.wav */, - 65B35E08121C261E003EAD18 /* started.wav */, - 65B35E09121C261E003EAD18 /* stopped.wav */, - 65B35E0A121C261E003EAD18 /* takeoff.wav */, - 65B35E0B121C261E003EAD18 /* telemetry.wav */, - 65B35E0C121C261E003EAD18 /* time.wav */, - 65B35E0D121C261E003EAD18 /* triggered.wav */, - 65B35E0E121C261E003EAD18 /* uav.wav */, - 65B35E0F121C261E003EAD18 /* volts.wav */, - 65B35E10121C261E003EAD18 /* warning.wav */, - 65B35E11121C261E003EAD18 /* waypoint.wav */, - 65B35E12121C261E003EAD18 /* whoopsound.wav */, - ); - path = default; - sourceTree = ""; - }; - 65B35E14121C261E003EAD18 /* translations */ = { - isa = PBXGroup; - children = ( - 65B35E15121C261E003EAD18 /* extract-mimetypes.xq */, - 65B35E16121C261E003EAD18 /* extract-mimetypes.xq.in */, - 65B35E17121C261E003EAD18 /* openpilotgcs_de.ts */, - 65B35E18121C261E003EAD18 /* openpilotgcs_es.ts */, - 65B35E19121C261E003EAD18 /* openpilotgcs_fr.ts */, - 65B35E1A121C261E003EAD18 /* openpilotgcs_it.ts */, - 65B35E1B121C261E003EAD18 /* Readme.txt */, - 65B35E1C121C261E003EAD18 /* translations.pro */, - ); - path = translations; - sourceTree = ""; - }; - 65B35E1E121C261E003EAD18 /* src */ = { - isa = PBXGroup; - children = ( - 65B35E1F121C261E003EAD18 /* app */, - 65B35E28121C261E003EAD18 /* experimental */, - 65B35E9A121C261E003EAD18 /* libs */, - 65B364B2121C261F003EAD18 /* openpilotgcslibrary.pri */, - 65B364B3121C261F003EAD18 /* openpilotgcsplugin.pri */, - 65B364B4121C261F003EAD18 /* plugins */, - 65B367C8121C2620003EAD18 /* rpath.pri */, - 65B367C9121C2620003EAD18 /* shared */, - 65B367FF121C2620003EAD18 /* src.pro */, - ); - path = src; - sourceTree = ""; - }; - 65B35E1F121C261E003EAD18 /* app */ = { - isa = PBXGroup; - children = ( - 65B35E20121C261E003EAD18 /* app.pro */, - 65B35E21121C261E003EAD18 /* Info.plist */, - 65B35E22121C261E003EAD18 /* main.cpp */, - 65B35E23121C261E003EAD18 /* openpilotgcs.icns */, - 65B35E24121C261E003EAD18 /* openpilotgcs.ico */, - 65B35E25121C261E003EAD18 /* openpilotgcs.rc */, - 65B35E26121C261E003EAD18 /* prifile.icns */, - 65B35E27121C261E003EAD18 /* profile.icns */, - ); - path = app; - sourceTree = ""; - }; - 65B35E28121C261E003EAD18 /* experimental */ = { - isa = PBXGroup; - children = ( - 65B35E29121C261E003EAD18 /* HIDTest */, - 65B35E2C121C261E003EAD18 /* OPMapWidget */, - 65B35E93121C261E003EAD18 /* tools */, - ); - path = experimental; - sourceTree = ""; - }; - 65B35E29121C261E003EAD18 /* HIDTest */ = { - isa = PBXGroup; - children = ( - 65B35E2A121C261E003EAD18 /* HIDTest.pro */, - 65B35E2B121C261E003EAD18 /* main.cpp */, - ); - path = HIDTest; - sourceTree = ""; - }; - 65B35E2C121C261E003EAD18 /* OPMapWidget */ = { - isa = PBXGroup; - children = ( - 65B35E2D121C261E003EAD18 /* common.pri */, - 65B35E2E121C261E003EAD18 /* core */, - 65B35E54121C261E003EAD18 /* finaltest */, - 65B35E5B121C261E003EAD18 /* gettilestest */, - 65B35E5E121C261E003EAD18 /* internals */, - 65B35E81121C261E003EAD18 /* mapwidget */, - 65B35E8A121C261E003EAD18 /* OPMapControl.pro */, - 65B35E8B121C261E003EAD18 /* teste */, - 65B35E8E121C261E003EAD18 /* widgettest */, - ); - path = OPMapWidget; - sourceTree = ""; - }; - 65B35E2E121C261E003EAD18 /* core */ = { - isa = PBXGroup; - children = ( - 65B35E2F121C261E003EAD18 /* accessmode.h */, - 65B35E30121C261E003EAD18 /* alllayersoftype.cpp */, - 65B35E31121C261E003EAD18 /* alllayersoftype.h */, - 65B35E32121C261E003EAD18 /* cache.cpp */, - 65B35E33121C261E003EAD18 /* cache.h */, - 65B35E34121C261E003EAD18 /* cacheitemqueue.cpp */, - 65B35E35121C261E003EAD18 /* cacheitemqueue.h */, - 65B35E36121C261E003EAD18 /* core.pro */, - 65B35E37121C261E003EAD18 /* debugheader.h */, - 65B35E38121C261E003EAD18 /* geodecoderstatus.h */, - 65B35E39121C261E003EAD18 /* kibertilecache.cpp */, - 65B35E3A121C261E003EAD18 /* kibertilecache.h */, - 65B35E3B121C261E003EAD18 /* languagetype.cpp */, - 65B35E3C121C261E003EAD18 /* languagetype.h */, - 65B35E3D121C261E003EAD18 /* maptype.h */, - 65B35E3E121C261E003EAD18 /* memorycache.cpp */, - 65B35E3F121C261E003EAD18 /* memorycache.h */, - 65B35E40121C261E003EAD18 /* opmaps.cpp */, - 65B35E41121C261E003EAD18 /* opmaps.h */, - 65B35E42121C261E003EAD18 /* placemark.cpp */, - 65B35E43121C261E003EAD18 /* placemark.h */, - 65B35E44121C261E003EAD18 /* point.cpp */, - 65B35E45121C261E003EAD18 /* point.h */, - 65B35E46121C261E003EAD18 /* providerstrings.cpp */, - 65B35E47121C261E003EAD18 /* providerstrings.h */, - 65B35E48121C261E003EAD18 /* pureimage.cpp */, - 65B35E49121C261E003EAD18 /* pureimage.h */, - 65B35E4A121C261E003EAD18 /* pureimagecache.cpp */, - 65B35E4B121C261E003EAD18 /* pureimagecache.h */, - 65B35E4C121C261E003EAD18 /* rawtile.cpp */, - 65B35E4D121C261E003EAD18 /* rawtile.h */, - 65B35E4E121C261E003EAD18 /* size.cpp */, - 65B35E4F121C261E003EAD18 /* size.h */, - 65B35E50121C261E003EAD18 /* tilecachequeue.cpp */, - 65B35E51121C261E003EAD18 /* tilecachequeue.h */, - 65B35E52121C261E003EAD18 /* urlfactory.cpp */, - 65B35E53121C261E003EAD18 /* urlfactory.h */, - ); - path = core; - sourceTree = ""; - }; - 65B35E54121C261E003EAD18 /* finaltest */ = { - isa = PBXGroup; - children = ( - 65B35E55121C261E003EAD18 /* finaltest.pro */, - 65B35E56121C261E003EAD18 /* main.cpp */, - 65B35E57121C261E003EAD18 /* mainwindow.cpp */, - 65B35E58121C261E003EAD18 /* mainwindow.h */, - 65B35E59121C261E003EAD18 /* mainwindow.ui */, - 65B35E5A121C261E003EAD18 /* ui_mainwindow.h */, - ); - path = finaltest; - sourceTree = ""; - }; - 65B35E5B121C261E003EAD18 /* gettilestest */ = { - isa = PBXGroup; - children = ( - 65B35E5C121C261E003EAD18 /* gettilestest.pro */, - 65B35E5D121C261E003EAD18 /* main.cpp */, - ); - path = gettilestest; - sourceTree = ""; - }; - 65B35E5E121C261E003EAD18 /* internals */ = { - isa = PBXGroup; - children = ( - 65B35E5F121C261E003EAD18 /* copyrightstrings.h */, - 65B35E60121C261E003EAD18 /* core.cpp */, - 65B35E61121C261E003EAD18 /* core.h */, - 65B35E62121C261E003EAD18 /* debugheader.h */, - 65B35E63121C261E003EAD18 /* internals.pro */, - 65B35E64121C261E003EAD18 /* loadtask.cpp */, - 65B35E65121C261E003EAD18 /* loadtask.h */, - 65B35E66121C261E003EAD18 /* MouseWheelZoomType.cpp */, - 65B35E67121C261E003EAD18 /* mousewheelzoomtype.h */, - 65B35E68121C261E003EAD18 /* pointlatlng.cpp */, - 65B35E69121C261E003EAD18 /* pointlatlng.h */, - 65B35E6A121C261E003EAD18 /* projections */, - 65B35E75121C261E003EAD18 /* pureprojection.cpp */, - 65B35E76121C261E003EAD18 /* pureprojection.h */, - 65B35E77121C261E003EAD18 /* rectangle.cpp */, - 65B35E78121C261E003EAD18 /* rectangle.h */, - 65B35E79121C261E003EAD18 /* rectlatlng.cpp */, - 65B35E7A121C261E003EAD18 /* rectlatlng.h */, - 65B35E7B121C261E003EAD18 /* sizelatlng.cpp */, - 65B35E7C121C261E003EAD18 /* sizelatlng.h */, - 65B35E7D121C261E003EAD18 /* tile.cpp */, - 65B35E7E121C261E003EAD18 /* tile.h */, - 65B35E7F121C261E003EAD18 /* tilematrix.cpp */, - 65B35E80121C261E003EAD18 /* tilematrix.h */, - ); - path = internals; - sourceTree = ""; - }; - 65B35E6A121C261E003EAD18 /* projections */ = { - isa = PBXGroup; - children = ( - 65B35E6B121C261E003EAD18 /* lks94projection.cpp */, - 65B35E6C121C261E003EAD18 /* lks94projection.h */, - 65B35E6D121C261E003EAD18 /* mercatorprojection.cpp */, - 65B35E6E121C261E003EAD18 /* mercatorprojection.h */, - 65B35E6F121C261E003EAD18 /* mercatorprojectionyandex.cpp */, - 65B35E70121C261E003EAD18 /* mercatorprojectionyandex.h */, - 65B35E71121C261E003EAD18 /* platecarreeprojection.cpp */, - 65B35E72121C261E003EAD18 /* platecarreeprojection.h */, - 65B35E73121C261E003EAD18 /* platecarreeprojectionpergo.cpp */, - 65B35E74121C261E003EAD18 /* platecarreeprojectionpergo.h */, - ); - path = projections; - sourceTree = ""; - }; - 65B35E81121C261E003EAD18 /* mapwidget */ = { - isa = PBXGroup; - children = ( - 65B35E82121C261E003EAD18 /* mapgraphicitem.cpp */, - 65B35E83121C261E003EAD18 /* mapgraphicitem.h */, - 65B35E84121C261E003EAD18 /* mapresources.qrc */, - 65B35E85121C261E003EAD18 /* mapwidget.pro */, - 65B35E86121C261E003EAD18 /* opmapcontrol.cpp */, - 65B35E87121C261E003EAD18 /* opmapcontrol.h */, - 65B35E88121C261E003EAD18 /* opmapwidget.cpp */, - 65B35E89121C261E003EAD18 /* opmapwidget.h */, - ); - path = mapwidget; - sourceTree = ""; - }; - 65B35E8B121C261E003EAD18 /* teste */ = { - isa = PBXGroup; - children = ( - 65B35E8C121C261E003EAD18 /* main.cpp */, - 65B35E8D121C261E003EAD18 /* teste.pro */, - ); - path = teste; - sourceTree = ""; - }; - 65B35E8E121C261E003EAD18 /* widgettest */ = { - isa = PBXGroup; - children = ( - 65B35E8F121C261E003EAD18 /* main.cpp */, - 65B35E90121C261E003EAD18 /* map.cpp */, - 65B35E91121C261E003EAD18 /* map.h */, - 65B35E92121C261E003EAD18 /* widgettest.pro */, - ); - path = widgettest; - sourceTree = ""; - }; - 65B35E93121C261E003EAD18 /* tools */ = { - isa = PBXGroup; - children = ( - 65B35E94121C261E003EAD18 /* DocumentationHelper */, - ); - path = tools; - sourceTree = ""; - }; - 65B35E94121C261E003EAD18 /* DocumentationHelper */ = { - isa = PBXGroup; - children = ( - 65B35E95121C261E003EAD18 /* DocumentationHelper.pro */, - 65B35E96121C261E003EAD18 /* main.cpp */, - 65B35E97121C261E003EAD18 /* mainwindow.cpp */, - 65B35E98121C261E003EAD18 /* mainwindow.h */, - 65B35E99121C261E003EAD18 /* mainwindow.ui */, - ); - path = DocumentationHelper; - sourceTree = ""; - }; - 65B35E9A121C261E003EAD18 /* libs */ = { - isa = PBXGroup; - children = ( - 65B35E9B121C261E003EAD18 /* aggregation */, - 65B35EA9121C261E003EAD18 /* extensionsystem */, - 65B35F2F121C261E003EAD18 /* glc_lib */, - 65B360A5121C261E003EAD18 /* libqxt */, - 65B3632F121C261F003EAD18 /* libs.pro */, - 65B36330121C261F003EAD18 /* opmapcontrol */, - 65B363A4121C261F003EAD18 /* qextserialport */, - 65B363B2121C261F003EAD18 /* qtconcurrent */, - 65B363B9121C261F003EAD18 /* qwt */, - 65B36449121C261F003EAD18 /* qymodem */, - 65B36455121C261F003EAD18 /* uavobjgenerator */, - 65B3645C121C261F003EAD18 /* utils */, - ); - path = libs; - sourceTree = ""; - }; - 65B35E9B121C261E003EAD18 /* aggregation */ = { - isa = PBXGroup; - children = ( - 65B35E9C121C261E003EAD18 /* aggregate.cpp */, - 65B35E9D121C261E003EAD18 /* aggregate.h */, - 65B35E9E121C261E003EAD18 /* aggregation.pri */, - 65B35E9F121C261E003EAD18 /* aggregation.pro */, - 65B35EA0121C261E003EAD18 /* aggregation_global.h */, - 65B35EA1121C261E003EAD18 /* examples */, - ); - path = aggregation; - sourceTree = ""; - }; - 65B35EA1121C261E003EAD18 /* examples */ = { - isa = PBXGroup; - children = ( - 65B35EA2121C261E003EAD18 /* examples.pro */, - 65B35EA3121C261E003EAD18 /* text */, - ); - path = examples; - sourceTree = ""; - }; - 65B35EA3121C261E003EAD18 /* text */ = { - isa = PBXGroup; - children = ( - 65B35EA4121C261E003EAD18 /* main.cpp */, - 65B35EA5121C261E003EAD18 /* main.h */, - 65B35EA6121C261E003EAD18 /* main.ui */, - 65B35EA7121C261E003EAD18 /* myinterfaces.h */, - 65B35EA8121C261E003EAD18 /* text.pro */, - ); - path = text; - sourceTree = ""; - }; - 65B35EA9121C261E003EAD18 /* extensionsystem */ = { - isa = PBXGroup; - children = ( - 65B35EAA121C261E003EAD18 /* extensionsystem.pri */, - 65B35EAB121C261E003EAD18 /* extensionsystem.pro */, - 65B35EAC121C261E003EAD18 /* extensionsystem_dependencies.pri */, - 65B35EAD121C261E003EAD18 /* extensionsystem_global.h */, - 65B35EAE121C261E003EAD18 /* images */, - 65B35EB1121C261E003EAD18 /* iplugin.cpp */, - 65B35EB2121C261E003EAD18 /* iplugin.h */, - 65B35EB3121C261E003EAD18 /* iplugin_p.h */, - 65B35EB4121C261E003EAD18 /* optionsparser.cpp */, - 65B35EB5121C261E003EAD18 /* optionsparser.h */, - 65B35EB6121C261E003EAD18 /* plugindetailsview.cpp */, - 65B35EB7121C261E003EAD18 /* plugindetailsview.h */, - 65B35EB8121C261E003EAD18 /* plugindetailsview.ui */, - 65B35EB9121C261E003EAD18 /* pluginerrorview.cpp */, - 65B35EBA121C261E003EAD18 /* pluginerrorview.h */, - 65B35EBB121C261E003EAD18 /* pluginerrorview.ui */, - 65B35EBC121C261E003EAD18 /* pluginmanager.cpp */, - 65B35EBD121C261E003EAD18 /* pluginmanager.h */, - 65B35EBE121C261E003EAD18 /* pluginmanager_p.h */, - 65B35EBF121C261E003EAD18 /* pluginspec.cpp */, - 65B35EC0121C261E003EAD18 /* pluginspec.h */, - 65B35EC1121C261E003EAD18 /* pluginspec_p.h */, - 65B35EC2121C261E003EAD18 /* pluginview.cpp */, - 65B35EC3121C261E003EAD18 /* pluginview.h */, - 65B35EC4121C261E003EAD18 /* pluginview.qrc */, - 65B35EC5121C261E003EAD18 /* pluginview.ui */, - 65B35EC6121C261E003EAD18 /* pluginview_p.h */, - 65B35EC7121C261E003EAD18 /* test */, - ); - path = extensionsystem; - sourceTree = ""; - }; - 65B35EAE121C261E003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B35EAF121C261E003EAD18 /* error.png */, - 65B35EB0121C261E003EAD18 /* ok.png */, - ); - path = images; - sourceTree = ""; - }; - 65B35EC7121C261E003EAD18 /* test */ = { - isa = PBXGroup; - children = ( - 65B35EC8121C261E003EAD18 /* auto */, - 65B35F12121C261E003EAD18 /* extensionsystem_test.pri */, - 65B35F13121C261E003EAD18 /* manual */, - 65B35F2E121C261E003EAD18 /* test.pro */, - ); - path = test; - sourceTree = ""; - }; - 65B35EC8121C261E003EAD18 /* auto */ = { - isa = PBXGroup; - children = ( - 65B35EC9121C261E003EAD18 /* auto.pro */, - 65B35ECA121C261E003EAD18 /* pluginmanager */, - 65B35EF6121C261E003EAD18 /* pluginspec */, - ); - path = auto; - sourceTree = ""; - }; - 65B35ECA121C261E003EAD18 /* pluginmanager */ = { - isa = PBXGroup; - children = ( - 65B35ECB121C261E003EAD18 /* circularplugins */, - 65B35EDC121C261E003EAD18 /* correctplugins1 */, - 65B35EED121C261E003EAD18 /* pluginmanager.pro */, - 65B35EEE121C261E003EAD18 /* plugins */, - 65B35EF3121C261E003EAD18 /* test.pro */, - 65B35EF4121C261E003EAD18 /* test.sh */, - 65B35EF5121C261E003EAD18 /* tst_pluginmanager.cpp */, - ); - path = pluginmanager; - sourceTree = ""; - }; - 65B35ECB121C261E003EAD18 /* circularplugins */ = { - isa = PBXGroup; - children = ( - 65B35ECC121C261E003EAD18 /* circularplugins.pro */, - 65B35ECD121C261E003EAD18 /* plugin1 */, - 65B35ED2121C261E003EAD18 /* plugin2 */, - 65B35ED7121C261E003EAD18 /* plugin3 */, - ); - path = circularplugins; - sourceTree = ""; - }; - 65B35ECD121C261E003EAD18 /* plugin1 */ = { - isa = PBXGroup; - children = ( - 65B35ECE121C261E003EAD18 /* plugin.xml */, - 65B35ECF121C261E003EAD18 /* plugin1.cpp */, - 65B35ED0121C261E003EAD18 /* plugin1.h */, - 65B35ED1121C261E003EAD18 /* plugin1.pro */, - ); - path = plugin1; - sourceTree = ""; - }; - 65B35ED2121C261E003EAD18 /* plugin2 */ = { - isa = PBXGroup; - children = ( - 65B35ED3121C261E003EAD18 /* plugin.xml */, - 65B35ED4121C261E003EAD18 /* plugin2.cpp */, - 65B35ED5121C261E003EAD18 /* plugin2.h */, - 65B35ED6121C261E003EAD18 /* plugin2.pro */, - ); - path = plugin2; - sourceTree = ""; - }; - 65B35ED7121C261E003EAD18 /* plugin3 */ = { - isa = PBXGroup; - children = ( - 65B35ED8121C261E003EAD18 /* plugin.xml */, - 65B35ED9121C261E003EAD18 /* plugin3.cpp */, - 65B35EDA121C261E003EAD18 /* plugin3.h */, - 65B35EDB121C261E003EAD18 /* plugin3.pro */, - ); - path = plugin3; - sourceTree = ""; - }; - 65B35EDC121C261E003EAD18 /* correctplugins1 */ = { - isa = PBXGroup; - children = ( - 65B35EDD121C261E003EAD18 /* correctplugins1.pro */, - 65B35EDE121C261E003EAD18 /* plugin1 */, - 65B35EE3121C261E003EAD18 /* plugin2 */, - 65B35EE8121C261E003EAD18 /* plugin3 */, - ); - path = correctplugins1; - sourceTree = ""; - }; - 65B35EDE121C261E003EAD18 /* plugin1 */ = { - isa = PBXGroup; - children = ( - 65B35EDF121C261E003EAD18 /* plugin.spec */, - 65B35EE0121C261E003EAD18 /* plugin1.cpp */, - 65B35EE1121C261E003EAD18 /* plugin1.h */, - 65B35EE2121C261E003EAD18 /* plugin1.pro */, - ); - path = plugin1; - sourceTree = ""; - }; - 65B35EE3121C261E003EAD18 /* plugin2 */ = { - isa = PBXGroup; - children = ( - 65B35EE4121C261E003EAD18 /* plugin.spec */, - 65B35EE5121C261E003EAD18 /* plugin2.cpp */, - 65B35EE6121C261E003EAD18 /* plugin2.h */, - 65B35EE7121C261E003EAD18 /* plugin2.pro */, - ); - path = plugin2; - sourceTree = ""; - }; - 65B35EE8121C261E003EAD18 /* plugin3 */ = { - isa = PBXGroup; - children = ( - 65B35EE9121C261E003EAD18 /* plugin.spec */, - 65B35EEA121C261E003EAD18 /* plugin3.cpp */, - 65B35EEB121C261E003EAD18 /* plugin3.h */, - 65B35EEC121C261E003EAD18 /* plugin3.pro */, - ); - path = plugin3; - sourceTree = ""; - }; - 65B35EEE121C261E003EAD18 /* plugins */ = { - isa = PBXGroup; - children = ( - 65B35EEF121C261E003EAD18 /* myplug */, - 65B35EF1121C261E003EAD18 /* otherplugin.xml */, - 65B35EF2121C261E003EAD18 /* plugin1.xml */, - ); - path = plugins; - sourceTree = ""; - }; - 65B35EEF121C261E003EAD18 /* myplug */ = { - isa = PBXGroup; - children = ( - 65B35EF0121C261E003EAD18 /* myplug.xml */, - ); - path = myplug; - sourceTree = ""; - }; - 65B35EF6121C261E003EAD18 /* pluginspec */ = { - isa = PBXGroup; - children = ( - 65B35EF7121C261E003EAD18 /* pluginspec.pro */, - 65B35EF8121C261E003EAD18 /* test.pro */, - 65B35EF9121C261E003EAD18 /* test.sh */, - 65B35EFA121C261E003EAD18 /* testdependencies */, - 65B35F00121C261E003EAD18 /* testdir */, - 65B35F02121C261E003EAD18 /* testplugin */, - 65B35F08121C261E003EAD18 /* testspecs */, - 65B35F11121C261E003EAD18 /* tst_pluginspec.cpp */, - ); - path = pluginspec; - sourceTree = ""; - }; - 65B35EFA121C261E003EAD18 /* testdependencies */ = { - isa = PBXGroup; - children = ( - 65B35EFB121C261E003EAD18 /* spec1.xml */, - 65B35EFC121C261E003EAD18 /* spec2.xml */, - 65B35EFD121C261E003EAD18 /* spec3.xml */, - 65B35EFE121C261E003EAD18 /* spec4.xml */, - 65B35EFF121C261E003EAD18 /* spec5.xml */, - ); - path = testdependencies; - sourceTree = ""; - }; - 65B35F00121C261E003EAD18 /* testdir */ = { - isa = PBXGroup; - children = ( - 65B35F01121C261E003EAD18 /* spec.xml */, - ); - path = testdir; - sourceTree = ""; - }; - 65B35F02121C261E003EAD18 /* testplugin */ = { - isa = PBXGroup; - children = ( - 65B35F03121C261E003EAD18 /* testplugin.cpp */, - 65B35F04121C261E003EAD18 /* testplugin.h */, - 65B35F05121C261E003EAD18 /* testplugin.pro */, - 65B35F06121C261E003EAD18 /* testplugin.xml */, - 65B35F07121C261E003EAD18 /* testplugin_global.h */, - ); - path = testplugin; - sourceTree = ""; - }; - 65B35F08121C261E003EAD18 /* testspecs */ = { - isa = PBXGroup; - children = ( - 65B35F09121C261E003EAD18 /* simplespec.xml */, - 65B35F0A121C261E003EAD18 /* spec1.xml */, - 65B35F0B121C261E003EAD18 /* spec2.xml */, - 65B35F0C121C261E003EAD18 /* spec_wrong1.xml */, - 65B35F0D121C261E003EAD18 /* spec_wrong2.xml */, - 65B35F0E121C261E003EAD18 /* spec_wrong3.xml */, - 65B35F0F121C261E003EAD18 /* spec_wrong4.xml */, - 65B35F10121C261E003EAD18 /* spec_wrong5.xml */, - ); - path = testspecs; - sourceTree = ""; - }; - 65B35F13121C261E003EAD18 /* manual */ = { - isa = PBXGroup; - children = ( - 65B35F14121C261E003EAD18 /* manual.pro */, - 65B35F15121C261E003EAD18 /* pluginview */, - ); - path = manual; - sourceTree = ""; - }; - 65B35F15121C261E003EAD18 /* pluginview */ = { - isa = PBXGroup; - children = ( - 65B35F16121C261E003EAD18 /* plugindialog.cpp */, - 65B35F17121C261E003EAD18 /* plugindialog.h */, - 65B35F18121C261E003EAD18 /* plugins */, - 65B35F2B121C261E003EAD18 /* pluginview.pro */, - 65B35F2C121C261E003EAD18 /* test.pro */, - 65B35F2D121C261E003EAD18 /* test.sh */, - ); - path = pluginview; - sourceTree = ""; - }; - 65B35F18121C261E003EAD18 /* plugins */ = { - isa = PBXGroup; - children = ( - 65B35F19121C261E003EAD18 /* plugin1 */, - 65B35F1E121C261E003EAD18 /* plugin2 */, - 65B35F23121C261E003EAD18 /* plugin3 */, - 65B35F28121C261E003EAD18 /* plugin4 */, - 65B35F2A121C261E003EAD18 /* plugins.pro */, - ); - path = plugins; - sourceTree = ""; - }; - 65B35F19121C261E003EAD18 /* plugin1 */ = { - isa = PBXGroup; - children = ( - 65B35F1A121C261E003EAD18 /* plugin.xml */, - 65B35F1B121C261E003EAD18 /* plugin1.cpp */, - 65B35F1C121C261E003EAD18 /* plugin1.h */, - 65B35F1D121C261E003EAD18 /* plugin1.pro */, - ); - path = plugin1; - sourceTree = ""; - }; - 65B35F1E121C261E003EAD18 /* plugin2 */ = { - isa = PBXGroup; - children = ( - 65B35F1F121C261E003EAD18 /* plugin.xml */, - 65B35F20121C261E003EAD18 /* plugin2.cpp */, - 65B35F21121C261E003EAD18 /* plugin2.h */, - 65B35F22121C261E003EAD18 /* plugin2.pro */, - ); - path = plugin2; - sourceTree = ""; - }; - 65B35F23121C261E003EAD18 /* plugin3 */ = { - isa = PBXGroup; - children = ( - 65B35F24121C261E003EAD18 /* plugin.xml */, - 65B35F25121C261E003EAD18 /* plugin3.cpp */, - 65B35F26121C261E003EAD18 /* plugin3.h */, - 65B35F27121C261E003EAD18 /* plugin3.pro */, - ); - path = plugin3; - sourceTree = ""; - }; - 65B35F28121C261E003EAD18 /* plugin4 */ = { - isa = PBXGroup; - children = ( - 65B35F29121C261E003EAD18 /* plugin.xml */, - ); - path = plugin4; - sourceTree = ""; - }; - 65B35F2F121C261E003EAD18 /* glc_lib */ = { - isa = PBXGroup; - children = ( - 65B35F30121C261E003EAD18 /* 3DWidget */, - 65B35F41121C261E003EAD18 /* 3rdparty */, - 65B35FA1121C261E003EAD18 /* Build */, - 65B35FA2121C261E003EAD18 /* COPYING */, - 65B35FA3121C261E003EAD18 /* geometry */, - 65B35FCE121C261E003EAD18 /* glc_boundingbox.cpp */, - 65B35FCF121C261E003EAD18 /* glc_boundingbox.h */, - 65B35FD0121C261E003EAD18 /* glc_cachemanager.cpp */, - 65B35FD1121C261E003EAD18 /* glc_cachemanager.h */, - 65B35FD2121C261E003EAD18 /* glc_config.h */, - 65B35FD3121C261E003EAD18 /* glc_exception.cpp */, - 65B35FD4121C261E003EAD18 /* glc_exception.h */, - 65B35FD5121C261E003EAD18 /* glc_ext.cpp */, - 65B35FD6121C261E003EAD18 /* glc_ext.h */, - 65B35FD7121C261E003EAD18 /* glc_factory.cpp */, - 65B35FD8121C261E003EAD18 /* glc_factory.h */, - 65B35FD9121C261E003EAD18 /* glc_fileformatexception.cpp */, - 65B35FDA121C261E003EAD18 /* glc_fileformatexception.h */, - 65B35FDB121C261E003EAD18 /* glc_global.cpp */, - 65B35FDC121C261E003EAD18 /* glc_global.h */, - 65B35FDD121C261E003EAD18 /* glc_lib.pri */, - 65B35FDE121C261E003EAD18 /* glc_lib.pro */, - 65B35FDF121C261E003EAD18 /* glc_object.cpp */, - 65B35FE0121C261E003EAD18 /* glc_object.h */, - 65B35FE1121C261E003EAD18 /* glc_openglexception.cpp */, - 65B35FE2121C261E003EAD18 /* glc_openglexception.h */, - 65B35FE3121C261E003EAD18 /* glc_renderstatistics.cpp */, - 65B35FE4121C261E003EAD18 /* glc_renderstatistics.h */, - 65B35FE5121C261E003EAD18 /* glc_state.cpp */, - 65B35FE6121C261E003EAD18 /* glc_state.h */, - 65B35FE7121C261E003EAD18 /* include */, - 65B3603B121C261E003EAD18 /* io */, - 65B3604E121C261E003EAD18 /* maths */, - 65B36060121C261E003EAD18 /* sceneGraph */, - 65B36077121C261E003EAD18 /* shading */, - 65B36084121C261E003EAD18 /* viewport */, - ); - path = glc_lib; - sourceTree = ""; - }; - 65B35F30121C261E003EAD18 /* 3DWidget */ = { - isa = PBXGroup; - children = ( - 65B35F31121C261E003EAD18 /* glc_3dwidget.cpp */, - 65B35F32121C261E003EAD18 /* glc_3dwidget.h */, - 65B35F33121C261E003EAD18 /* glc_3dwidgetmanager.cpp */, - 65B35F34121C261E003EAD18 /* glc_3dwidgetmanager.h */, - 65B35F35121C261E003EAD18 /* glc_3dwidgetmanagerhandle.cpp */, - 65B35F36121C261E003EAD18 /* glc_3dwidgetmanagerhandle.h */, - 65B35F37121C261E003EAD18 /* glc_abstractmanipulator.cpp */, - 65B35F38121C261E003EAD18 /* glc_abstractmanipulator.h */, - 65B35F39121C261E003EAD18 /* glc_axis.cpp */, - 65B35F3A121C261E003EAD18 /* glc_axis.h */, - 65B35F3B121C261E003EAD18 /* glc_cuttingplane.cpp */, - 65B35F3C121C261E003EAD18 /* glc_cuttingplane.h */, - 65B35F3D121C261E003EAD18 /* glc_pullmanipulator.cpp */, - 65B35F3E121C261E003EAD18 /* glc_pullmanipulator.h */, - 65B35F3F121C261E003EAD18 /* glc_rotationmanipulator.cpp */, - 65B35F40121C261E003EAD18 /* glc_rotationmanipulator.h */, - ); - path = 3DWidget; - sourceTree = ""; - }; - 65B35F41121C261E003EAD18 /* 3rdparty */ = { - isa = PBXGroup; - children = ( - 65B35F42121C261E003EAD18 /* glext */, - 65B35F44121C261E003EAD18 /* lib3ds */, - 65B35F6E121C261E003EAD18 /* quazip */, - 65B35F7D121C261E003EAD18 /* zlib */, - ); - path = 3rdparty; - sourceTree = ""; - }; - 65B35F42121C261E003EAD18 /* glext */ = { - isa = PBXGroup; - children = ( - 65B35F43121C261E003EAD18 /* glext.h */, - ); - path = glext; - sourceTree = ""; - }; - 65B35F44121C261E003EAD18 /* lib3ds */ = { - isa = PBXGroup; - children = ( - 65B35F45121C261E003EAD18 /* atmosphere.c */, - 65B35F46121C261E003EAD18 /* atmosphere.h */, - 65B35F47121C261E003EAD18 /* AUTHORS */, - 65B35F48121C261E003EAD18 /* background.c */, - 65B35F49121C261E003EAD18 /* background.h */, - 65B35F4A121C261E003EAD18 /* camera.c */, - 65B35F4B121C261E003EAD18 /* camera.h */, - 65B35F4C121C261E003EAD18 /* ChangeLog */, - 65B35F4D121C261E003EAD18 /* chunk.c */, - 65B35F4E121C261E003EAD18 /* chunk.h */, - 65B35F4F121C261E003EAD18 /* chunktable.h */, - 65B35F50121C261E003EAD18 /* ease.c */, - 65B35F51121C261E003EAD18 /* ease.h */, - 65B35F52121C261E003EAD18 /* file.c */, - 65B35F53121C261E003EAD18 /* file.h */, - 65B35F54121C261E003EAD18 /* io.c */, - 65B35F55121C261E003EAD18 /* io.h */, - 65B35F56121C261E003EAD18 /* light.c */, - 65B35F57121C261E003EAD18 /* light.h */, - 65B35F58121C261E003EAD18 /* material.c */, - 65B35F59121C261E003EAD18 /* material.h */, - 65B35F5A121C261E003EAD18 /* matrix.c */, - 65B35F5B121C261E003EAD18 /* matrix.h */, - 65B35F5C121C261E003EAD18 /* mesh.c */, - 65B35F5D121C261E003EAD18 /* mesh.h */, - 65B35F5E121C261E003EAD18 /* node.c */, - 65B35F5F121C261E003EAD18 /* node.h */, - 65B35F60121C261E003EAD18 /* quat.c */, - 65B35F61121C261E003EAD18 /* quat.h */, - 65B35F62121C261E003EAD18 /* README */, - 65B35F63121C261E003EAD18 /* shadow.c */, - 65B35F64121C261E003EAD18 /* shadow.h */, - 65B35F65121C261E003EAD18 /* tcb.c */, - 65B35F66121C261E003EAD18 /* tcb.h */, - 65B35F67121C261E003EAD18 /* tracks.c */, - 65B35F68121C261E003EAD18 /* tracks.h */, - 65B35F69121C261E003EAD18 /* types.h */, - 65B35F6A121C261E003EAD18 /* vector.c */, - 65B35F6B121C261E003EAD18 /* vector.h */, - 65B35F6C121C261E003EAD18 /* viewport.c */, - 65B35F6D121C261E003EAD18 /* viewport.h */, - ); - path = lib3ds; - sourceTree = ""; - }; - 65B35F6E121C261E003EAD18 /* quazip */ = { - isa = PBXGroup; - children = ( - 65B35F6F121C261E003EAD18 /* crypt.h */, - 65B35F70121C261E003EAD18 /* ioapi.c */, - 65B35F71121C261E003EAD18 /* ioapi.h */, - 65B35F72121C261E003EAD18 /* quazip.cpp */, - 65B35F73121C261E003EAD18 /* quazip.h */, - 65B35F74121C261E003EAD18 /* quazipfile.cpp */, - 65B35F75121C261E003EAD18 /* quazipfile.h */, - 65B35F76121C261E003EAD18 /* quazipfileinfo.h */, - 65B35F77121C261E003EAD18 /* quazipnewinfo.cpp */, - 65B35F78121C261E003EAD18 /* quazipnewinfo.h */, - 65B35F79121C261E003EAD18 /* unzip.c */, - 65B35F7A121C261E003EAD18 /* unzip.h */, - 65B35F7B121C261E003EAD18 /* zip.c */, - 65B35F7C121C261E003EAD18 /* zip.h */, - ); - path = quazip; - sourceTree = ""; - }; - 65B35F7D121C261E003EAD18 /* zlib */ = { - isa = PBXGroup; - children = ( - 65B35F7E121C261E003EAD18 /* adler32.c */, - 65B35F7F121C261E003EAD18 /* algorithm.txt */, - 65B35F80121C261E003EAD18 /* ChangeLog */, - 65B35F81121C261E003EAD18 /* compress.c */, - 65B35F82121C261E003EAD18 /* configure */, - 65B35F83121C261E003EAD18 /* crc32.c */, - 65B35F84121C261E003EAD18 /* crc32.h */, - 65B35F85121C261E003EAD18 /* deflate.c */, - 65B35F86121C261E003EAD18 /* deflate.h */, - 65B35F87121C261E003EAD18 /* example.c */, - 65B35F88121C261E003EAD18 /* FAQ */, - 65B35F89121C261E003EAD18 /* gzio.c */, - 65B35F8A121C261E003EAD18 /* INDEX */, - 65B35F8B121C261E003EAD18 /* infback.c */, - 65B35F8C121C261E003EAD18 /* inffast.c */, - 65B35F8D121C261E003EAD18 /* inffast.h */, - 65B35F8E121C261E003EAD18 /* inffixed.h */, - 65B35F8F121C261E003EAD18 /* inflate.c */, - 65B35F90121C261E003EAD18 /* inflate.h */, - 65B35F91121C261E003EAD18 /* inftrees.c */, - 65B35F92121C261E003EAD18 /* inftrees.h */, - 65B35F93121C261E003EAD18 /* make_vms.com */, - 65B35F94121C261E003EAD18 /* Makefile */, - 65B35F95121C261E003EAD18 /* Makefile.in */, - 65B35F96121C261E003EAD18 /* minigzip.c */, - 65B35F97121C261E003EAD18 /* README */, - 65B35F98121C261E003EAD18 /* trees.c */, - 65B35F99121C261E003EAD18 /* trees.h */, - 65B35F9A121C261E003EAD18 /* uncompr.c */, - 65B35F9B121C261E003EAD18 /* zconf.h */, - 65B35F9C121C261E003EAD18 /* zconf.in.h */, - 65B35F9D121C261E003EAD18 /* zlib.3 */, - 65B35F9E121C261E003EAD18 /* zlib.h */, - 65B35F9F121C261E003EAD18 /* zutil.c */, - 65B35FA0121C261E003EAD18 /* zutil.h */, - ); - path = zlib; - sourceTree = ""; - }; - 65B35FA1121C261E003EAD18 /* Build */ = { - isa = PBXGroup; - children = ( - ); - path = Build; - sourceTree = ""; - }; - 65B35FA3121C261E003EAD18 /* geometry */ = { - isa = PBXGroup; - children = ( - 65B35FA4121C261E003EAD18 /* glc_3drep.cpp */, - 65B35FA5121C261E003EAD18 /* glc_3drep.h */, - 65B35FA6121C261E003EAD18 /* glc_arrow.cpp */, - 65B35FA7121C261E003EAD18 /* glc_arrow.h */, - 65B35FA8121C261E003EAD18 /* glc_box.cpp */, - 65B35FA9121C261E003EAD18 /* glc_box.h */, - 65B35FAA121C261E003EAD18 /* glc_bsrep.cpp */, - 65B35FAB121C261E003EAD18 /* glc_bsrep.h */, - 65B35FAC121C261E003EAD18 /* glc_circle.cpp */, - 65B35FAD121C261E003EAD18 /* glc_circle.h */, - 65B35FAE121C261E003EAD18 /* glc_cone.cpp */, - 65B35FAF121C261E003EAD18 /* glc_cone.h */, - 65B35FB0121C261E003EAD18 /* glc_cylinder.cpp */, - 65B35FB1121C261E003EAD18 /* glc_cylinder.h */, - 65B35FB2121C261E003EAD18 /* glc_disc.cpp */, - 65B35FB3121C261E003EAD18 /* glc_disc.h */, - 65B35FB4121C261E003EAD18 /* glc_geometry.cpp */, - 65B35FB5121C261E003EAD18 /* glc_geometry.h */, - 65B35FB6121C261E003EAD18 /* glc_line.cpp */, - 65B35FB7121C261E003EAD18 /* glc_line.h */, - 65B35FB8121C261E003EAD18 /* glc_lod.cpp */, - 65B35FB9121C261E003EAD18 /* glc_lod.h */, - 65B35FBA121C261E003EAD18 /* glc_mesh.cpp */, - 65B35FBB121C261E003EAD18 /* glc_mesh.h */, - 65B35FBC121C261E003EAD18 /* glc_meshdata.cpp */, - 65B35FBD121C261E003EAD18 /* glc_meshdata.h */, - 65B35FBE121C261E003EAD18 /* glc_point.cpp */, - 65B35FBF121C261E003EAD18 /* glc_point.h */, - 65B35FC0121C261E003EAD18 /* glc_pointsprite.cpp */, - 65B35FC1121C261E003EAD18 /* glc_pointsprite.h */, - 65B35FC2121C261E003EAD18 /* glc_polylines.cpp */, - 65B35FC3121C261E003EAD18 /* glc_polylines.h */, - 65B35FC4121C261E003EAD18 /* glc_primitivegroup.cpp */, - 65B35FC5121C261E003EAD18 /* glc_primitivegroup.h */, - 65B35FC6121C261E003EAD18 /* glc_rectangle.cpp */, - 65B35FC7121C261E003EAD18 /* glc_rectangle.h */, - 65B35FC8121C261E003EAD18 /* glc_rep.cpp */, - 65B35FC9121C261E003EAD18 /* glc_rep.h */, - 65B35FCA121C261E003EAD18 /* glc_sphere.cpp */, - 65B35FCB121C261E003EAD18 /* glc_sphere.h */, - 65B35FCC121C261E003EAD18 /* glc_wiredata.cpp */, - 65B35FCD121C261E003EAD18 /* glc_wiredata.h */, - ); - path = geometry; - sourceTree = ""; - }; - 65B35FE7121C261E003EAD18 /* include */ = { - isa = PBXGroup; - children = ( - 65B35FE8121C261E003EAD18 /* GLC_3DRep */, - 65B35FE9121C261E003EAD18 /* GLC_3DViewCollection */, - 65B35FEA121C261E003EAD18 /* GLC_3DViewInstance */, - 65B35FEB121C261E003EAD18 /* GLC_3DWidget */, - 65B35FEC121C261E003EAD18 /* GLC_3DWidgetManager */, - 65B35FED121C261E003EAD18 /* GLC_3DWidgetManagerHandle */, - 65B35FEE121C261E003EAD18 /* GLC_AbstractManipulator */, - 65B35FEF121C261E003EAD18 /* GLC_Arrow */, - 65B35FF0121C261E003EAD18 /* GLC_Attribute */, - 65B35FF1121C261E003EAD18 /* GLC_Axis */, - 65B35FF2121C261E003EAD18 /* GLC_BoundingBox */, - 65B35FF3121C261E003EAD18 /* GLC_Box */, - 65B35FF4121C261E003EAD18 /* GLC_BSRep */, - 65B35FF5121C261E003EAD18 /* GLC_CacheManager */, - 65B35FF6121C261E003EAD18 /* GLC_Camera */, - 65B35FF7121C261E003EAD18 /* GLC_Circle */, - 65B35FF8121C261E003EAD18 /* GLC_Cone */, - 65B35FF9121C261E003EAD18 /* GLC_CuttingPlane */, - 65B35FFA121C261E003EAD18 /* GLC_Cylinder */, - 65B35FFB121C261E003EAD18 /* GLC_Disc */, - 65B35FFC121C261E003EAD18 /* GLC_Exception */, - 65B35FFD121C261E003EAD18 /* GLC_Ext */, - 65B35FFE121C261E003EAD18 /* GLC_Factory */, - 65B35FFF121C261E003EAD18 /* GLC_FileFormatException */, - 65B36000121C261E003EAD18 /* GLC_FlyMover */, - 65B36001121C261E003EAD18 /* GLC_Frustum */, - 65B36002121C261E003EAD18 /* GLC_Geometry */, - 65B36003121C261E003EAD18 /* GLC_GeomTools */, - 65B36004121C261E003EAD18 /* GLC_Global */, - 65B36005121C261E003EAD18 /* GLC_ImagePlane */, - 65B36006121C261E003EAD18 /* GLC_Interpolator */, - 65B36007121C261E003EAD18 /* GLC_Light */, - 65B36008121C261E003EAD18 /* GLC_Line */, - 65B36009121C261E003EAD18 /* GLC_Line3d */, - 65B3600A121C261E003EAD18 /* GLC_Material */, - 65B3600B121C261E003EAD18 /* GLC_Matrix4x4 */, - 65B3600C121C261E003EAD18 /* GLC_Mesh */, - 65B3600D121C261E003EAD18 /* GLC_Mover */, - 65B3600E121C261E003EAD18 /* GLC_MoverController */, - 65B3600F121C261E003EAD18 /* GLC_Object */, - 65B36010121C261E003EAD18 /* GLC_Octree */, - 65B36011121C261E003EAD18 /* GLC_OctreeNode */, - 65B36012121C261E003EAD18 /* GLC_OpenGlException */, - 65B36013121C261E003EAD18 /* GLC_PanMover */, - 65B36014121C261E003EAD18 /* GLC_Plane */, - 65B36015121C261E003EAD18 /* GLC_Point */, - 65B36016121C261E003EAD18 /* GLC_Point2d */, - 65B36017121C261E003EAD18 /* GLC_Point2df */, - 65B36018121C261E003EAD18 /* GLC_Point3d */, - 65B36019121C261E003EAD18 /* GLC_Point3df */, - 65B3601A121C261E003EAD18 /* GLC_Point4d */, - 65B3601B121C261E003EAD18 /* GLC_PointSprite */, - 65B3601C121C261E003EAD18 /* GLC_Polylines */, - 65B3601D121C261E003EAD18 /* GLC_PullManipulator */, - 65B3601E121C261E003EAD18 /* GLC_Rectangle */, - 65B3601F121C261E003EAD18 /* GLC_RenderProperties */, - 65B36020121C261E003EAD18 /* GLC_RenderStatistics */, - 65B36021121C261E003EAD18 /* GLC_Rep */, - 65B36022121C261E003EAD18 /* GLC_RepCrossMover */, - 65B36023121C261E003EAD18 /* GLC_RepFlyMover */, - 65B36024121C261E003EAD18 /* GLC_RepMover */, - 65B36025121C261E003EAD18 /* GLC_RepTrackBallMover */, - 65B36026121C261E003EAD18 /* GLC_RotationManipulator */, - 65B36027121C261E003EAD18 /* GLC_SelectionMaterial */, - 65B36028121C261E003EAD18 /* GLC_Shader */, - 65B36029121C261E003EAD18 /* GLC_SpacePartitioning */, - 65B3602A121C261E003EAD18 /* GLC_Sphere */, - 65B3602B121C261E003EAD18 /* GLC_State */, - 65B3602C121C261E003EAD18 /* GLC_StructInstance */, - 65B3602D121C261E003EAD18 /* GLC_StructOccurence */, - 65B3602E121C261E003EAD18 /* GLC_StructReference */, - 65B3602F121C261E003EAD18 /* GLC_Texture */, - 65B36030121C261E003EAD18 /* GLC_TrackBallMover */, - 65B36031121C261E003EAD18 /* GLC_TurnTableMover */, - 65B36032121C261E003EAD18 /* GLC_Vector2d */, - 65B36033121C261E003EAD18 /* GLC_Vector2df */, - 65B36034121C261E003EAD18 /* GLC_Vector3d */, - 65B36035121C261E003EAD18 /* GLC_Vector3df */, - 65B36036121C261E003EAD18 /* GLC_Vector4d */, - 65B36037121C261E003EAD18 /* GLC_Viewport */, - 65B36038121C261E003EAD18 /* GLC_World */, - 65B36039121C261E003EAD18 /* GLC_WorldTo3dxml */, - 65B3603A121C261E003EAD18 /* GLC_ZoomMover */, - ); - path = include; - sourceTree = ""; - }; - 65B3603B121C261E003EAD18 /* io */ = { - isa = PBXGroup; - children = ( - 65B3603C121C261E003EAD18 /* glc_3dstoworld.cpp */, - 65B3603D121C261E003EAD18 /* glc_3dstoworld.h */, - 65B3603E121C261E003EAD18 /* glc_3dxmltoworld.cpp */, - 65B3603F121C261E003EAD18 /* glc_3dxmltoworld.h */, - 65B36040121C261E003EAD18 /* glc_bsreptoworld.cpp */, - 65B36041121C261E003EAD18 /* glc_bsreptoworld.h */, - 65B36042121C261E003EAD18 /* glc_colladatoworld.cpp */, - 65B36043121C261E003EAD18 /* glc_colladatoworld.h */, - 65B36044121C261E003EAD18 /* glc_objmtlloader.cpp */, - 65B36045121C261E003EAD18 /* glc_objmtlloader.h */, - 65B36046121C261E003EAD18 /* glc_objtoworld.cpp */, - 65B36047121C261E003EAD18 /* glc_objtoworld.h */, - 65B36048121C261E003EAD18 /* glc_offtoworld.cpp */, - 65B36049121C261E003EAD18 /* glc_offtoworld.h */, - 65B3604A121C261E003EAD18 /* glc_stltoworld.cpp */, - 65B3604B121C261E003EAD18 /* glc_stltoworld.h */, - 65B3604C121C261E003EAD18 /* glc_worldto3dxml.cpp */, - 65B3604D121C261E003EAD18 /* glc_worldto3dxml.h */, - ); - path = io; - sourceTree = ""; - }; - 65B3604E121C261E003EAD18 /* maths */ = { - isa = PBXGroup; - children = ( - 65B3604F121C261E003EAD18 /* glc_geomtools.cpp */, - 65B36050121C261E003EAD18 /* glc_geomtools.h */, - 65B36051121C261E003EAD18 /* glc_interpolator.cpp */, - 65B36052121C261E003EAD18 /* glc_interpolator.h */, - 65B36053121C261E003EAD18 /* glc_line3d.cpp */, - 65B36054121C261E003EAD18 /* glc_line3d.h */, - 65B36055121C261E003EAD18 /* glc_matrix4x4.cpp */, - 65B36056121C261E003EAD18 /* glc_matrix4x4.h */, - 65B36057121C261E003EAD18 /* glc_plane.cpp */, - 65B36058121C261E003EAD18 /* glc_plane.h */, - 65B36059121C261E003EAD18 /* glc_utils_maths.h */, - 65B3605A121C261E003EAD18 /* glc_vector2d.h */, - 65B3605B121C261E003EAD18 /* glc_vector2df.h */, - 65B3605C121C261E003EAD18 /* glc_vector3d.h */, - 65B3605D121C261E003EAD18 /* glc_vector3df.h */, - 65B3605E121C261E003EAD18 /* glc_vector4d.cpp */, - 65B3605F121C261E003EAD18 /* glc_vector4d.h */, - ); - path = maths; - sourceTree = ""; - }; - 65B36060121C261E003EAD18 /* sceneGraph */ = { - isa = PBXGroup; - children = ( - 65B36061121C261E003EAD18 /* glc_3dviewcollection.cpp */, - 65B36062121C261E003EAD18 /* glc_3dviewcollection.h */, - 65B36063121C261E003EAD18 /* glc_3dviewinstance.cpp */, - 65B36064121C261E003EAD18 /* glc_3dviewinstance.h */, - 65B36065121C261E003EAD18 /* glc_attributes.cpp */, - 65B36066121C261E003EAD18 /* glc_attributes.h */, - 65B36067121C261E003EAD18 /* glc_octree.cpp */, - 65B36068121C261E003EAD18 /* glc_octree.h */, - 65B36069121C261E003EAD18 /* glc_octreenode.cpp */, - 65B3606A121C261E003EAD18 /* glc_octreenode.h */, - 65B3606B121C261E003EAD18 /* glc_spacepartitioning.cpp */, - 65B3606C121C261E003EAD18 /* glc_spacepartitioning.h */, - 65B3606D121C261E003EAD18 /* glc_structinstance.cpp */, - 65B3606E121C261E003EAD18 /* glc_structinstance.h */, - 65B3606F121C261E003EAD18 /* glc_structoccurence.cpp */, - 65B36070121C261E003EAD18 /* glc_structoccurence.h */, - 65B36071121C261E003EAD18 /* glc_structreference.cpp */, - 65B36072121C261E003EAD18 /* glc_structreference.h */, - 65B36073121C261E003EAD18 /* glc_world.cpp */, - 65B36074121C261E003EAD18 /* glc_world.h */, - 65B36075121C261E003EAD18 /* glc_worldhandle.cpp */, - 65B36076121C261E003EAD18 /* glc_worldhandle.h */, - ); - path = sceneGraph; - sourceTree = ""; - }; - 65B36077121C261E003EAD18 /* shading */ = { - isa = PBXGroup; - children = ( - 65B36078121C261E003EAD18 /* glc_light.cpp */, - 65B36079121C261E003EAD18 /* glc_light.h */, - 65B3607A121C261E003EAD18 /* glc_material.cpp */, - 65B3607B121C261E003EAD18 /* glc_material.h */, - 65B3607C121C261E003EAD18 /* glc_renderproperties.cpp */, - 65B3607D121C261E003EAD18 /* glc_renderproperties.h */, - 65B3607E121C261E003EAD18 /* glc_selectionmaterial.cpp */, - 65B3607F121C261E003EAD18 /* glc_selectionmaterial.h */, - 65B36080121C261E003EAD18 /* glc_shader.cpp */, - 65B36081121C261E003EAD18 /* glc_shader.h */, - 65B36082121C261E003EAD18 /* glc_texture.cpp */, - 65B36083121C261E003EAD18 /* glc_texture.h */, - ); - path = shading; - sourceTree = ""; - }; - 65B36084121C261E003EAD18 /* viewport */ = { - isa = PBXGroup; - children = ( - 65B36085121C261E003EAD18 /* glc_camera.cpp */, - 65B36086121C261E003EAD18 /* glc_camera.h */, - 65B36087121C261E003EAD18 /* glc_flymover.cpp */, - 65B36088121C261E003EAD18 /* glc_flymover.h */, - 65B36089121C261E003EAD18 /* glc_frustum.cpp */, - 65B3608A121C261E003EAD18 /* glc_frustum.h */, - 65B3608B121C261E003EAD18 /* glc_imageplane.cpp */, - 65B3608C121C261E003EAD18 /* glc_imageplane.h */, - 65B3608D121C261E003EAD18 /* glc_mover.cpp */, - 65B3608E121C261E003EAD18 /* glc_mover.h */, - 65B3608F121C261E003EAD18 /* glc_movercontroller.cpp */, - 65B36090121C261E003EAD18 /* glc_movercontroller.h */, - 65B36091121C261E003EAD18 /* glc_panmover.cpp */, - 65B36092121C261E003EAD18 /* glc_panmover.h */, - 65B36093121C261E003EAD18 /* glc_repcrossmover.cpp */, - 65B36094121C261E003EAD18 /* glc_repcrossmover.h */, - 65B36095121C261E003EAD18 /* glc_repflymover.cpp */, - 65B36096121C261E003EAD18 /* glc_repflymover.h */, - 65B36097121C261E003EAD18 /* glc_repmover.cpp */, - 65B36098121C261E003EAD18 /* glc_repmover.h */, - 65B36099121C261E003EAD18 /* glc_reptrackballmover.cpp */, - 65B3609A121C261E003EAD18 /* glc_reptrackballmover.h */, - 65B3609B121C261E003EAD18 /* glc_settargetmover.cpp */, - 65B3609C121C261E003EAD18 /* glc_settargetmover.h */, - 65B3609D121C261E003EAD18 /* glc_trackballmover.cpp */, - 65B3609E121C261E003EAD18 /* glc_trackballmover.h */, - 65B3609F121C261E003EAD18 /* glc_turntablemover.cpp */, - 65B360A0121C261E003EAD18 /* glc_turntablemover.h */, - 65B360A1121C261E003EAD18 /* glc_viewport.cpp */, - 65B360A2121C261E003EAD18 /* glc_viewport.h */, - 65B360A3121C261E003EAD18 /* glc_zoommover.cpp */, - 65B360A4121C261E003EAD18 /* glc_zoommover.h */, - ); - path = viewport; - sourceTree = ""; - }; - 65B360A5121C261E003EAD18 /* libqxt */ = { - isa = PBXGroup; - children = ( - 65B360A6121C261E003EAD18 /* AUTHORS */, - 65B360A7121C261E003EAD18 /* cpl1.0.txt */, - 65B360A8121C261E003EAD18 /* lgpl-2.1.txt */, - 65B360A9121C261E003EAD18 /* libqxt.pri */, - 65B360AA121C261E003EAD18 /* libqxt.pro */, - 65B360AB121C261E003EAD18 /* LICENSE */, - 65B360AC121C261E003EAD18 /* README */, - 65B360AD121C261E003EAD18 /* src */, - 65B36327121C261F003EAD18 /* translations */, - ); - path = libqxt; - sourceTree = ""; - }; - 65B360AD121C261E003EAD18 /* src */ = { - isa = PBXGroup; - children = ( - 65B360AE121C261E003EAD18 /* berkeley */, - 65B360B8121C261E003EAD18 /* core */, - 65B36127121C261F003EAD18 /* designer */, - 65B36152121C261F003EAD18 /* gui */, - 65B362CE121C261F003EAD18 /* network */, - 65B362EA121C261F003EAD18 /* qxtbase.pri */, - 65B362EB121C261F003EAD18 /* qxtlibs.pri */, - 65B362EC121C261F003EAD18 /* sql */, - 65B362F5121C261F003EAD18 /* web */, - 65B36313121C261F003EAD18 /* zeroconf */, - ); - path = src; - sourceTree = ""; - }; - 65B360AE121C261E003EAD18 /* berkeley */ = { - isa = PBXGroup; - children = ( - 65B360AF121C261E003EAD18 /* berkeley.pri */, - 65B360B0121C261E003EAD18 /* berkeley.pro */, - 65B360B1121C261E003EAD18 /* qxtbdb.cpp */, - 65B360B2121C261E003EAD18 /* qxtbdb.h */, - 65B360B3121C261E003EAD18 /* qxtbdbhash.cpp */, - 65B360B4121C261E003EAD18 /* qxtbdbhash.h */, - 65B360B5121C261E003EAD18 /* qxtbdbtree.cpp */, - 65B360B6121C261E003EAD18 /* qxtbdbtree.h */, - 65B360B7121C261E003EAD18 /* qxtberkeley.h */, - ); - path = berkeley; - sourceTree = ""; - }; - 65B360B8121C261E003EAD18 /* core */ = { - isa = PBXGroup; - children = ( - 65B360B9121C261E003EAD18 /* core.pri */, - 65B360BA121C261E003EAD18 /* core.pro */, - 65B360BB121C261E003EAD18 /* logengines */, - 65B360C7121C261E003EAD18 /* qxtabstractconnectionmanager.cpp */, - 65B360C8121C261E003EAD18 /* qxtabstractconnectionmanager.h */, - 65B360C9121C261E003EAD18 /* qxtabstractsignalserializer.h */, - 65B360CA121C261E003EAD18 /* qxtalgorithms.h */, - 65B360CB121C261E003EAD18 /* qxtboundcfunction.h */, - 65B360CC121C261E003EAD18 /* qxtboundfunction.h */, - 65B360CD121C261E003EAD18 /* qxtboundfunctionbase.h */, - 65B360CE121C261E003EAD18 /* qxtcommandoptions.cpp */, - 65B360CF121C261E003EAD18 /* qxtcommandoptions.h */, - 65B360D0121C261E003EAD18 /* qxtcore.h */, - 65B360D1121C261E003EAD18 /* qxtcsvmodel.cpp */, - 65B360D2121C261E003EAD18 /* qxtcsvmodel.h */, - 65B360D3121C261E003EAD18 /* qxtdaemon.cpp */, - 65B360D4121C261E003EAD18 /* qxtdaemon.h */, - 65B360D5121C261E003EAD18 /* qxtdatastreamsignalserializer.cpp */, - 65B360D6121C261E003EAD18 /* qxtdatastreamsignalserializer.h */, - 65B360D7121C261E003EAD18 /* qxtdeplex.cpp */, - 65B360D8121C261E003EAD18 /* qxtdeplex.h */, - 65B360D9121C261E003EAD18 /* qxtdeplex_p.h */, - 65B360DA121C261E003EAD18 /* qxterror.cpp */, - 65B360DB121C261E003EAD18 /* qxterror.h */, - 65B360DC121C261E003EAD18 /* qxtfifo.cpp */, - 65B360DD121C261E003EAD18 /* qxtfifo.h */, - 65B360DE121C261E003EAD18 /* qxtfilelock.cpp */, - 65B360DF121C261E003EAD18 /* qxtfilelock.h */, - 65B360E0121C261E003EAD18 /* qxtfilelock_p.h */, - 65B360E1121C261E003EAD18 /* qxtfilelock_unix.cpp */, - 65B360E2121C261E003EAD18 /* qxtfilelock_win.cpp */, - 65B360E3121C261E003EAD18 /* qxtglobal.cpp */, - 65B360E4121C261E003EAD18 /* qxtglobal.h */, - 65B360E5121C261E003EAD18 /* qxthmac.cpp */, - 65B360E6121C261E003EAD18 /* qxthmac.h */, - 65B360E7121C261E003EAD18 /* qxtjob.cpp */, - 65B360E8121C261E003EAD18 /* qxtjob.h */, - 65B360E9121C261E003EAD18 /* qxtjob_p.h */, - 65B360EA121C261E003EAD18 /* qxtjson.cpp */, - 65B360EB121C261E003EAD18 /* qxtjson.h */, - 65B360EC121C261E003EAD18 /* qxtlinesocket.cpp */, - 65B360ED121C261E003EAD18 /* qxtlinesocket.h */, - 65B360EE121C261E003EAD18 /* qxtlinesocket_p.h */, - 65B360EF121C261E003EAD18 /* qxtlinkedtree.cpp */, - 65B360F0121C261E003EAD18 /* qxtlinkedtree.h */, - 65B360F1121C261E003EAD18 /* qxtlocale.cpp */, - 65B360F2121C261E003EAD18 /* qxtlocale.h */, - 65B360F3121C261E003EAD18 /* qxtlocale_data_p.h */, - 65B360F4121C261E003EAD18 /* qxtlogger.cpp */, - 65B360F5121C261E003EAD18 /* qxtlogger.h */, - 65B360F6121C261E003EAD18 /* qxtlogger_p.h */, - 65B360F7121C261E003EAD18 /* qxtloggerengine.cpp */, - 65B360F8121C261E003EAD18 /* qxtloggerengine.h */, - 65B360F9121C261E003EAD18 /* qxtlogstream.cpp */, - 65B360FA121C261E003EAD18 /* qxtlogstream.h */, - 65B360FB121C261E003EAD18 /* qxtlogstream_p.h */, - 65B360FC121C261E003EAD18 /* qxtmetaobject.cpp */, - 65B360FD121C261E003EAD18 /* qxtmetaobject.h */, - 65B360FE121C261E003EAD18 /* qxtmetatype.h */, - 65B360FF121C261E003EAD18 /* qxtmodelserializer.cpp */, - 65B36100121C261E003EAD18 /* qxtmodelserializer.h */, - 65B36101121C261E003EAD18 /* qxtmultisignalwaiter.cpp */, - 65B36102121C261E003EAD18 /* qxtmultisignalwaiter.h */, - 65B36103121C261E003EAD18 /* qxtnamespace.h */, - 65B36104121C261F003EAD18 /* qxtnull.cpp */, - 65B36105121C261F003EAD18 /* qxtnull.h */, - 65B36106121C261F003EAD18 /* qxtnullable.h */, - 65B36107121C261F003EAD18 /* qxtpairlist.h */, - 65B36108121C261F003EAD18 /* qxtpimpl.h */, - 65B36109121C261F003EAD18 /* qxtpipe.cpp */, - 65B3610A121C261F003EAD18 /* qxtpipe.h */, - 65B3610B121C261F003EAD18 /* qxtpipe_p.h */, - 65B3610C121C261F003EAD18 /* qxtpointerlist.cpp */, - 65B3610D121C261F003EAD18 /* qxtpointerlist.h */, - 65B3610E121C261F003EAD18 /* qxtrpcservice.cpp */, - 65B3610F121C261F003EAD18 /* qxtrpcservice.h */, - 65B36110121C261F003EAD18 /* qxtrpcservice_p.h */, - 65B36111121C261F003EAD18 /* qxtserialdevice.cpp */, - 65B36112121C261F003EAD18 /* qxtserialdevice.h */, - 65B36113121C261F003EAD18 /* qxtserialdevice_p.h */, - 65B36114121C261F003EAD18 /* qxtserialdevice_unix.cpp */, - 65B36115121C261F003EAD18 /* qxtsharedprivate.h */, - 65B36116121C261F003EAD18 /* qxtsignalgroup.cpp */, - 65B36117121C261F003EAD18 /* qxtsignalgroup.h */, - 65B36118121C261F003EAD18 /* qxtsignalwaiter.cpp */, - 65B36119121C261F003EAD18 /* qxtsignalwaiter.h */, - 65B3611A121C261F003EAD18 /* qxtslotjob.cpp */, - 65B3611B121C261F003EAD18 /* qxtslotjob.h */, - 65B3611C121C261F003EAD18 /* qxtslotjob_p.h */, - 65B3611D121C261F003EAD18 /* qxtslotmapper.cpp */, - 65B3611E121C261F003EAD18 /* qxtslotmapper.h */, - 65B3611F121C261F003EAD18 /* qxtstdio.cpp */, - 65B36120121C261F003EAD18 /* qxtstdio.h */, - 65B36121121C261F003EAD18 /* qxtstdio_p.h */, - 65B36122121C261F003EAD18 /* qxtstdstreambufdevice.cpp */, - 65B36123121C261F003EAD18 /* qxtstdstreambufdevice.h */, - 65B36124121C261F003EAD18 /* qxttimer.cpp */, - 65B36125121C261F003EAD18 /* qxttimer.h */, - 65B36126121C261F003EAD18 /* qxttypelist.h */, - ); - path = core; - sourceTree = ""; - }; - 65B360BB121C261E003EAD18 /* logengines */ = { - isa = PBXGroup; - children = ( - 65B360BC121C261E003EAD18 /* logengines.pri */, - 65B360BD121C261E003EAD18 /* qxtabstractfileloggerengine.cpp */, - 65B360BE121C261E003EAD18 /* qxtabstractfileloggerengine.h */, - 65B360BF121C261E003EAD18 /* qxtabstractiologgerengine.cpp */, - 65B360C0121C261E003EAD18 /* qxtabstractiologgerengine.h */, - 65B360C1121C261E003EAD18 /* qxtbasicfileloggerengine.cpp */, - 65B360C2121C261E003EAD18 /* qxtbasicfileloggerengine.h */, - 65B360C3121C261E003EAD18 /* qxtbasicstdloggerengine.cpp */, - 65B360C4121C261E003EAD18 /* qxtbasicstdloggerengine.h */, - 65B360C5121C261E003EAD18 /* qxtxmlfileloggerengine.cpp */, - 65B360C6121C261E003EAD18 /* qxtxmlfileloggerengine.h */, - ); - path = logengines; - sourceTree = ""; - }; - 65B36127121C261F003EAD18 /* designer */ = { - isa = PBXGroup; - children = ( - 65B36128121C261F003EAD18 /* designer.pri */, - 65B36129121C261F003EAD18 /* designer.pro */, - 65B3612A121C261F003EAD18 /* Makefile */, - 65B3612B121C261F003EAD18 /* qxtbasespinboxplugin.cpp */, - 65B3612C121C261F003EAD18 /* qxtbasespinboxplugin.h */, - 65B3612D121C261F003EAD18 /* qxtcheckcomboboxplugin.cpp */, - 65B3612E121C261F003EAD18 /* qxtcheckcomboboxplugin.h */, - 65B3612F121C261F003EAD18 /* qxtcountrycomboboxplugin.cpp */, - 65B36130121C261F003EAD18 /* qxtcountrycomboboxplugin.h */, - 65B36131121C261F003EAD18 /* qxtdesignerplugin.cpp */, - 65B36132121C261F003EAD18 /* qxtdesignerplugin.h */, - 65B36133121C261F003EAD18 /* qxtdesignerplugins.cpp */, - 65B36134121C261F003EAD18 /* qxtdesignerplugins.h */, - 65B36135121C261F003EAD18 /* qxtflowviewplugin.cpp */, - 65B36136121C261F003EAD18 /* qxtflowviewplugin.h */, - 65B36137121C261F003EAD18 /* qxtgroupboxplugin.cpp */, - 65B36138121C261F003EAD18 /* qxtgroupboxplugin.h */, - 65B36139121C261F003EAD18 /* qxtlabelplugin.cpp */, - 65B3613A121C261F003EAD18 /* qxtlabelplugin.h */, - 65B3613B121C261F003EAD18 /* qxtlanguagecomboboxplugin.cpp */, - 65B3613C121C261F003EAD18 /* qxtlanguagecomboboxplugin.h */, - 65B3613D121C261F003EAD18 /* qxtletterboxwidgetplugin.cpp */, - 65B3613E121C261F003EAD18 /* qxtletterboxwidgetplugin.h */, - 65B3613F121C261F003EAD18 /* qxtlineeditplugin.cpp */, - 65B36140121C261F003EAD18 /* qxtlineeditplugin.h */, - 65B36141121C261F003EAD18 /* qxtlistwidgetplugin.cpp */, - 65B36142121C261F003EAD18 /* qxtlistwidgetplugin.h */, - 65B36143121C261F003EAD18 /* qxtprogresslabelplugin.cpp */, - 65B36144121C261F003EAD18 /* qxtprogresslabelplugin.h */, - 65B36145121C261F003EAD18 /* qxtpushbuttonplugin.cpp */, - 65B36146121C261F003EAD18 /* qxtpushbuttonplugin.h */, - 65B36147121C261F003EAD18 /* qxtspansliderplugin.cpp */, - 65B36148121C261F003EAD18 /* qxtspansliderplugin.h */, - 65B36149121C261F003EAD18 /* qxtstarsplugin.cpp */, - 65B3614A121C261F003EAD18 /* qxtstarsplugin.h */, - 65B3614B121C261F003EAD18 /* qxtstringspinboxplugin.cpp */, - 65B3614C121C261F003EAD18 /* qxtstringspinboxplugin.h */, - 65B3614D121C261F003EAD18 /* qxttablewidgetplugin.cpp */, - 65B3614E121C261F003EAD18 /* qxttablewidgetplugin.h */, - 65B3614F121C261F003EAD18 /* qxttreewidgetplugin.cpp */, - 65B36150121C261F003EAD18 /* qxttreewidgetplugin.h */, - 65B36151121C261F003EAD18 /* resources.qrc */, - ); - path = designer; - sourceTree = ""; - }; - 65B36152121C261F003EAD18 /* gui */ = { - isa = PBXGroup; - children = ( - 65B36153121C261F003EAD18 /* gui.pri */, - 65B36154121C261F003EAD18 /* gui.pro */, - 65B36155121C261F003EAD18 /* Makefile */, - 65B36156121C261F003EAD18 /* qxtapplication.cpp */, - 65B36157121C261F003EAD18 /* qxtapplication.h */, - 65B36158121C261F003EAD18 /* qxtapplication_mac.cpp */, - 65B36159121C261F003EAD18 /* qxtapplication_p.h */, - 65B3615A121C261F003EAD18 /* qxtapplication_win.cpp */, - 65B3615B121C261F003EAD18 /* qxtapplication_x11.cpp */, - 65B3615C121C261F003EAD18 /* qxtbasespinbox.cpp */, - 65B3615D121C261F003EAD18 /* qxtbasespinbox.h */, - 65B3615E121C261F003EAD18 /* qxtcheckcombobox.cpp */, - 65B3615F121C261F003EAD18 /* qxtcheckcombobox.h */, - 65B36160121C261F003EAD18 /* qxtcheckcombobox_p.h */, - 65B36161121C261F003EAD18 /* qxtconfigdialog.cpp */, - 65B36162121C261F003EAD18 /* qxtconfigdialog.h */, - 65B36163121C261F003EAD18 /* qxtconfigdialog_p.h */, - 65B36164121C261F003EAD18 /* qxtconfigwidget.cpp */, - 65B36165121C261F003EAD18 /* qxtconfigwidget.h */, - 65B36166121C261F003EAD18 /* qxtconfigwidget_p.h */, - 65B36167121C261F003EAD18 /* qxtconfirmationmessage.cpp */, - 65B36168121C261F003EAD18 /* qxtconfirmationmessage.h */, - 65B36169121C261F003EAD18 /* qxtcountrycombobox.cpp */, - 65B3616A121C261F003EAD18 /* qxtcountrycombobox.h */, - 65B3616B121C261F003EAD18 /* qxtcountrycombobox_p.h */, - 65B3616C121C261F003EAD18 /* qxtcountrymodel.cpp */, - 65B3616D121C261F003EAD18 /* qxtcountrymodel.h */, - 65B3616E121C261F003EAD18 /* qxtcountrymodel_p.h */, - 65B3616F121C261F003EAD18 /* qxtcrumbview.cpp */, - 65B36170121C261F003EAD18 /* qxtcrumbview.h */, - 65B36171121C261F003EAD18 /* qxtcrumbview_p.h */, - 65B36172121C261F003EAD18 /* qxtfilterdialog.cpp */, - 65B36173121C261F003EAD18 /* qxtfilterdialog.h */, - 65B36174121C261F003EAD18 /* qxtfilterdialog_p.h */, - 65B36175121C261F003EAD18 /* qxtflowview.cpp */, - 65B36176121C261F003EAD18 /* qxtflowview.h */, - 65B36177121C261F003EAD18 /* qxtflowview_p.cpp */, - 65B36178121C261F003EAD18 /* qxtflowview_p.h */, - 65B36179121C261F003EAD18 /* qxtglobalshortcut.cpp */, - 65B3617A121C261F003EAD18 /* qxtglobalshortcut.h */, - 65B3617B121C261F003EAD18 /* qxtglobalshortcut_mac.cpp */, - 65B3617C121C261F003EAD18 /* qxtglobalshortcut_p.h */, - 65B3617D121C261F003EAD18 /* qxtglobalshortcut_win.cpp */, - 65B3617E121C261F003EAD18 /* qxtglobalshortcut_x11.cpp */, - 65B3617F121C261F003EAD18 /* qxtgroupbox.cpp */, - 65B36180121C261F003EAD18 /* qxtgroupbox.h */, - 65B36181121C261F003EAD18 /* qxtgui.h */, - 65B36182121C261F003EAD18 /* qxtheaderview.cpp */, - 65B36183121C261F003EAD18 /* qxtheaderview.h */, - 65B36184121C261F003EAD18 /* qxtitemdelegate.cpp */, - 65B36185121C261F003EAD18 /* qxtitemdelegate.h */, - 65B36186121C261F003EAD18 /* qxtitemdelegate_p.h */, - 65B36187121C261F003EAD18 /* qxtitemeditorcreator.h */, - 65B36188121C261F003EAD18 /* qxtitemeditorcreatorbase.h */, - 65B36189121C261F003EAD18 /* qxtlabel.cpp */, - 65B3618A121C261F003EAD18 /* qxtlabel.h */, - 65B3618B121C261F003EAD18 /* qxtlanguagecombobox.cpp */, - 65B3618C121C261F003EAD18 /* qxtlanguagecombobox.h */, - 65B3618D121C261F003EAD18 /* qxtlanguagecombobox_p.h */, - 65B3618E121C261F003EAD18 /* qxtletterboxwidget.cpp */, - 65B3618F121C261F003EAD18 /* qxtletterboxwidget.h */, - 65B36190121C261F003EAD18 /* qxtletterboxwidget_p.h */, - 65B36191121C261F003EAD18 /* qxtlineedit.cpp */, - 65B36192121C261F003EAD18 /* qxtlineedit.h */, - 65B36193121C261F003EAD18 /* qxtlistwidget.cpp */, - 65B36194121C261F003EAD18 /* qxtlistwidget.h */, - 65B36195121C261F003EAD18 /* qxtlistwidget_p.h */, - 65B36196121C261F003EAD18 /* qxtlistwidgetitem.cpp */, - 65B36197121C261F003EAD18 /* qxtlistwidgetitem.h */, - 65B36198121C261F003EAD18 /* qxtlookuplineedit.cpp */, - 65B36199121C261F003EAD18 /* qxtlookuplineedit.h */, - 65B3619A121C261F003EAD18 /* qxtlookuplineedit_p.h */, - 65B3619B121C261F003EAD18 /* qxtnativeeventfilter.h */, - 65B3619C121C261F003EAD18 /* qxtprogresslabel.cpp */, - 65B3619D121C261F003EAD18 /* qxtprogresslabel.h */, - 65B3619E121C261F003EAD18 /* qxtproxystyle.cpp */, - 65B3619F121C261F003EAD18 /* qxtproxystyle.h */, - 65B361A0121C261F003EAD18 /* qxtpushbutton.cpp */, - 65B361A1121C261F003EAD18 /* qxtpushbutton.h */, - 65B361A2121C261F003EAD18 /* qxtscheduleheaderwidget.cpp */, - 65B361A3121C261F003EAD18 /* qxtscheduleheaderwidget.h */, - 65B361A4121C261F003EAD18 /* qxtscheduleitemdelegate.cpp */, - 65B361A5121C261F003EAD18 /* qxtscheduleitemdelegate.h */, - 65B361A6121C261F003EAD18 /* qxtscheduleview.cpp */, - 65B361A7121C261F003EAD18 /* qxtscheduleview.h */, - 65B361A8121C261F003EAD18 /* qxtscheduleview_p.cpp */, - 65B361A9121C261F003EAD18 /* qxtscheduleview_p.h */, - 65B361AA121C261F003EAD18 /* qxtscheduleviewheadermodel_p.cpp */, - 65B361AB121C261F003EAD18 /* qxtscheduleviewheadermodel_p.h */, - 65B361AC121C261F003EAD18 /* qxtscreen.cpp */, - 65B361AD121C261F003EAD18 /* qxtscreen.h */, - 65B361AE121C261F003EAD18 /* qxtscreen_p.h */, - 65B361AF121C261F003EAD18 /* qxtscreen_win.cpp */, - 65B361B0121C261F003EAD18 /* qxtscreen_x11.cpp */, - 65B361B1121C261F003EAD18 /* qxtsortfilterproxymodel.cpp */, - 65B361B2121C261F003EAD18 /* qxtsortfilterproxymodel.h */, - 65B361B3121C261F003EAD18 /* qxtspanslider.cpp */, - 65B361B4121C261F003EAD18 /* qxtspanslider.h */, - 65B361B5121C261F003EAD18 /* qxtspanslider_p.h */, - 65B361B6121C261F003EAD18 /* qxtstandarditemeditorcreator.h */, - 65B361B7121C261F003EAD18 /* qxtstars.cpp */, - 65B361B8121C261F003EAD18 /* qxtstars.h */, - 65B361B9121C261F003EAD18 /* qxtstringspinbox.cpp */, - 65B361BA121C261F003EAD18 /* qxtstringspinbox.h */, - 65B361BB121C261F003EAD18 /* qxtstringvalidator.cpp */, - 65B361BC121C261F003EAD18 /* qxtstringvalidator.h */, - 65B361BD121C261F003EAD18 /* qxtstringvalidator_p.h */, - 65B361BE121C261F003EAD18 /* qxtstyleoptionscheduleviewitem.cpp */, - 65B361BF121C261F003EAD18 /* qxtstyleoptionscheduleviewitem.h */, - 65B361C0121C261F003EAD18 /* qxttablewidget.cpp */, - 65B361C1121C261F003EAD18 /* qxttablewidget.h */, - 65B361C2121C261F003EAD18 /* qxttablewidget_p.h */, - 65B361C3121C261F003EAD18 /* qxttablewidgetitem.cpp */, - 65B361C4121C261F003EAD18 /* qxttablewidgetitem.h */, - 65B361C5121C261F003EAD18 /* qxttabwidget.cpp */, - 65B361C6121C261F003EAD18 /* qxttabwidget.h */, - 65B361C7121C261F003EAD18 /* qxttabwidget_p.h */, - 65B361C8121C261F003EAD18 /* qxttooltip.cpp */, - 65B361C9121C261F003EAD18 /* qxttooltip.h */, - 65B361CA121C261F003EAD18 /* qxttooltip_p.h */, - 65B361CB121C261F003EAD18 /* qxttreewidget.cpp */, - 65B361CC121C261F003EAD18 /* qxttreewidget.h */, - 65B361CD121C261F003EAD18 /* qxttreewidget_p.h */, - 65B361CE121C261F003EAD18 /* qxttreewidgetitem.cpp */, - 65B361CF121C261F003EAD18 /* qxttreewidgetitem.h */, - 65B361D0121C261F003EAD18 /* qxtwindowsystem.cpp */, - 65B361D1121C261F003EAD18 /* qxtwindowsystem.h */, - 65B361D2121C261F003EAD18 /* qxtwindowsystem_win.cpp */, - 65B361D3121C261F003EAD18 /* qxtwindowsystem_x11.cpp */, - 65B361D4121C261F003EAD18 /* resources */, - 65B362CD121C261F003EAD18 /* resources.qrc */, - ); - path = gui; - sourceTree = ""; - }; - 65B361D4121C261F003EAD18 /* resources */ = { - isa = PBXGroup; - children = ( - 65B361D5121C261F003EAD18 /* flags */, - ); - path = resources; - sourceTree = ""; - }; - 65B361D5121C261F003EAD18 /* flags */ = { - isa = PBXGroup; - children = ( - 65B361D6121C261F003EAD18 /* AD.png */, - 65B361D7121C261F003EAD18 /* AE.png */, - 65B361D8121C261F003EAD18 /* AF.png */, - 65B361D9121C261F003EAD18 /* AG.png */, - 65B361DA121C261F003EAD18 /* AI.png */, - 65B361DB121C261F003EAD18 /* AL.png */, - 65B361DC121C261F003EAD18 /* AM.png */, - 65B361DD121C261F003EAD18 /* AN.png */, - 65B361DE121C261F003EAD18 /* AO.png */, - 65B361DF121C261F003EAD18 /* AQ.png */, - 65B361E0121C261F003EAD18 /* AR.png */, - 65B361E1121C261F003EAD18 /* AS.png */, - 65B361E2121C261F003EAD18 /* AT.png */, - 65B361E3121C261F003EAD18 /* AU.png */, - 65B361E4121C261F003EAD18 /* AW.png */, - 65B361E5121C261F003EAD18 /* AX.png */, - 65B361E6121C261F003EAD18 /* AZ.png */, - 65B361E7121C261F003EAD18 /* BA.png */, - 65B361E8121C261F003EAD18 /* BB.png */, - 65B361E9121C261F003EAD18 /* BD.png */, - 65B361EA121C261F003EAD18 /* BE.png */, - 65B361EB121C261F003EAD18 /* BF.png */, - 65B361EC121C261F003EAD18 /* BG.png */, - 65B361ED121C261F003EAD18 /* BH.png */, - 65B361EE121C261F003EAD18 /* BI.png */, - 65B361EF121C261F003EAD18 /* BJ.png */, - 65B361F0121C261F003EAD18 /* BM.png */, - 65B361F1121C261F003EAD18 /* BN.png */, - 65B361F2121C261F003EAD18 /* BO.png */, - 65B361F3121C261F003EAD18 /* BR.png */, - 65B361F4121C261F003EAD18 /* BS.png */, - 65B361F5121C261F003EAD18 /* BT.png */, - 65B361F6121C261F003EAD18 /* BV.png */, - 65B361F7121C261F003EAD18 /* BW.png */, - 65B361F8121C261F003EAD18 /* BY.png */, - 65B361F9121C261F003EAD18 /* BZ.png */, - 65B361FA121C261F003EAD18 /* C.png */, - 65B361FB121C261F003EAD18 /* CA.png */, - 65B361FC121C261F003EAD18 /* CC.png */, - 65B361FD121C261F003EAD18 /* CD.png */, - 65B361FE121C261F003EAD18 /* CF.png */, - 65B361FF121C261F003EAD18 /* CG.png */, - 65B36200121C261F003EAD18 /* CH.png */, - 65B36201121C261F003EAD18 /* CI.png */, - 65B36202121C261F003EAD18 /* CK.png */, - 65B36203121C261F003EAD18 /* CL.png */, - 65B36204121C261F003EAD18 /* CM.png */, - 65B36205121C261F003EAD18 /* CN.png */, - 65B36206121C261F003EAD18 /* CO.png */, - 65B36207121C261F003EAD18 /* CR.png */, - 65B36208121C261F003EAD18 /* CS.png */, - 65B36209121C261F003EAD18 /* CU.png */, - 65B3620A121C261F003EAD18 /* CV.png */, - 65B3620B121C261F003EAD18 /* CX.png */, - 65B3620C121C261F003EAD18 /* CY.png */, - 65B3620D121C261F003EAD18 /* CZ.png */, - 65B3620E121C261F003EAD18 /* DE.png */, - 65B3620F121C261F003EAD18 /* DJ.png */, - 65B36210121C261F003EAD18 /* DK.png */, - 65B36211121C261F003EAD18 /* DM.png */, - 65B36212121C261F003EAD18 /* DO.png */, - 65B36213121C261F003EAD18 /* DZ.png */, - 65B36214121C261F003EAD18 /* EC.png */, - 65B36215121C261F003EAD18 /* EE.png */, - 65B36216121C261F003EAD18 /* EG.png */, - 65B36217121C261F003EAD18 /* EH.png */, - 65B36218121C261F003EAD18 /* ER.png */, - 65B36219121C261F003EAD18 /* ES.png */, - 65B3621A121C261F003EAD18 /* ET.png */, - 65B3621B121C261F003EAD18 /* FI.png */, - 65B3621C121C261F003EAD18 /* FJ.png */, - 65B3621D121C261F003EAD18 /* FK.png */, - 65B3621E121C261F003EAD18 /* FM.png */, - 65B3621F121C261F003EAD18 /* FO.png */, - 65B36220121C261F003EAD18 /* FR.png */, - 65B36221121C261F003EAD18 /* FX.png */, - 65B36222121C261F003EAD18 /* GA.png */, - 65B36223121C261F003EAD18 /* GB.png */, - 65B36224121C261F003EAD18 /* GD.png */, - 65B36225121C261F003EAD18 /* GE.png */, - 65B36226121C261F003EAD18 /* GF.png */, - 65B36227121C261F003EAD18 /* GG.png */, - 65B36228121C261F003EAD18 /* GH.png */, - 65B36229121C261F003EAD18 /* GI.png */, - 65B3622A121C261F003EAD18 /* GL.png */, - 65B3622B121C261F003EAD18 /* GM.png */, - 65B3622C121C261F003EAD18 /* GN.png */, - 65B3622D121C261F003EAD18 /* GP.png */, - 65B3622E121C261F003EAD18 /* GQ.png */, - 65B3622F121C261F003EAD18 /* GR.png */, - 65B36230121C261F003EAD18 /* GS.png */, - 65B36231121C261F003EAD18 /* GT.png */, - 65B36232121C261F003EAD18 /* GU.png */, - 65B36233121C261F003EAD18 /* GW.png */, - 65B36234121C261F003EAD18 /* GY.png */, - 65B36235121C261F003EAD18 /* HK.png */, - 65B36236121C261F003EAD18 /* HM.png */, - 65B36237121C261F003EAD18 /* HN.png */, - 65B36238121C261F003EAD18 /* HR.png */, - 65B36239121C261F003EAD18 /* HT.png */, - 65B3623A121C261F003EAD18 /* HU.png */, - 65B3623B121C261F003EAD18 /* ID.png */, - 65B3623C121C261F003EAD18 /* IE.png */, - 65B3623D121C261F003EAD18 /* IL.png */, - 65B3623E121C261F003EAD18 /* IM.png */, - 65B3623F121C261F003EAD18 /* IN.png */, - 65B36240121C261F003EAD18 /* IO.png */, - 65B36241121C261F003EAD18 /* IQ.png */, - 65B36242121C261F003EAD18 /* IR.png */, - 65B36243121C261F003EAD18 /* IS.png */, - 65B36244121C261F003EAD18 /* IT.png */, - 65B36245121C261F003EAD18 /* JE.png */, - 65B36246121C261F003EAD18 /* JM.png */, - 65B36247121C261F003EAD18 /* JO.png */, - 65B36248121C261F003EAD18 /* JP.png */, - 65B36249121C261F003EAD18 /* KE.png */, - 65B3624A121C261F003EAD18 /* KG.png */, - 65B3624B121C261F003EAD18 /* KH.png */, - 65B3624C121C261F003EAD18 /* KI.png */, - 65B3624D121C261F003EAD18 /* KM.png */, - 65B3624E121C261F003EAD18 /* KN.png */, - 65B3624F121C261F003EAD18 /* KP.png */, - 65B36250121C261F003EAD18 /* KR.png */, - 65B36251121C261F003EAD18 /* KW.png */, - 65B36252121C261F003EAD18 /* KY.png */, - 65B36253121C261F003EAD18 /* KZ.png */, - 65B36254121C261F003EAD18 /* LA.png */, - 65B36255121C261F003EAD18 /* LB.png */, - 65B36256121C261F003EAD18 /* LC.png */, - 65B36257121C261F003EAD18 /* LI.png */, - 65B36258121C261F003EAD18 /* LK.png */, - 65B36259121C261F003EAD18 /* LR.png */, - 65B3625A121C261F003EAD18 /* LS.png */, - 65B3625B121C261F003EAD18 /* LT.png */, - 65B3625C121C261F003EAD18 /* LU.png */, - 65B3625D121C261F003EAD18 /* LV.png */, - 65B3625E121C261F003EAD18 /* LY.png */, - 65B3625F121C261F003EAD18 /* MA.png */, - 65B36260121C261F003EAD18 /* MC.png */, - 65B36261121C261F003EAD18 /* MD.png */, - 65B36262121C261F003EAD18 /* ME.png */, - 65B36263121C261F003EAD18 /* MG.png */, - 65B36264121C261F003EAD18 /* MH.png */, - 65B36265121C261F003EAD18 /* MK.png */, - 65B36266121C261F003EAD18 /* ML.png */, - 65B36267121C261F003EAD18 /* MM.png */, - 65B36268121C261F003EAD18 /* MN.png */, - 65B36269121C261F003EAD18 /* MO.png */, - 65B3626A121C261F003EAD18 /* MP.png */, - 65B3626B121C261F003EAD18 /* MQ.png */, - 65B3626C121C261F003EAD18 /* MR.png */, - 65B3626D121C261F003EAD18 /* MS.png */, - 65B3626E121C261F003EAD18 /* MT.png */, - 65B3626F121C261F003EAD18 /* MU.png */, - 65B36270121C261F003EAD18 /* MV.png */, - 65B36271121C261F003EAD18 /* MW.png */, - 65B36272121C261F003EAD18 /* MX.png */, - 65B36273121C261F003EAD18 /* MY.png */, - 65B36274121C261F003EAD18 /* MZ.png */, - 65B36275121C261F003EAD18 /* NA.png */, - 65B36276121C261F003EAD18 /* NC.png */, - 65B36277121C261F003EAD18 /* NE.png */, - 65B36278121C261F003EAD18 /* NF.png */, - 65B36279121C261F003EAD18 /* NG.png */, - 65B3627A121C261F003EAD18 /* NI.png */, - 65B3627B121C261F003EAD18 /* NL.png */, - 65B3627C121C261F003EAD18 /* NO.png */, - 65B3627D121C261F003EAD18 /* NP.png */, - 65B3627E121C261F003EAD18 /* NR.png */, - 65B3627F121C261F003EAD18 /* NU.png */, - 65B36280121C261F003EAD18 /* NZ.png */, - 65B36281121C261F003EAD18 /* OM.png */, - 65B36282121C261F003EAD18 /* PA.png */, - 65B36283121C261F003EAD18 /* PE.png */, - 65B36284121C261F003EAD18 /* PF.png */, - 65B36285121C261F003EAD18 /* PG.png */, - 65B36286121C261F003EAD18 /* PH.png */, - 65B36287121C261F003EAD18 /* PK.png */, - 65B36288121C261F003EAD18 /* PL.png */, - 65B36289121C261F003EAD18 /* PM.png */, - 65B3628A121C261F003EAD18 /* PN.png */, - 65B3628B121C261F003EAD18 /* PR.png */, - 65B3628C121C261F003EAD18 /* PS.png */, - 65B3628D121C261F003EAD18 /* PT.png */, - 65B3628E121C261F003EAD18 /* PW.png */, - 65B3628F121C261F003EAD18 /* PY.png */, - 65B36290121C261F003EAD18 /* QA.png */, - 65B36291121C261F003EAD18 /* RE.png */, - 65B36292121C261F003EAD18 /* RO.png */, - 65B36293121C261F003EAD18 /* RS.png */, - 65B36294121C261F003EAD18 /* RU.png */, - 65B36295121C261F003EAD18 /* RW.png */, - 65B36296121C261F003EAD18 /* SA.png */, - 65B36297121C261F003EAD18 /* SB.png */, - 65B36298121C261F003EAD18 /* SC.png */, - 65B36299121C261F003EAD18 /* SD.png */, - 65B3629A121C261F003EAD18 /* SE.png */, - 65B3629B121C261F003EAD18 /* SG.png */, - 65B3629C121C261F003EAD18 /* SH.png */, - 65B3629D121C261F003EAD18 /* SI.png */, - 65B3629E121C261F003EAD18 /* SJ.png */, - 65B3629F121C261F003EAD18 /* SK.png */, - 65B362A0121C261F003EAD18 /* SL.png */, - 65B362A1121C261F003EAD18 /* SM.png */, - 65B362A2121C261F003EAD18 /* SN.png */, - 65B362A3121C261F003EAD18 /* SO.png */, - 65B362A4121C261F003EAD18 /* SR.png */, - 65B362A5121C261F003EAD18 /* ST.png */, - 65B362A6121C261F003EAD18 /* SV.png */, - 65B362A7121C261F003EAD18 /* SY.png */, - 65B362A8121C261F003EAD18 /* SZ.png */, - 65B362A9121C261F003EAD18 /* TC.png */, - 65B362AA121C261F003EAD18 /* TD.png */, - 65B362AB121C261F003EAD18 /* TF.png */, - 65B362AC121C261F003EAD18 /* TG.png */, - 65B362AD121C261F003EAD18 /* TH.png */, - 65B362AE121C261F003EAD18 /* TJ.png */, - 65B362AF121C261F003EAD18 /* TK.png */, - 65B362B0121C261F003EAD18 /* TL.png */, - 65B362B1121C261F003EAD18 /* TM.png */, - 65B362B2121C261F003EAD18 /* TN.png */, - 65B362B3121C261F003EAD18 /* TO.png */, - 65B362B4121C261F003EAD18 /* TR.png */, - 65B362B5121C261F003EAD18 /* TT.png */, - 65B362B6121C261F003EAD18 /* TV.png */, - 65B362B7121C261F003EAD18 /* TW.png */, - 65B362B8121C261F003EAD18 /* TZ.png */, - 65B362B9121C261F003EAD18 /* UA.png */, - 65B362BA121C261F003EAD18 /* UG.png */, - 65B362BB121C261F003EAD18 /* UM.png */, - 65B362BC121C261F003EAD18 /* US.png */, - 65B362BD121C261F003EAD18 /* UY.png */, - 65B362BE121C261F003EAD18 /* UZ.png */, - 65B362BF121C261F003EAD18 /* VA.png */, - 65B362C0121C261F003EAD18 /* VC.png */, - 65B362C1121C261F003EAD18 /* VE.png */, - 65B362C2121C261F003EAD18 /* VG.png */, - 65B362C3121C261F003EAD18 /* VI.png */, - 65B362C4121C261F003EAD18 /* VN.png */, - 65B362C5121C261F003EAD18 /* VU.png */, - 65B362C6121C261F003EAD18 /* WF.png */, - 65B362C7121C261F003EAD18 /* WS.png */, - 65B362C8121C261F003EAD18 /* YE.png */, - 65B362C9121C261F003EAD18 /* YT.png */, - 65B362CA121C261F003EAD18 /* ZA.png */, - 65B362CB121C261F003EAD18 /* ZM.png */, - 65B362CC121C261F003EAD18 /* ZW.png */, - ); - path = flags; - sourceTree = ""; - }; - 65B362CE121C261F003EAD18 /* network */ = { - isa = PBXGroup; - children = ( - 65B362CF121C261F003EAD18 /* Makefile */, - 65B362D0121C261F003EAD18 /* network.pri */, - 65B362D1121C261F003EAD18 /* network.pro */, - 65B362D2121C261F003EAD18 /* qxtjsonrpccall.cpp */, - 65B362D3121C261F003EAD18 /* qxtjsonrpccall.h */, - 65B362D4121C261F003EAD18 /* qxtjsonrpcclient.cpp */, - 65B362D5121C261F003EAD18 /* qxtjsonrpcclient.h */, - 65B362D6121C261F003EAD18 /* qxtmail_p.h */, - 65B362D7121C261F003EAD18 /* qxtmailattachment.cpp */, - 65B362D8121C261F003EAD18 /* qxtmailattachment.h */, - 65B362D9121C261F003EAD18 /* qxtmailmessage.cpp */, - 65B362DA121C261F003EAD18 /* qxtmailmessage.h */, - 65B362DB121C261F003EAD18 /* qxtnetwork.h */, - 65B362DC121C261F003EAD18 /* qxtrpcpeer.cpp */, - 65B362DD121C261F003EAD18 /* qxtrpcpeer.h */, - 65B362DE121C261F003EAD18 /* qxtsmtp.cpp */, - 65B362DF121C261F003EAD18 /* qxtsmtp.h */, - 65B362E0121C261F003EAD18 /* qxtsmtp_p.h */, - 65B362E1121C261F003EAD18 /* qxttcpconnectionmanager.cpp */, - 65B362E2121C261F003EAD18 /* qxttcpconnectionmanager.h */, - 65B362E3121C261F003EAD18 /* qxttcpconnectionmanager_p.h */, - 65B362E4121C261F003EAD18 /* qxtxmlrpc_p.cpp */, - 65B362E5121C261F003EAD18 /* qxtxmlrpc_p.h */, - 65B362E6121C261F003EAD18 /* qxtxmlrpccall.cpp */, - 65B362E7121C261F003EAD18 /* qxtxmlrpccall.h */, - 65B362E8121C261F003EAD18 /* qxtxmlrpcclient.cpp */, - 65B362E9121C261F003EAD18 /* qxtxmlrpcclient.h */, - ); - path = network; - sourceTree = ""; - }; - 65B362EC121C261F003EAD18 /* sql */ = { - isa = PBXGroup; - children = ( - 65B362ED121C261F003EAD18 /* Makefile */, - 65B362EE121C261F003EAD18 /* qxtsql.h */, - 65B362EF121C261F003EAD18 /* qxtsqlpackage.cpp */, - 65B362F0121C261F003EAD18 /* qxtsqlpackage.h */, - 65B362F1121C261F003EAD18 /* qxtsqlpackagemodel.cpp */, - 65B362F2121C261F003EAD18 /* qxtsqlpackagemodel.h */, - 65B362F3121C261F003EAD18 /* sql.pri */, - 65B362F4121C261F003EAD18 /* sql.pro */, - ); - path = sql; - sourceTree = ""; - }; - 65B362F5121C261F003EAD18 /* web */ = { - isa = PBXGroup; - children = ( - 65B362F6121C261F003EAD18 /* Makefile */, - 65B362F7121C261F003EAD18 /* qxtabstracthttpconnector.cpp */, - 65B362F8121C261F003EAD18 /* qxtabstracthttpconnector.h */, - 65B362F9121C261F003EAD18 /* qxtabstractwebservice.cpp */, - 65B362FA121C261F003EAD18 /* qxtabstractwebservice.h */, - 65B362FB121C261F003EAD18 /* qxtabstractwebsessionmanager.cpp */, - 65B362FC121C261F003EAD18 /* qxtabstractwebsessionmanager.h */, - 65B362FD121C261F003EAD18 /* qxtabstractwebsessionmanager_p.h */, - 65B362FE121C261F003EAD18 /* qxthtmltemplate.cpp */, - 65B362FF121C261F003EAD18 /* qxthtmltemplate.h */, - 65B36300121C261F003EAD18 /* qxthttpserverconnector.cpp */, - 65B36301121C261F003EAD18 /* qxthttpsessionmanager.cpp */, - 65B36302121C261F003EAD18 /* qxthttpsessionmanager.h */, - 65B36303121C261F003EAD18 /* qxtscgiserverconnector.cpp */, - 65B36304121C261F003EAD18 /* qxtweb.h */, - 65B36305121C261F003EAD18 /* qxtwebcgiservice.cpp */, - 65B36306121C261F003EAD18 /* qxtwebcgiservice.h */, - 65B36307121C261F003EAD18 /* qxtwebcgiservice_p.h */, - 65B36308121C261F003EAD18 /* qxtwebcontent.cpp */, - 65B36309121C261F003EAD18 /* qxtwebcontent.h */, - 65B3630A121C261F003EAD18 /* qxtwebevent.cpp */, - 65B3630B121C261F003EAD18 /* qxtwebevent.h */, - 65B3630C121C261F003EAD18 /* qxtwebservicedirectory.cpp */, - 65B3630D121C261F003EAD18 /* qxtwebservicedirectory.h */, - 65B3630E121C261F003EAD18 /* qxtwebservicedirectory_p.h */, - 65B3630F121C261F003EAD18 /* qxtwebslotservice.cpp */, - 65B36310121C261F003EAD18 /* qxtwebslotservice.h */, - 65B36311121C261F003EAD18 /* web.pri */, - 65B36312121C261F003EAD18 /* web.pro */, - ); - path = web; - sourceTree = ""; - }; - 65B36313121C261F003EAD18 /* zeroconf */ = { - isa = PBXGroup; - children = ( - 65B36314121C261F003EAD18 /* qxtavahipoll.cpp */, - 65B36315121C261F003EAD18 /* qxtavahipoll.h */, - 65B36316121C261F003EAD18 /* qxtavahipoll_p.h */, - 65B36317121C261F003EAD18 /* qxtdiscoverableservice.cpp */, - 65B36318121C261F003EAD18 /* qxtdiscoverableservice.h */, - 65B36319121C261F003EAD18 /* qxtdiscoverableservice_p.h */, - 65B3631A121C261F003EAD18 /* qxtdiscoverableservicename.cpp */, - 65B3631B121C261F003EAD18 /* qxtdiscoverableservicename.h */, - 65B3631C121C261F003EAD18 /* qxtmdns_avahi.cpp */, - 65B3631D121C261F003EAD18 /* qxtmdns_avahi.h */, - 65B3631E121C261F003EAD18 /* qxtmdns_avahi_p.h */, - 65B3631F121C261F003EAD18 /* qxtmdns_bonjour.cpp */, - 65B36320121C261F003EAD18 /* qxtmdns_bonjour.h */, - 65B36321121C261F003EAD18 /* qxtservicebrowser.cpp */, - 65B36322121C261F003EAD18 /* qxtservicebrowser.h */, - 65B36323121C261F003EAD18 /* qxtservicebrowser_p.h */, - 65B36324121C261F003EAD18 /* qxtzeroconf.h */, - 65B36325121C261F003EAD18 /* zeroconf.pri */, - 65B36326121C261F003EAD18 /* zeroconf.pro */, - ); - path = zeroconf; - sourceTree = ""; - }; - 65B36327121C261F003EAD18 /* translations */ = { - isa = PBXGroup; - children = ( - 65B36328121C261F003EAD18 /* gen_qlocale.cpp */, - 65B36329121C261F003EAD18 /* qxt_de.ts */, - 65B3632A121C261F003EAD18 /* qxt_en.ts */, - 65B3632B121C261F003EAD18 /* qxt_es.ts */, - 65B3632C121C261F003EAD18 /* qxt_fi.ts */, - 65B3632D121C261F003EAD18 /* qxt_fr.ts */, - 65B3632E121C261F003EAD18 /* qxt_it.ts */, - ); - path = translations; - sourceTree = ""; - }; - 65B36330121C261F003EAD18 /* opmapcontrol */ = { - isa = PBXGroup; - children = ( - 65B36331121C261F003EAD18 /* opmapcontrol.h */, - 65B36332121C261F003EAD18 /* opmapcontrol.pri */, - 65B36333121C261F003EAD18 /* opmapcontrol.pro */, - 65B36334121C261F003EAD18 /* src */, - ); - path = opmapcontrol; - sourceTree = ""; - }; - 65B36334121C261F003EAD18 /* src */ = { - isa = PBXGroup; - children = ( - 65B36335121C261F003EAD18 /* common.pri */, - 65B36336121C261F003EAD18 /* core */, - 65B3635C121C261F003EAD18 /* internals */, - 65B3637F121C261F003EAD18 /* mapwidget */, - 65B363A3121C261F003EAD18 /* src.pro */, - ); - path = src; - sourceTree = ""; - }; - 65B36336121C261F003EAD18 /* core */ = { - isa = PBXGroup; - children = ( - 65B36337121C261F003EAD18 /* accessmode.h */, - 65B36338121C261F003EAD18 /* alllayersoftype.cpp */, - 65B36339121C261F003EAD18 /* alllayersoftype.h */, - 65B3633A121C261F003EAD18 /* cache.cpp */, - 65B3633B121C261F003EAD18 /* cache.h */, - 65B3633C121C261F003EAD18 /* cacheitemqueue.cpp */, - 65B3633D121C261F003EAD18 /* cacheitemqueue.h */, - 65B3633E121C261F003EAD18 /* core.pro */, - 65B3633F121C261F003EAD18 /* debugheader.h */, - 65B36340121C261F003EAD18 /* geodecoderstatus.h */, - 65B36341121C261F003EAD18 /* kibertilecache.cpp */, - 65B36342121C261F003EAD18 /* kibertilecache.h */, - 65B36343121C261F003EAD18 /* languagetype.cpp */, - 65B36344121C261F003EAD18 /* languagetype.h */, - 65B36345121C261F003EAD18 /* maptype.h */, - 65B36346121C261F003EAD18 /* memorycache.cpp */, - 65B36347121C261F003EAD18 /* memorycache.h */, - 65B36348121C261F003EAD18 /* opmaps.cpp */, - 65B36349121C261F003EAD18 /* opmaps.h */, - 65B3634A121C261F003EAD18 /* placemark.cpp */, - 65B3634B121C261F003EAD18 /* placemark.h */, - 65B3634C121C261F003EAD18 /* point.cpp */, - 65B3634D121C261F003EAD18 /* point.h */, - 65B3634E121C261F003EAD18 /* providerstrings.cpp */, - 65B3634F121C261F003EAD18 /* providerstrings.h */, - 65B36350121C261F003EAD18 /* pureimage.cpp */, - 65B36351121C261F003EAD18 /* pureimage.h */, - 65B36352121C261F003EAD18 /* pureimagecache.cpp */, - 65B36353121C261F003EAD18 /* pureimagecache.h */, - 65B36354121C261F003EAD18 /* rawtile.cpp */, - 65B36355121C261F003EAD18 /* rawtile.h */, - 65B36356121C261F003EAD18 /* size.cpp */, - 65B36357121C261F003EAD18 /* size.h */, - 65B36358121C261F003EAD18 /* tilecachequeue.cpp */, - 65B36359121C261F003EAD18 /* tilecachequeue.h */, - 65B3635A121C261F003EAD18 /* urlfactory.cpp */, - 65B3635B121C261F003EAD18 /* urlfactory.h */, - ); - path = core; - sourceTree = ""; - }; - 65B3635C121C261F003EAD18 /* internals */ = { - isa = PBXGroup; - children = ( - 65B3635D121C261F003EAD18 /* copyrightstrings.h */, - 65B3635E121C261F003EAD18 /* core.cpp */, - 65B3635F121C261F003EAD18 /* core.h */, - 65B36360121C261F003EAD18 /* debugheader.h */, - 65B36361121C261F003EAD18 /* internals.pro */, - 65B36362121C261F003EAD18 /* loadtask.cpp */, - 65B36363121C261F003EAD18 /* loadtask.h */, - 65B36364121C261F003EAD18 /* MouseWheelZoomType.cpp */, - 65B36365121C261F003EAD18 /* mousewheelzoomtype.h */, - 65B36366121C261F003EAD18 /* pointlatlng.cpp */, - 65B36367121C261F003EAD18 /* pointlatlng.h */, - 65B36368121C261F003EAD18 /* projections */, - 65B36373121C261F003EAD18 /* pureprojection.cpp */, - 65B36374121C261F003EAD18 /* pureprojection.h */, - 65B36375121C261F003EAD18 /* rectangle.cpp */, - 65B36376121C261F003EAD18 /* rectangle.h */, - 65B36377121C261F003EAD18 /* rectlatlng.cpp */, - 65B36378121C261F003EAD18 /* rectlatlng.h */, - 65B36379121C261F003EAD18 /* sizelatlng.cpp */, - 65B3637A121C261F003EAD18 /* sizelatlng.h */, - 65B3637B121C261F003EAD18 /* tile.cpp */, - 65B3637C121C261F003EAD18 /* tile.h */, - 65B3637D121C261F003EAD18 /* tilematrix.cpp */, - 65B3637E121C261F003EAD18 /* tilematrix.h */, - ); - path = internals; - sourceTree = ""; - }; - 65B36368121C261F003EAD18 /* projections */ = { - isa = PBXGroup; - children = ( - 65B36369121C261F003EAD18 /* lks94projection.cpp */, - 65B3636A121C261F003EAD18 /* lks94projection.h */, - 65B3636B121C261F003EAD18 /* mercatorprojection.cpp */, - 65B3636C121C261F003EAD18 /* mercatorprojection.h */, - 65B3636D121C261F003EAD18 /* mercatorprojectionyandex.cpp */, - 65B3636E121C261F003EAD18 /* mercatorprojectionyandex.h */, - 65B3636F121C261F003EAD18 /* platecarreeprojection.cpp */, - 65B36370121C261F003EAD18 /* platecarreeprojection.h */, - 65B36371121C261F003EAD18 /* platecarreeprojectionpergo.cpp */, - 65B36372121C261F003EAD18 /* platecarreeprojectionpergo.h */, - ); - path = projections; - sourceTree = ""; - }; - 65B3637F121C261F003EAD18 /* mapwidget */ = { - isa = PBXGroup; - children = ( - 65B36380121C261F003EAD18 /* configuration.cpp */, - 65B36381121C261F003EAD18 /* configuration.h */, - 65B36382121C261F003EAD18 /* homeitem.cpp */, - 65B36383121C261F003EAD18 /* homeitem.h */, - 65B36384121C261F003EAD18 /* images */, - 65B36390121C261F003EAD18 /* mapgraphicitem.cpp */, - 65B36391121C261F003EAD18 /* mapgraphicitem.h */, - 65B36392121C261F003EAD18 /* mapresources.qrc */, - 65B36393121C261F003EAD18 /* mapripform.cpp */, - 65B36394121C261F003EAD18 /* mapripform.h */, - 65B36395121C261F003EAD18 /* mapripform.ui */, - 65B36396121C261F003EAD18 /* mapripper.cpp */, - 65B36397121C261F003EAD18 /* mapripper.h */, - 65B36398121C261F003EAD18 /* mapwidget.pro */, - 65B36399121C261F003EAD18 /* opmapwidget.cpp */, - 65B3639A121C261F003EAD18 /* opmapwidget.h */, - 65B3639B121C261F003EAD18 /* trailitem.cpp */, - 65B3639C121C261F003EAD18 /* trailitem.h */, - 65B3639D121C261F003EAD18 /* uavitem.cpp */, - 65B3639E121C261F003EAD18 /* uavitem.h */, - 65B3639F121C261F003EAD18 /* uavmapfollowtype.h */, - 65B363A0121C261F003EAD18 /* uavtrailtype.h */, - 65B363A1121C261F003EAD18 /* waypointitem.cpp */, - 65B363A2121C261F003EAD18 /* waypointitem.h */, - ); - path = mapwidget; - sourceTree = ""; - }; - 65B36384121C261F003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B36385121C261F003EAD18 /* airplane.png */, - 65B36386121C261F003EAD18 /* airplane.svg */, - 65B36387121C261F003EAD18 /* airplanepip.png */, - 65B36388121C261F003EAD18 /* bigMarkerGreen.png */, - 65B36389121C261F003EAD18 /* compas.svg */, - 65B3638A121C261F003EAD18 /* EasystarBlue.png */, - 65B3638B121C261F003EAD18 /* home.png */, - 65B3638C121C261F003EAD18 /* home.svg */, - 65B3638D121C261F003EAD18 /* home2.svg */, - 65B3638E121C261F003EAD18 /* mapquad.png */, - 65B3638F121C261F003EAD18 /* marker.png */, - ); - path = images; - sourceTree = ""; - }; - 65B363A4121C261F003EAD18 /* qextserialport */ = { - isa = PBXGroup; - children = ( - 65B363A5121C261F003EAD18 /* qextserialport.pri */, - 65B363A6121C261F003EAD18 /* qextserialport.pro */, - 65B363A7121C261F003EAD18 /* src */, - ); - path = qextserialport; - sourceTree = ""; - }; - 65B363A7121C261F003EAD18 /* src */ = { - isa = PBXGroup; - children = ( - 65B363A8121C261F003EAD18 /* posix_qextserialport.cpp */, - 65B363A9121C261F003EAD18 /* qextserialenumerator.h */, - 65B363AA121C261F003EAD18 /* qextserialenumerator_osx.cpp */, - 65B363AB121C261F003EAD18 /* qextserialenumerator_unix.cpp */, - 65B363AC121C261F003EAD18 /* qextserialenumerator_win.cpp */, - 65B363AD121C261F003EAD18 /* qextserialport.cpp */, - 65B363AE121C261F003EAD18 /* qextserialport.h */, - 65B363AF121C261F003EAD18 /* qextserialport_global.h */, - 65B363B0121C261F003EAD18 /* src.pro */, - 65B363B1121C261F003EAD18 /* win_qextserialport.cpp */, - ); - path = src; - sourceTree = ""; - }; - 65B363B2121C261F003EAD18 /* qtconcurrent */ = { - isa = PBXGroup; - children = ( - 65B363B3121C261F003EAD18 /* multitask.h */, - 65B363B4121C261F003EAD18 /* qtconcurrent.pri */, - 65B363B5121C261F003EAD18 /* qtconcurrent.pro */, - 65B363B6121C261F003EAD18 /* qtconcurrent_global.h */, - 65B363B7121C261F003EAD18 /* QtConcurrentTools */, - 65B363B8121C261F003EAD18 /* runextensions.h */, - ); - path = qtconcurrent; - sourceTree = ""; - }; - 65B363B9121C261F003EAD18 /* qwt */ = { - isa = PBXGroup; - children = ( - 65B363BA121C261F003EAD18 /* COPYING */, - 65B363BB121C261F003EAD18 /* qwt.pri */, - 65B363BC121C261F003EAD18 /* qwt.pro */, - 65B363BD121C261F003EAD18 /* qwtconfig.pri */, - 65B363BE121C261F003EAD18 /* src */, - ); - path = qwt; - sourceTree = ""; - }; - 65B363BE121C261F003EAD18 /* src */ = { - isa = PBXGroup; - children = ( - 65B363BF121C261F003EAD18 /* qwt.h */, - 65B363C0121C261F003EAD18 /* qwt_abstract_scale.cpp */, - 65B363C1121C261F003EAD18 /* qwt_abstract_scale.h */, - 65B363C2121C261F003EAD18 /* qwt_abstract_scale_draw.cpp */, - 65B363C3121C261F003EAD18 /* qwt_abstract_scale_draw.h */, - 65B363C4121C261F003EAD18 /* qwt_abstract_slider.cpp */, - 65B363C5121C261F003EAD18 /* qwt_abstract_slider.h */, - 65B363C6121C261F003EAD18 /* qwt_analog_clock.cpp */, - 65B363C7121C261F003EAD18 /* qwt_analog_clock.h */, - 65B363C8121C261F003EAD18 /* qwt_array.h */, - 65B363C9121C261F003EAD18 /* qwt_arrow_button.cpp */, - 65B363CA121C261F003EAD18 /* qwt_arrow_button.h */, - 65B363CB121C261F003EAD18 /* qwt_clipper.cpp */, - 65B363CC121C261F003EAD18 /* qwt_clipper.h */, - 65B363CD121C261F003EAD18 /* qwt_color_map.cpp */, - 65B363CE121C261F003EAD18 /* qwt_color_map.h */, - 65B363CF121C261F003EAD18 /* qwt_compass.cpp */, - 65B363D0121C261F003EAD18 /* qwt_compass.h */, - 65B363D1121C261F003EAD18 /* qwt_compass_rose.cpp */, - 65B363D2121C261F003EAD18 /* qwt_compass_rose.h */, - 65B363D3121C261F003EAD18 /* qwt_counter.cpp */, - 65B363D4121C261F003EAD18 /* qwt_counter.h */, - 65B363D5121C261F003EAD18 /* qwt_curve_fitter.cpp */, - 65B363D6121C261F003EAD18 /* qwt_curve_fitter.h */, - 65B363D7121C261F003EAD18 /* qwt_data.cpp */, - 65B363D8121C261F003EAD18 /* qwt_data.h */, - 65B363D9121C261F003EAD18 /* qwt_dial.cpp */, - 65B363DA121C261F003EAD18 /* qwt_dial.h */, - 65B363DB121C261F003EAD18 /* qwt_dial_needle.cpp */, - 65B363DC121C261F003EAD18 /* qwt_dial_needle.h */, - 65B363DD121C261F003EAD18 /* qwt_double_interval.cpp */, - 65B363DE121C261F003EAD18 /* qwt_double_interval.h */, - 65B363DF121C261F003EAD18 /* qwt_double_range.cpp */, - 65B363E0121C261F003EAD18 /* qwt_double_range.h */, - 65B363E1121C261F003EAD18 /* qwt_double_rect.cpp */, - 65B363E2121C261F003EAD18 /* qwt_double_rect.h */, - 65B363E3121C261F003EAD18 /* qwt_dyngrid_layout.cpp */, - 65B363E4121C261F003EAD18 /* qwt_dyngrid_layout.h */, - 65B363E5121C261F003EAD18 /* qwt_event_pattern.cpp */, - 65B363E6121C261F003EAD18 /* qwt_event_pattern.h */, - 65B363E7121C261F003EAD18 /* qwt_global.h */, - 65B363E8121C261F003EAD18 /* qwt_interval_data.cpp */, - 65B363E9121C261F003EAD18 /* qwt_interval_data.h */, - 65B363EA121C261F003EAD18 /* qwt_knob.cpp */, - 65B363EB121C261F003EAD18 /* qwt_knob.h */, - 65B363EC121C261F003EAD18 /* qwt_layout_metrics.cpp */, - 65B363ED121C261F003EAD18 /* qwt_layout_metrics.h */, - 65B363EE121C261F003EAD18 /* qwt_legend.cpp */, - 65B363EF121C261F003EAD18 /* qwt_legend.h */, - 65B363F0121C261F003EAD18 /* qwt_legend_item.cpp */, - 65B363F1121C261F003EAD18 /* qwt_legend_item.h */, - 65B363F2121C261F003EAD18 /* qwt_legend_itemmanager.h */, - 65B363F3121C261F003EAD18 /* qwt_magnifier.cpp */, - 65B363F4121C261F003EAD18 /* qwt_magnifier.h */, - 65B363F5121C261F003EAD18 /* qwt_math.cpp */, - 65B363F6121C261F003EAD18 /* qwt_math.h */, - 65B363F7121C261F003EAD18 /* qwt_paint_buffer.cpp */, - 65B363F8121C261F003EAD18 /* qwt_paint_buffer.h */, - 65B363F9121C261F003EAD18 /* qwt_painter.cpp */, - 65B363FA121C261F003EAD18 /* qwt_painter.h */, - 65B363FB121C261F003EAD18 /* qwt_panner.cpp */, - 65B363FC121C261F003EAD18 /* qwt_panner.h */, - 65B363FD121C261F003EAD18 /* qwt_picker.cpp */, - 65B363FE121C261F003EAD18 /* qwt_picker.h */, - 65B363FF121C261F003EAD18 /* qwt_picker_machine.cpp */, - 65B36400121C261F003EAD18 /* qwt_picker_machine.h */, - 65B36401121C261F003EAD18 /* qwt_plot.cpp */, - 65B36402121C261F003EAD18 /* qwt_plot.h */, - 65B36403121C261F003EAD18 /* qwt_plot_axis.cpp */, - 65B36404121C261F003EAD18 /* qwt_plot_canvas.cpp */, - 65B36405121C261F003EAD18 /* qwt_plot_canvas.h */, - 65B36406121C261F003EAD18 /* qwt_plot_curve.cpp */, - 65B36407121C261F003EAD18 /* qwt_plot_curve.h */, - 65B36408121C261F003EAD18 /* qwt_plot_dict.cpp */, - 65B36409121C261F003EAD18 /* qwt_plot_dict.h */, - 65B3640A121C261F003EAD18 /* qwt_plot_grid.cpp */, - 65B3640B121C261F003EAD18 /* qwt_plot_grid.h */, - 65B3640C121C261F003EAD18 /* qwt_plot_item.cpp */, - 65B3640D121C261F003EAD18 /* qwt_plot_item.h */, - 65B3640E121C261F003EAD18 /* qwt_plot_layout.cpp */, - 65B3640F121C261F003EAD18 /* qwt_plot_layout.h */, - 65B36410121C261F003EAD18 /* qwt_plot_magnifier.cpp */, - 65B36411121C261F003EAD18 /* qwt_plot_magnifier.h */, - 65B36412121C261F003EAD18 /* qwt_plot_marker.cpp */, - 65B36413121C261F003EAD18 /* qwt_plot_marker.h */, - 65B36414121C261F003EAD18 /* qwt_plot_panner.cpp */, - 65B36415121C261F003EAD18 /* qwt_plot_panner.h */, - 65B36416121C261F003EAD18 /* qwt_plot_picker.cpp */, - 65B36417121C261F003EAD18 /* qwt_plot_picker.h */, - 65B36418121C261F003EAD18 /* qwt_plot_print.cpp */, - 65B36419121C261F003EAD18 /* qwt_plot_printfilter.cpp */, - 65B3641A121C261F003EAD18 /* qwt_plot_printfilter.h */, - 65B3641B121C261F003EAD18 /* qwt_plot_rasteritem.cpp */, - 65B3641C121C261F003EAD18 /* qwt_plot_rasteritem.h */, - 65B3641D121C261F003EAD18 /* qwt_plot_rescaler.cpp */, - 65B3641E121C261F003EAD18 /* qwt_plot_rescaler.h */, - 65B3641F121C261F003EAD18 /* qwt_plot_scaleitem.cpp */, - 65B36420121C261F003EAD18 /* qwt_plot_scaleitem.h */, - 65B36421121C261F003EAD18 /* qwt_plot_spectrogram.cpp */, - 65B36422121C261F003EAD18 /* qwt_plot_spectrogram.h */, - 65B36423121C261F003EAD18 /* qwt_plot_svgitem.cpp */, - 65B36424121C261F003EAD18 /* qwt_plot_svgitem.h */, - 65B36425121C261F003EAD18 /* qwt_plot_xml.cpp */, - 65B36426121C261F003EAD18 /* qwt_plot_zoomer.cpp */, - 65B36427121C261F003EAD18 /* qwt_plot_zoomer.h */, - 65B36428121C261F003EAD18 /* qwt_polygon.h */, - 65B36429121C261F003EAD18 /* qwt_raster_data.cpp */, - 65B3642A121C261F003EAD18 /* qwt_raster_data.h */, - 65B3642B121C261F003EAD18 /* qwt_round_scale_draw.cpp */, - 65B3642C121C261F003EAD18 /* qwt_round_scale_draw.h */, - 65B3642D121C261F003EAD18 /* qwt_scale_div.cpp */, - 65B3642E121C261F003EAD18 /* qwt_scale_div.h */, - 65B3642F121C261F003EAD18 /* qwt_scale_draw.cpp */, - 65B36430121C261F003EAD18 /* qwt_scale_draw.h */, - 65B36431121C261F003EAD18 /* qwt_scale_engine.cpp */, - 65B36432121C261F003EAD18 /* qwt_scale_engine.h */, - 65B36433121C261F003EAD18 /* qwt_scale_map.cpp */, - 65B36434121C261F003EAD18 /* qwt_scale_map.h */, - 65B36435121C261F003EAD18 /* qwt_scale_widget.cpp */, - 65B36436121C261F003EAD18 /* qwt_scale_widget.h */, - 65B36437121C261F003EAD18 /* qwt_slider.cpp */, - 65B36438121C261F003EAD18 /* qwt_slider.h */, - 65B36439121C261F003EAD18 /* qwt_spline.cpp */, - 65B3643A121C261F003EAD18 /* qwt_spline.h */, - 65B3643B121C261F003EAD18 /* qwt_symbol.cpp */, - 65B3643C121C261F003EAD18 /* qwt_symbol.h */, - 65B3643D121C261F003EAD18 /* qwt_text.cpp */, - 65B3643E121C261F003EAD18 /* qwt_text.h */, - 65B3643F121C261F003EAD18 /* qwt_text_engine.cpp */, - 65B36440121C261F003EAD18 /* qwt_text_engine.h */, - 65B36441121C261F003EAD18 /* qwt_text_label.cpp */, - 65B36442121C261F003EAD18 /* qwt_text_label.h */, - 65B36443121C261F003EAD18 /* qwt_thermo.cpp */, - 65B36444121C261F003EAD18 /* qwt_thermo.h */, - 65B36445121C261F003EAD18 /* qwt_valuelist.h */, - 65B36446121C261F003EAD18 /* qwt_wheel.cpp */, - 65B36447121C261F003EAD18 /* qwt_wheel.h */, - 65B36448121C261F003EAD18 /* src.pro */, - ); - path = src; - sourceTree = ""; - }; - 65B36449121C261F003EAD18 /* qymodem */ = { - isa = PBXGroup; - children = ( - 65B3644A121C261F003EAD18 /* qymodem.pri */, - 65B3644B121C261F003EAD18 /* qymodem.pro */, - 65B3644C121C261F003EAD18 /* src */, - ); - path = qymodem; - sourceTree = ""; - }; - 65B3644C121C261F003EAD18 /* src */ = { - isa = PBXGroup; - children = ( - 65B3644D121C261F003EAD18 /* qymodem.cpp */, - 65B3644E121C261F003EAD18 /* qymodem.h */, - 65B3644F121C261F003EAD18 /* qymodem_tx.cpp */, - 65B36450121C261F003EAD18 /* qymodem_tx.h */, - 65B36451121C261F003EAD18 /* qymodemfilestream.cpp */, - 65B36452121C261F003EAD18 /* qymodemsend.cpp */, - 65B36453121C261F003EAD18 /* qymodemsend.h */, - 65B36454121C261F003EAD18 /* src.pro */, - ); - path = src; - sourceTree = ""; - }; - 65B36455121C261F003EAD18 /* uavobjgenerator */ = { - isa = PBXGroup; - children = ( - 65B36456121C261F003EAD18 /* main.cpp */, - 65B36457121C261F003EAD18 /* uavobjectgenerator.cpp */, - 65B36458121C261F003EAD18 /* uavobjectgenerator.h */, - 65B36459121C261F003EAD18 /* uavobjectparser.cpp */, - 65B3645A121C261F003EAD18 /* uavobjectparser.h */, - 65B3645B121C261F003EAD18 /* uavobjgenerator.pro */, - ); - path = uavobjgenerator; - sourceTree = ""; - }; - 65B3645C121C261F003EAD18 /* utils */ = { - isa = PBXGroup; - children = ( - 65B3645D121C261F003EAD18 /* abstractprocess.h */, - 65B3645E121C261F003EAD18 /* abstractprocess_win.cpp */, - 65B3645F121C261F003EAD18 /* basevalidatinglineedit.cpp */, - 65B36460121C261F003EAD18 /* basevalidatinglineedit.h */, - 65B36461121C261F003EAD18 /* checkablemessagebox.cpp */, - 65B36462121C261F003EAD18 /* checkablemessagebox.h */, - 65B36463121C261F003EAD18 /* checkablemessagebox.ui */, - 65B36464121C261F003EAD18 /* classnamevalidatinglineedit.cpp */, - 65B36465121C261F003EAD18 /* classnamevalidatinglineedit.h */, - 65B36466121C261F003EAD18 /* codegeneration.cpp */, - 65B36467121C261F003EAD18 /* codegeneration.h */, - 65B36468121C261F003EAD18 /* consoleprocess.cpp */, - 65B36469121C261F003EAD18 /* consoleprocess.h */, - 65B3646A121C261F003EAD18 /* consoleprocess_unix.cpp */, - 65B3646B121C261F003EAD18 /* consoleprocess_win.cpp */, - 65B3646C121C261F003EAD18 /* detailsbutton.cpp */, - 65B3646D121C261F003EAD18 /* detailsbutton.h */, - 65B3646E121C261F003EAD18 /* detailswidget.cpp */, - 65B3646F121C261F003EAD18 /* detailswidget.h */, - 65B36470121C261F003EAD18 /* fancylineedit.cpp */, - 65B36471121C261F003EAD18 /* fancylineedit.h */, - 65B36472121C261F003EAD18 /* fancymainwindow.cpp */, - 65B36473121C261F003EAD18 /* fancymainwindow.h */, - 65B36474121C261F003EAD18 /* filenamevalidatinglineedit.cpp */, - 65B36475121C261F003EAD18 /* filenamevalidatinglineedit.h */, - 65B36476121C261F003EAD18 /* filesearch.cpp */, - 65B36477121C261F003EAD18 /* filesearch.h */, - 65B36478121C261F003EAD18 /* filewizarddialog.cpp */, - 65B36479121C261F003EAD18 /* filewizarddialog.h */, - 65B3647A121C261F003EAD18 /* filewizardpage.cpp */, - 65B3647B121C261F003EAD18 /* filewizardpage.h */, - 65B3647C121C261F003EAD18 /* filewizardpage.ui */, - 65B3647D121C261F003EAD18 /* images */, - 65B3647F121C261F003EAD18 /* iwelcomepage.cpp */, - 65B36480121C261F003EAD18 /* iwelcomepage.h */, - 65B36481121C261F003EAD18 /* linecolumnlabel.cpp */, - 65B36482121C261F003EAD18 /* linecolumnlabel.h */, - 65B36483121C261F003EAD18 /* listutils.h */, - 65B36484121C261F003EAD18 /* newclasswidget.cpp */, - 65B36485121C261F003EAD18 /* newclasswidget.h */, - 65B36486121C261F003EAD18 /* newclasswidget.ui */, - 65B36487121C261F003EAD18 /* parameteraction.cpp */, - 65B36488121C261F003EAD18 /* parameteraction.h */, - 65B36489121C261F003EAD18 /* pathchooser.cpp */, - 65B3648A121C261F003EAD18 /* pathchooser.h */, - 65B3648B121C261F003EAD18 /* pathlisteditor.cpp */, - 65B3648C121C261F003EAD18 /* pathlisteditor.h */, - 65B3648D121C261F003EAD18 /* projectintropage.cpp */, - 65B3648E121C261F003EAD18 /* projectintropage.h */, - 65B3648F121C261F003EAD18 /* projectintropage.ui */, - 65B36490121C261F003EAD18 /* projectnamevalidatinglineedit.cpp */, - 65B36491121C261F003EAD18 /* projectnamevalidatinglineedit.h */, - 65B36492121C261F003EAD18 /* qtcassert.h */, - 65B36493121C261F003EAD18 /* qtcolorbutton.cpp */, - 65B36494121C261F003EAD18 /* qtcolorbutton.h */, - 65B36495121C261F003EAD18 /* reloadpromptutils.cpp */, - 65B36496121C261F003EAD18 /* reloadpromptutils.h */, - 65B36497121C261F003EAD18 /* savedaction.cpp */, - 65B36498121C261F003EAD18 /* savedaction.h */, - 65B36499121C261F003EAD18 /* settingsutils.cpp */, - 65B3649A121C261F003EAD18 /* settingsutils.h */, - 65B3649B121C261F003EAD18 /* styledbar.cpp */, - 65B3649C121C261F003EAD18 /* styledbar.h */, - 65B3649D121C261F003EAD18 /* stylehelper.cpp */, - 65B3649E121C261F003EAD18 /* stylehelper.h */, - 65B3649F121C261F003EAD18 /* submiteditorwidget.cpp */, - 65B364A0121C261F003EAD18 /* submiteditorwidget.h */, - 65B364A1121C261F003EAD18 /* submiteditorwidget.ui */, - 65B364A2121C261F003EAD18 /* submitfieldwidget.cpp */, - 65B364A3121C261F003EAD18 /* submitfieldwidget.h */, - 65B364A4121C261F003EAD18 /* synchronousprocess.cpp */, - 65B364A5121C261F003EAD18 /* synchronousprocess.h */, - 65B364A6121C261F003EAD18 /* treewidgetcolumnstretcher.cpp */, - 65B364A7121C261F003EAD18 /* treewidgetcolumnstretcher.h */, - 65B364A8121C261F003EAD18 /* uncommentselection.cpp */, - 65B364A9121C261F003EAD18 /* uncommentselection.h */, - 65B364AA121C261F003EAD18 /* utils.pri */, - 65B364AB121C261F003EAD18 /* utils.pro */, - 65B364AC121C261F003EAD18 /* utils.qrc */, - 65B364AD121C261F003EAD18 /* utils_global.h */, - 65B364AE121C261F003EAD18 /* welcomemodetreewidget.cpp */, - 65B364AF121C261F003EAD18 /* welcomemodetreewidget.h */, - 65B364B0121C261F003EAD18 /* winutils.cpp */, - 65B364B1121C261F003EAD18 /* winutils.h */, - ); - path = utils; - sourceTree = ""; - }; - 65B3647D121C261F003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B3647E121C261F003EAD18 /* removesubmitfield.png */, - ); - path = images; - sourceTree = ""; - }; - 65B364B4121C261F003EAD18 /* plugins */ = { - isa = PBXGroup; - children = ( - 65B364B5121C261F003EAD18 /* config */, - 65B364CF121C261F003EAD18 /* consolegadget */, - 65B364DC121C261F003EAD18 /* coreplugin */, - 65B36591121C261F003EAD18 /* dial */, - 65B365A5121C261F003EAD18 /* donothing */, - 65B365AA121C261F003EAD18 /* emptygadget */, - 65B365B5121C261F003EAD18 /* gcscontrol */, - 65B365C7121C261F003EAD18 /* gpsdisplay */, - 65B365E3121C261F003EAD18 /* hitl */, - 65B365F9121C2620003EAD18 /* hitlil2 */, - 65B3660D121C2620003EAD18 /* importexport */, - 65B36620121C2620003EAD18 /* ipconnection */, - 65B3662D121C2620003EAD18 /* lineardial */, - 65B36641121C2620003EAD18 /* modelview */, - 65B36652121C2620003EAD18 /* notify */, - 65B3666C121C2620003EAD18 /* opmap */, - 65B366AA121C2620003EAD18 /* pfd */, - 65B366BE121C2620003EAD18 /* plugins.pro */, - 65B366BF121C2620003EAD18 /* rawhid */, - 65B366CE121C2620003EAD18 /* scope */, - 65B366E0121C2620003EAD18 /* serialconnection */, - 65B366E8121C2620003EAD18 /* systemhealth */, - 65B366F9121C2620003EAD18 /* uavobjectbrowser */, - 65B36713121C2620003EAD18 /* uavobjects */, - 65B36782121C2620003EAD18 /* uavtalk */, - 65B36792121C2620003EAD18 /* uploader */, - 65B367A1121C2620003EAD18 /* welcome */, - ); - path = plugins; - sourceTree = ""; - }; - 65B364B5121C261F003EAD18 /* config */ = { - isa = PBXGroup; - children = ( - 65B364B6121C261F003EAD18 /* airframe.ui */, - 65B364B7121C261F003EAD18 /* Config.pluginspec */, - 65B364B8121C261F003EAD18 /* config.pro */, - 65B364B9121C261F003EAD18 /* configfactory.h */, - 65B364BA121C261F003EAD18 /* configgadget.cpp */, - 65B364BB121C261F003EAD18 /* configgadget.h */, - 65B364BC121C261F003EAD18 /* configgadget.qrc */, - 65B364BD121C261F003EAD18 /* configgadgetconfiguration.cpp */, - 65B364BE121C261F003EAD18 /* configgadgetconfiguration.h */, - 65B364BF121C261F003EAD18 /* configgadgetfactory.cpp */, - 65B364C0121C261F003EAD18 /* configgadgetfactory.h */, - 65B364C1121C261F003EAD18 /* configgadgetoptionspage.cpp */, - 65B364C2121C261F003EAD18 /* configgadgetoptionspage.h */, - 65B364C3121C261F003EAD18 /* configgadgetwidget.cpp */, - 65B364C4121C261F003EAD18 /* configgadgetwidget.h */, - 65B364C5121C261F003EAD18 /* configplugin.cpp */, - 65B364C6121C261F003EAD18 /* configplugin.h */, - 65B364C7121C261F003EAD18 /* fancytabwidget.cpp */, - 65B364C8121C261F003EAD18 /* fancytabwidget.h */, - 65B364C9121C261F003EAD18 /* images */, - 65B364CD121C261F003EAD18 /* settingswidget.ui */, - 65B364CE121C261F003EAD18 /* telemetry.ui */, - ); - path = config; - sourceTree = ""; - }; - 65B364C9121C261F003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B364CA121C261F003EAD18 /* Airframe.png */, - 65B364CB121C261F003EAD18 /* Servo.png */, - 65B364CC121C261F003EAD18 /* XBee.svg */, - ); - path = images; - sourceTree = ""; - }; - 65B364CF121C261F003EAD18 /* consolegadget */ = { - isa = PBXGroup; - children = ( - 65B364D0121C261F003EAD18 /* consolegadget.cpp */, - 65B364D1121C261F003EAD18 /* consolegadget.h */, - 65B364D2121C261F003EAD18 /* ConsoleGadget.pluginspec */, - 65B364D3121C261F003EAD18 /* consolegadget.pro */, - 65B364D4121C261F003EAD18 /* consolegadgetfactory.cpp */, - 65B364D5121C261F003EAD18 /* consolegadgetfactory.h */, - 65B364D6121C261F003EAD18 /* consolegadgetwidget.cpp */, - 65B364D7121C261F003EAD18 /* consolegadgetwidget.h */, - 65B364D8121C261F003EAD18 /* consoleplugin.cpp */, - 65B364D9121C261F003EAD18 /* consoleplugin.h */, - 65B364DA121C261F003EAD18 /* texteditloggerengine.cpp */, - 65B364DB121C261F003EAD18 /* texteditloggerengine.h */, - ); - path = consolegadget; - sourceTree = ""; - }; - 65B364DC121C261F003EAD18 /* coreplugin */ = { - isa = PBXGroup; - children = ( - 65B364DD121C261F003EAD18 /* actionmanager */, - 65B364E9121C261F003EAD18 /* basemode.cpp */, - 65B364EA121C261F003EAD18 /* basemode.h */, - 65B364EB121C261F003EAD18 /* baseview.cpp */, - 65B364EC121C261F003EAD18 /* baseview.h */, - 65B364ED121C261F003EAD18 /* connectionmanager.cpp */, - 65B364EE121C261F003EAD18 /* connectionmanager.h */, - 65B364EF121C261F003EAD18 /* Core.pluginspec */, - 65B364F0121C261F003EAD18 /* core.qrc */, - 65B364F1121C261F003EAD18 /* core_global.h */, - 65B364F2121C261F003EAD18 /* coreconstants.h */, - 65B364F3121C261F003EAD18 /* coreimpl.cpp */, - 65B364F4121C261F003EAD18 /* coreimpl.h */, - 65B364F5121C261F003EAD18 /* coreplugin.cpp */, - 65B364F6121C261F003EAD18 /* coreplugin.h */, - 65B364F7121C261F003EAD18 /* coreplugin.pri */, - 65B364F8121C261F003EAD18 /* coreplugin.pro */, - 65B364F9121C261F003EAD18 /* coreplugin_dependencies.pri */, - 65B364FA121C261F003EAD18 /* dialogs */, - 65B36505121C261F003EAD18 /* eventfilteringmainwindow.cpp */, - 65B36506121C261F003EAD18 /* eventfilteringmainwindow.h */, - 65B36507121C261F003EAD18 /* fancyactionbar.cpp */, - 65B36508121C261F003EAD18 /* fancyactionbar.h */, - 65B36509121C261F003EAD18 /* fancyactionbar.qrc */, - 65B3650A121C261F003EAD18 /* fancytabwidget.cpp */, - 65B3650B121C261F003EAD18 /* fancytabwidget.h */, - 65B3650C121C261F003EAD18 /* fileiconprovider.cpp */, - 65B3650D121C261F003EAD18 /* fileiconprovider.h */, - 65B3650E121C261F003EAD18 /* generalsettings.cpp */, - 65B3650F121C261F003EAD18 /* generalsettings.h */, - 65B36510121C261F003EAD18 /* generalsettings.ui */, - 65B36511121C261F003EAD18 /* iconnection.cpp */, - 65B36512121C261F003EAD18 /* iconnection.h */, - 65B36513121C261F003EAD18 /* icontext.h */, - 65B36514121C261F003EAD18 /* icore.cpp */, - 65B36515121C261F003EAD18 /* icore.h */, - 65B36516121C261F003EAD18 /* icorelistener.h */, - 65B36517121C261F003EAD18 /* images */, - 65B36552121C261F003EAD18 /* imode.h */, - 65B36553121C261F003EAD18 /* ioutputpane.h */, - 65B36554121C261F003EAD18 /* iuavgadget.cpp */, - 65B36555121C261F003EAD18 /* iuavgadget.h */, - 65B36556121C261F003EAD18 /* iuavgadgetconfiguration.cpp */, - 65B36557121C261F003EAD18 /* iuavgadgetconfiguration.h */, - 65B36558121C261F003EAD18 /* iuavgadgetfactory.h */, - 65B36559121C261F003EAD18 /* iversioncontrol.h */, - 65B3655A121C261F003EAD18 /* iview.h */, - 65B3655B121C261F003EAD18 /* mainwindow.cpp */, - 65B3655C121C261F003EAD18 /* mainwindow.h */, - 65B3655D121C261F003EAD18 /* manhattanstyle.cpp */, - 65B3655E121C261F003EAD18 /* manhattanstyle.h */, - 65B3655F121C261F003EAD18 /* messagemanager.cpp */, - 65B36560121C261F003EAD18 /* messagemanager.h */, - 65B36561121C261F003EAD18 /* messageoutputwindow.cpp */, - 65B36562121C261F003EAD18 /* messageoutputwindow.h */, - 65B36563121C261F003EAD18 /* mimedatabase.cpp */, - 65B36564121C261F003EAD18 /* mimedatabase.h */, - 65B36565121C261F003EAD18 /* minisplitter.cpp */, - 65B36566121C261F003EAD18 /* minisplitter.h */, - 65B36567121C261F003EAD18 /* modemanager.cpp */, - 65B36568121C261F003EAD18 /* modemanager.h */, - 65B36569121C261F003EAD18 /* outputpane.h */, - 65B3656A121C261F003EAD18 /* plugindialog.cpp */, - 65B3656B121C261F003EAD18 /* plugindialog.h */, - 65B3656C121C261F003EAD18 /* rightpane.cpp */, - 65B3656D121C261F003EAD18 /* rightpane.h */, - 65B3656E121C261F003EAD18 /* settingsdatabase.cpp */, - 65B3656F121C261F003EAD18 /* settingsdatabase.h */, - 65B36570121C261F003EAD18 /* sidebar.cpp */, - 65B36571121C261F003EAD18 /* sidebar.h */, - 65B36572121C261F003EAD18 /* styleanimator.cpp */, - 65B36573121C261F003EAD18 /* styleanimator.h */, - 65B36574121C261F003EAD18 /* tabpositionindicator.cpp */, - 65B36575121C261F003EAD18 /* tabpositionindicator.h */, - 65B36576121C261F003EAD18 /* threadmanager.cpp */, - 65B36577121C261F003EAD18 /* threadmanager.h */, - 65B36578121C261F003EAD18 /* uavgadgetdecorator.cpp */, - 65B36579121C261F003EAD18 /* uavgadgetdecorator.h */, - 65B3657A121C261F003EAD18 /* uavgadgetinstancemanager.cpp */, - 65B3657B121C261F003EAD18 /* uavgadgetinstancemanager.h */, - 65B3657C121C261F003EAD18 /* uavgadgetmanager */, - 65B36581121C261F003EAD18 /* uavgadgetmode.cpp */, - 65B36582121C261F003EAD18 /* uavgadgetmode.h */, - 65B36583121C261F003EAD18 /* uavgadgetoptionspage.ui */, - 65B36584121C261F003EAD18 /* uavgadgetoptionspagedecorator.cpp */, - 65B36585121C261F003EAD18 /* uavgadgetoptionspagedecorator.h */, - 65B36586121C261F003EAD18 /* uniqueidmanager.cpp */, - 65B36587121C261F003EAD18 /* uniqueidmanager.h */, - 65B36588121C261F003EAD18 /* variablemanager.cpp */, - 65B36589121C261F003EAD18 /* variablemanager.h */, - 65B3658A121C261F003EAD18 /* versiondialog.cpp */, - 65B3658B121C261F003EAD18 /* versiondialog.h */, - 65B3658C121C261F003EAD18 /* viewmanager.cpp */, - 65B3658D121C261F003EAD18 /* viewmanager.h */, - 65B3658E121C261F003EAD18 /* workspacesettings.cpp */, - 65B3658F121C261F003EAD18 /* workspacesettings.h */, - 65B36590121C261F003EAD18 /* workspacesettings.ui */, - ); - path = coreplugin; - sourceTree = ""; - }; - 65B364DD121C261F003EAD18 /* actionmanager */ = { - isa = PBXGroup; - children = ( - 65B364DE121C261F003EAD18 /* actioncontainer.cpp */, - 65B364DF121C261F003EAD18 /* actioncontainer.h */, - 65B364E0121C261F003EAD18 /* actioncontainer_p.h */, - 65B364E1121C261F003EAD18 /* actionmanager.cpp */, - 65B364E2121C261F003EAD18 /* actionmanager.h */, - 65B364E3121C261F003EAD18 /* actionmanager_p.h */, - 65B364E4121C261F003EAD18 /* command.cpp */, - 65B364E5121C261F003EAD18 /* command.h */, - 65B364E6121C261F003EAD18 /* command_p.h */, - 65B364E7121C261F003EAD18 /* commandsfile.cpp */, - 65B364E8121C261F003EAD18 /* commandsfile.h */, - ); - path = actionmanager; - sourceTree = ""; - }; - 65B364FA121C261F003EAD18 /* dialogs */ = { - isa = PBXGroup; - children = ( - 65B364FB121C261F003EAD18 /* ioptionspage.cpp */, - 65B364FC121C261F003EAD18 /* ioptionspage.h */, - 65B364FD121C261F003EAD18 /* iwizard.cpp */, - 65B364FE121C261F003EAD18 /* iwizard.h */, - 65B364FF121C261F003EAD18 /* settingsdialog.cpp */, - 65B36500121C261F003EAD18 /* settingsdialog.h */, - 65B36501121C261F003EAD18 /* settingsdialog.ui */, - 65B36502121C261F003EAD18 /* shortcutsettings.cpp */, - 65B36503121C261F003EAD18 /* shortcutsettings.h */, - 65B36504121C261F003EAD18 /* shortcutsettings.ui */, - ); - path = dialogs; - sourceTree = ""; - }; - 65B36517121C261F003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B36518121C261F003EAD18 /* clean_pane_small.png */, - 65B36519121C261F003EAD18 /* clear.png */, - 65B3651A121C261F003EAD18 /* closebutton.png */, - 65B3651B121C261F003EAD18 /* darkclosebutton.png */, - 65B3651C121C261F003EAD18 /* dir.png */, - 65B3651D121C261F003EAD18 /* editcopy.png */, - 65B3651E121C261F003EAD18 /* editcut.png */, - 65B3651F121C261F003EAD18 /* editpaste.png */, - 65B36520121C261F003EAD18 /* empty14.png */, - 65B36521121C261F003EAD18 /* exiticon.png */, - 65B36522121C261F003EAD18 /* extension.png */, - 65B36523121C261F003EAD18 /* fancytoolbutton.svg */, - 65B36524121C261F003EAD18 /* filenew.png */, - 65B36525121C261F003EAD18 /* fileopen.png */, - 65B36526121C261F003EAD18 /* filesave.png */, - 65B36527121C261F003EAD18 /* find.png */, - 65B36528121C261F003EAD18 /* findnext.png */, - 65B36529121C261F003EAD18 /* helpicon.png */, - 65B3652A121C261F003EAD18 /* inputfield.png */, - 65B3652B121C261F003EAD18 /* inputfield_disabled.png */, - 65B3652C121C261F003EAD18 /* linkicon.png */, - 65B3652D121C261F003EAD18 /* locked.png */, - 65B3652E121C261F003EAD18 /* magnifier.png */, - 65B3652F121C261F003EAD18 /* minus.png */, - 65B36530121C261F003EAD18 /* mode_Debug.png */, - 65B36531121C261F003EAD18 /* mode_Edit.png */, - 65B36532121C261F003EAD18 /* mode_Output.png */, - 65B36533121C261F003EAD18 /* mode_Project.png */, - 65B36534121C261F003EAD18 /* mode_Reference.png */, - 65B36535121C261F003EAD18 /* next.png */, - 65B36536121C261F003EAD18 /* openpilot_logo_128.png */, - 65B36537121C261F003EAD18 /* openpilot_logo_256.png */, - 65B36538121C261F003EAD18 /* openpilot_logo_32.png */, - 65B36539121C261F003EAD18 /* openpilot_logo_64.png */, - 65B3653A121C261F003EAD18 /* openpiloticon.png */, - 65B3653B121C261F003EAD18 /* optionsicon.png */, - 65B3653C121C261F003EAD18 /* panel_button.png */, - 65B3653D121C261F003EAD18 /* panel_button_checked.png */, - 65B3653E121C261F003EAD18 /* panel_button_checked_hover.png */, - 65B3653F121C261F003EAD18 /* panel_button_hover.png */, - 65B36540121C261F003EAD18 /* panel_button_pressed.png */, - 65B36541121C261F003EAD18 /* pluginicon.png */, - 65B36542121C261F003EAD18 /* plus.png */, - 65B36543121C261F003EAD18 /* prev.png */, - 65B36544121C261F003EAD18 /* pushbutton.png */, - 65B36545121C261F003EAD18 /* pushbutton_hover.png */, - 65B36546121C261F003EAD18 /* pushbutton_pressed.png */, - 65B36547121C261F003EAD18 /* qtcreator_logo_32.png */, - 65B36548121C261F003EAD18 /* qtwatermark.png */, - 65B36549121C261F003EAD18 /* redo.png */, - 65B3654A121C261F003EAD18 /* replace.png */, - 65B3654B121C261F003EAD18 /* reset.png */, - 65B3654C121C261F003EAD18 /* sidebaricon.png */, - 65B3654D121C261F003EAD18 /* splitbutton_horizontal.png */, - 65B3654E121C261F003EAD18 /* statusbar.png */, - 65B3654F121C261F003EAD18 /* undo.png */, - 65B36550121C261F003EAD18 /* unknownfile.png */, - 65B36551121C261F003EAD18 /* unlocked.png */, - ); - path = images; - sourceTree = ""; - }; - 65B3657C121C261F003EAD18 /* uavgadgetmanager */ = { - isa = PBXGroup; - children = ( - 65B3657D121C261F003EAD18 /* uavgadgetmanager.cpp */, - 65B3657E121C261F003EAD18 /* uavgadgetmanager.h */, - 65B3657F121C261F003EAD18 /* uavgadgetview.cpp */, - 65B36580121C261F003EAD18 /* uavgadgetview.h */, - ); - path = uavgadgetmanager; - sourceTree = ""; - }; - 65B36591121C261F003EAD18 /* dial */ = { - isa = PBXGroup; - children = ( - 65B36592121C261F003EAD18 /* dial.pro */, - 65B36593121C261F003EAD18 /* dial.qrc */, - 65B36594121C261F003EAD18 /* dial_dependencies.pri */, - 65B36595121C261F003EAD18 /* dialgadget.cpp */, - 65B36596121C261F003EAD18 /* dialgadget.h */, - 65B36597121C261F003EAD18 /* DialGadget.pluginspec */, - 65B36598121C261F003EAD18 /* dialgadgetconfiguration.cpp */, - 65B36599121C261F003EAD18 /* dialgadgetconfiguration.h */, - 65B3659A121C261F003EAD18 /* dialgadgetfactory.cpp */, - 65B3659B121C261F003EAD18 /* dialgadgetfactory.h */, - 65B3659C121C261F003EAD18 /* dialgadgetoptionspage.cpp */, - 65B3659D121C261F003EAD18 /* dialgadgetoptionspage.h */, - 65B3659E121C261F003EAD18 /* dialgadgetoptionspage.ui */, - 65B3659F121C261F003EAD18 /* dialgadgetwidget.cpp */, - 65B365A0121C261F003EAD18 /* dialgadgetwidget.h */, - 65B365A1121C261F003EAD18 /* dialplugin.cpp */, - 65B365A2121C261F003EAD18 /* dialplugin.h */, - 65B365A3121C261F003EAD18 /* images */, - ); - path = dial; - sourceTree = ""; - }; - 65B365A3121C261F003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B365A4121C261F003EAD18 /* empty.svg */, - ); - path = images; - sourceTree = ""; - }; - 65B365A5121C261F003EAD18 /* donothing */ = { - isa = PBXGroup; - children = ( - 65B365A6121C261F003EAD18 /* DoNothing.pluginspec */, - 65B365A7121C261F003EAD18 /* donothing.pro */, - 65B365A8121C261F003EAD18 /* donothingplugin.cpp */, - 65B365A9121C261F003EAD18 /* donothingplugin.h */, - ); - path = donothing; - sourceTree = ""; - }; - 65B365AA121C261F003EAD18 /* emptygadget */ = { - isa = PBXGroup; - children = ( - 65B365AB121C261F003EAD18 /* emptygadget.cpp */, - 65B365AC121C261F003EAD18 /* emptygadget.h */, - 65B365AD121C261F003EAD18 /* EmptyGadget.pluginspec */, - 65B365AE121C261F003EAD18 /* emptygadget.pro */, - 65B365AF121C261F003EAD18 /* emptygadgetfactory.cpp */, - 65B365B0121C261F003EAD18 /* emptygadgetfactory.h */, - 65B365B1121C261F003EAD18 /* emptygadgetwidget.cpp */, - 65B365B2121C261F003EAD18 /* emptygadgetwidget.h */, - 65B365B3121C261F003EAD18 /* emptyplugin.cpp */, - 65B365B4121C261F003EAD18 /* emptyplugin.h */, - ); - path = emptygadget; - sourceTree = ""; - }; - 65B365B5121C261F003EAD18 /* gcscontrol */ = { - isa = PBXGroup; - children = ( - 65B365B6121C261F003EAD18 /* GCSControl.pluginspec */, - 65B365B7121C261F003EAD18 /* gcscontrol.pro */, - 65B365B8121C261F003EAD18 /* gcscontrol.qrc */, - 65B365B9121C261F003EAD18 /* gcscontrol.ui */, - 65B365BA121C261F003EAD18 /* gcscontrolgadget.cpp */, - 65B365BB121C261F003EAD18 /* gcscontrolgadget.h */, - 65B365BC121C261F003EAD18 /* gcscontrolgadgetfactory.cpp */, - 65B365BD121C261F003EAD18 /* gcscontrolgadgetfactory.h */, - 65B365BE121C261F003EAD18 /* gcscontrolgadgetwidget.cpp */, - 65B365BF121C261F003EAD18 /* gcscontrolgadgetwidget.h */, - 65B365C0121C261F003EAD18 /* gcscontrolplugin.cpp */, - 65B365C1121C261F003EAD18 /* gcscontrolplugin.h */, - 65B365C2121C261F003EAD18 /* gcsonctrolgadgetwidget.h */, - 65B365C3121C261F003EAD18 /* images */, - 65B365C5121C261F003EAD18 /* joystickcontrol.cpp */, - 65B365C6121C261F003EAD18 /* joystickcontrol.h */, - ); - path = gcscontrol; - sourceTree = ""; - }; - 65B365C3121C261F003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B365C4121C261F003EAD18 /* joystick.svg */, - ); - path = images; - sourceTree = ""; - }; - 65B365C7121C261F003EAD18 /* gpsdisplay */ = { - isa = PBXGroup; - children = ( - 65B365C8121C261F003EAD18 /* buffer.cpp */, - 65B365C9121C261F003EAD18 /* buffer.h */, - 65B365CA121C261F003EAD18 /* gpsdisplay.pro */, - 65B365CB121C261F003EAD18 /* gpsdisplay_dependencies.pri */, - 65B365CC121C261F003EAD18 /* gpsdisplaygadget.cpp */, - 65B365CD121C261F003EAD18 /* gpsdisplaygadget.h */, - 65B365CE121C261F003EAD18 /* GpsDisplayGadget.pluginspec */, - 65B365CF121C261F003EAD18 /* gpsdisplaygadgetconfiguration.cpp */, - 65B365D0121C261F003EAD18 /* gpsdisplaygadgetconfiguration.h */, - 65B365D1121C261F003EAD18 /* gpsdisplaygadgetfactory.cpp */, - 65B365D2121C261F003EAD18 /* gpsdisplaygadgetfactory.h */, - 65B365D3121C261F003EAD18 /* gpsdisplaygadgetoptionspage.cpp */, - 65B365D4121C261F003EAD18 /* gpsdisplaygadgetoptionspage.h */, - 65B365D5121C261F003EAD18 /* gpsdisplaygadgetoptionspage.ui */, - 65B365D6121C261F003EAD18 /* gpsdisplayplugin.cpp */, - 65B365D7121C261F003EAD18 /* gpsdisplayplugin.h */, - 65B365D8121C261F003EAD18 /* gpsdisplaythread.cpp */, - 65B365D9121C261F003EAD18 /* gpsdisplaythread.h */, - 65B365DA121C261F003EAD18 /* gpsdisplaywidget.cpp */, - 65B365DB121C261F003EAD18 /* gpsdisplaywidget.h */, - 65B365DC121C261F003EAD18 /* gpsdisplaywidget.ui */, - 65B365DD121C261F003EAD18 /* images */, - 65B365E0121C261F003EAD18 /* nmeaparser.cpp */, - 65B365E1121C261F003EAD18 /* nmeaparser.h */, - 65B365E2121C261F003EAD18 /* widgetresources.qrc */, - ); - path = gpsdisplay; - sourceTree = ""; - }; - 65B365DD121C261F003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B365DE121C261F003EAD18 /* flatEarth.png */, - 65B365DF121C261F003EAD18 /* gpsEarth.svg */, - ); - path = images; - sourceTree = ""; - }; - 65B365E3121C261F003EAD18 /* hitl */ = { - isa = PBXGroup; - children = ( - 65B365E4121C261F003EAD18 /* flightgearbridge.cpp */, - 65B365E5121C2620003EAD18 /* flightgearbridge.h */, - 65B365E6121C2620003EAD18 /* hitl.cpp */, - 65B365E7121C2620003EAD18 /* hitl.h */, - 65B365E8121C2620003EAD18 /* HITL.pluginspec */, - 65B365E9121C2620003EAD18 /* hitl.pro */, - 65B365EA121C2620003EAD18 /* hitl_dependencies.pri */, - 65B365EB121C2620003EAD18 /* hitlconfiguration.cpp */, - 65B365EC121C2620003EAD18 /* hitlconfiguration.h */, - 65B365ED121C2620003EAD18 /* hitlfactory.cpp */, - 65B365EE121C2620003EAD18 /* hitlfactory.h */, - 65B365EF121C2620003EAD18 /* hitloptionspage.cpp */, - 65B365F0121C2620003EAD18 /* hitloptionspage.h */, - 65B365F1121C2620003EAD18 /* hitloptionspage.ui */, - 65B365F2121C2620003EAD18 /* hitlplugin.cpp */, - 65B365F3121C2620003EAD18 /* hitlplugin.h */, - 65B365F4121C2620003EAD18 /* hitlresources.qrc */, - 65B365F5121C2620003EAD18 /* hitlwidget.cpp */, - 65B365F6121C2620003EAD18 /* hitlwidget.h */, - 65B365F7121C2620003EAD18 /* hitlwidget.ui */, - 65B365F8121C2620003EAD18 /* opfgprotocol.xml */, - ); - path = hitl; - sourceTree = ""; - }; - 65B365F9121C2620003EAD18 /* hitlil2 */ = { - isa = PBXGroup; - children = ( - 65B365FA121C2620003EAD18 /* hitlil2.cpp */, - 65B365FB121C2620003EAD18 /* hitlil2.h */, - 65B365FC121C2620003EAD18 /* HITLIL2.pluginspec */, - 65B365FD121C2620003EAD18 /* hitlil2.pro */, - 65B365FE121C2620003EAD18 /* hitlil2_dependencies.pri */, - 65B365FF121C2620003EAD18 /* hitlil2configuration.cpp */, - 65B36600121C2620003EAD18 /* hitlil2configuration.h */, - 65B36601121C2620003EAD18 /* hitlil2factory.cpp */, - 65B36602121C2620003EAD18 /* hitlil2factory.h */, - 65B36603121C2620003EAD18 /* hitlil2optionspage.cpp */, - 65B36604121C2620003EAD18 /* hitlil2optionspage.h */, - 65B36605121C2620003EAD18 /* hitlil2optionspage.ui */, - 65B36606121C2620003EAD18 /* hitlil2plugin.cpp */, - 65B36607121C2620003EAD18 /* hitlil2plugin.h */, - 65B36608121C2620003EAD18 /* hitlil2widget.cpp */, - 65B36609121C2620003EAD18 /* hitlil2widget.h */, - 65B3660A121C2620003EAD18 /* hitlil2widget.ui */, - 65B3660B121C2620003EAD18 /* il2bridge.cpp */, - 65B3660C121C2620003EAD18 /* il2bridge.h */, - ); - path = hitlil2; - sourceTree = ""; - }; - 65B3660D121C2620003EAD18 /* importexport */ = { - isa = PBXGroup; - children = ( - 65B3660E121C2620003EAD18 /* importexport.pro */, - 65B3660F121C2620003EAD18 /* importexport_dependencies.pri */, - 65B36610121C2620003EAD18 /* importexport_global.h */, - 65B36611121C2620003EAD18 /* importexportgadget.cpp */, - 65B36612121C2620003EAD18 /* importexportgadget.h */, - 65B36613121C2620003EAD18 /* ImportExportGadget.pluginspec */, - 65B36614121C2620003EAD18 /* importexportgadgetconfiguration.cpp */, - 65B36615121C2620003EAD18 /* importexportgadgetconfiguration.h */, - 65B36616121C2620003EAD18 /* importexportgadgetfactory.cpp */, - 65B36617121C2620003EAD18 /* importexportgadgetfactory.h */, - 65B36618121C2620003EAD18 /* importexportgadgetoptionspage.cpp */, - 65B36619121C2620003EAD18 /* importexportgadgetoptionspage.h */, - 65B3661A121C2620003EAD18 /* importexportgadgetoptionspage.ui */, - 65B3661B121C2620003EAD18 /* importexportgadgetwidget.cpp */, - 65B3661C121C2620003EAD18 /* importexportgadgetwidget.h */, - 65B3661D121C2620003EAD18 /* importexportgadgetwidget.ui */, - 65B3661E121C2620003EAD18 /* importexportplugin.cpp */, - 65B3661F121C2620003EAD18 /* importexportplugin.h */, - ); - path = importexport; - sourceTree = ""; - }; - 65B36620121C2620003EAD18 /* ipconnection */ = { - isa = PBXGroup; - children = ( - 65B36621121C2620003EAD18 /* IPconnection.pluginspec */, - 65B36622121C2620003EAD18 /* ipconnection.pri */, - 65B36623121C2620003EAD18 /* ipconnection.pro */, - 65B36624121C2620003EAD18 /* ipconnection_dependencies.pri */, - 65B36625121C2620003EAD18 /* ipconnection_global.h */, - 65B36626121C2620003EAD18 /* ipconnectionconfiguration.cpp */, - 65B36627121C2620003EAD18 /* ipconnectionconfiguration.h */, - 65B36628121C2620003EAD18 /* ipconnectionoptionspage.cpp */, - 65B36629121C2620003EAD18 /* ipconnectionoptionspage.h */, - 65B3662A121C2620003EAD18 /* ipconnectionoptionspage.ui */, - 65B3662B121C2620003EAD18 /* ipconnectionplugin.cpp */, - 65B3662C121C2620003EAD18 /* ipconnectionplugin.h */, - ); - path = ipconnection; - sourceTree = ""; - }; - 65B3662D121C2620003EAD18 /* lineardial */ = { - isa = PBXGroup; - children = ( - 65B3662E121C2620003EAD18 /* images */, - 65B36630121C2620003EAD18 /* lineardial.pro */, - 65B36631121C2620003EAD18 /* lineardial.qrc */, - 65B36632121C2620003EAD18 /* lineardial_dependencies.pri */, - 65B36633121C2620003EAD18 /* lineardialgadget.cpp */, - 65B36634121C2620003EAD18 /* lineardialgadget.h */, - 65B36635121C2620003EAD18 /* LineardialGadget.pluginspec */, - 65B36636121C2620003EAD18 /* lineardialgadgetconfiguration.cpp */, - 65B36637121C2620003EAD18 /* lineardialgadgetconfiguration.h */, - 65B36638121C2620003EAD18 /* lineardialgadgetfactory.cpp */, - 65B36639121C2620003EAD18 /* lineardialgadgetfactory.h */, - 65B3663A121C2620003EAD18 /* lineardialgadgetoptionspage.cpp */, - 65B3663B121C2620003EAD18 /* lineardialgadgetoptionspage.h */, - 65B3663C121C2620003EAD18 /* lineardialgadgetoptionspage.ui */, - 65B3663D121C2620003EAD18 /* lineardialgadgetwidget.cpp */, - 65B3663E121C2620003EAD18 /* lineardialgadgetwidget.h */, - 65B3663F121C2620003EAD18 /* lineardialplugin.cpp */, - 65B36640121C2620003EAD18 /* lineardialplugin.h */, - ); - path = lineardial; - sourceTree = ""; - }; - 65B3662E121C2620003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B3662F121C2620003EAD18 /* empty.svg */, - ); - path = images; - sourceTree = ""; - }; - 65B36641121C2620003EAD18 /* modelview */ = { - isa = PBXGroup; - children = ( - 65B36642121C2620003EAD18 /* modelview.pro */, - 65B36643121C2620003EAD18 /* modelview_dependencies.pri */, - 65B36644121C2620003EAD18 /* modelviewgadget.cpp */, - 65B36645121C2620003EAD18 /* modelviewgadget.h */, - 65B36646121C2620003EAD18 /* ModelViewGadget.pluginspec */, - 65B36647121C2620003EAD18 /* modelviewgadgetconfiguration.cpp */, - 65B36648121C2620003EAD18 /* modelviewgadgetconfiguration.h */, - 65B36649121C2620003EAD18 /* modelviewgadgetfactory.cpp */, - 65B3664A121C2620003EAD18 /* modelviewgadgetfactory.h */, - 65B3664B121C2620003EAD18 /* modelviewgadgetoptionspage.cpp */, - 65B3664C121C2620003EAD18 /* modelviewgadgetoptionspage.h */, - 65B3664D121C2620003EAD18 /* modelviewgadgetwidget.cpp */, - 65B3664E121C2620003EAD18 /* modelviewgadgetwidget.h */, - 65B3664F121C2620003EAD18 /* modelviewoptionspage.ui */, - 65B36650121C2620003EAD18 /* modelviewplugin.cpp */, - 65B36651121C2620003EAD18 /* modelviewplugin.h */, - ); - path = modelview; - sourceTree = ""; - }; - 65B36652121C2620003EAD18 /* notify */ = { - isa = PBXGroup; - children = ( - 65B36653121C2620003EAD18 /* images */, - 65B3665A121C2620003EAD18 /* notify.pro */, - 65B3665B121C2620003EAD18 /* notifyitemdelegate.cpp */, - 65B3665C121C2620003EAD18 /* notifyitemdelegate.h */, - 65B3665D121C2620003EAD18 /* notifyplugin.cpp */, - 65B3665E121C2620003EAD18 /* notifyplugin.h */, - 65B3665F121C2620003EAD18 /* NotifyPlugin.pluginspec */, - 65B36660121C2620003EAD18 /* notifyplugin_dependencies.pri */, - 65B36661121C2620003EAD18 /* notifypluginconfiguration.cpp */, - 65B36662121C2620003EAD18 /* notifypluginconfiguration.h */, - 65B36663121C2620003EAD18 /* notifypluginfactory.cpp */, - 65B36664121C2620003EAD18 /* notifypluginfactory.h */, - 65B36665121C2620003EAD18 /* notifyplugingadget.h */, - 65B36666121C2620003EAD18 /* notifypluginoptionspage.cpp */, - 65B36667121C2620003EAD18 /* notifypluginoptionspage.h */, - 65B36668121C2620003EAD18 /* notifypluginoptionspage.ui */, - 65B36669121C2620003EAD18 /* notifytablemodel.cpp */, - 65B3666A121C2620003EAD18 /* notifytablemodel.h */, - 65B3666B121C2620003EAD18 /* res.qrc */, - ); - path = notify; - sourceTree = ""; - }; - 65B36653121C2620003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B36654121C2620003EAD18 /* add.png */, - 65B36655121C2620003EAD18 /* delete.png */, - 65B36656121C2620003EAD18 /* modify.png */, - 65B36657121C2620003EAD18 /* play.png */, - 65B36658121C2620003EAD18 /* play2.png */, - 65B36659121C2620003EAD18 /* stop.png */, - ); - path = images; - sourceTree = ""; - }; - 65B3666C121C2620003EAD18 /* opmap */ = { - isa = PBXGroup; - children = ( - 65B3666D121C2620003EAD18 /* images */, - 65B3668A121C2620003EAD18 /* opmap.pro */, - 65B3668B121C2620003EAD18 /* opmap.qrc */, - 65B3668C121C2620003EAD18 /* opmap_edit_waypoint_dialog.cpp */, - 65B3668D121C2620003EAD18 /* opmap_edit_waypoint_dialog.h */, - 65B3668E121C2620003EAD18 /* opmap_edit_waypoint_dialog.ui */, - 65B3668F121C2620003EAD18 /* opmap_overlay_widget.cpp */, - 65B36690121C2620003EAD18 /* opmap_overlay_widget.h */, - 65B36691121C2620003EAD18 /* opmap_overlay_widget.ui */, - 65B36692121C2620003EAD18 /* opmap_statusbar_widget.cpp */, - 65B36693121C2620003EAD18 /* opmap_statusbar_widget.h */, - 65B36694121C2620003EAD18 /* opmap_statusbar_widget.ui */, - 65B36695121C2620003EAD18 /* opmap_waypointeditor_dialog.cpp */, - 65B36696121C2620003EAD18 /* opmap_waypointeditor_dialog.h */, - 65B36697121C2620003EAD18 /* opmap_waypointeditor_dialog.ui */, - 65B36698121C2620003EAD18 /* opmap_widget.ui */, - 65B36699121C2620003EAD18 /* opmap_zoom_slider_widget.cpp */, - 65B3669A121C2620003EAD18 /* opmap_zoom_slider_widget.h */, - 65B3669B121C2620003EAD18 /* opmap_zoom_slider_widget.ui */, - 65B3669C121C2620003EAD18 /* opmapgadget.cpp */, - 65B3669D121C2620003EAD18 /* opmapgadget.h */, - 65B3669E121C2620003EAD18 /* OPMapGadget.pluginspec */, - 65B3669F121C2620003EAD18 /* opmapgadgetconfiguration.cpp */, - 65B366A0121C2620003EAD18 /* opmapgadgetconfiguration.h */, - 65B366A1121C2620003EAD18 /* opmapgadgetfactory.cpp */, - 65B366A2121C2620003EAD18 /* opmapgadgetfactory.h */, - 65B366A3121C2620003EAD18 /* opmapgadgetoptionspage.cpp */, - 65B366A4121C2620003EAD18 /* opmapgadgetoptionspage.h */, - 65B366A5121C2620003EAD18 /* opmapgadgetoptionspage.ui */, - 65B366A6121C2620003EAD18 /* opmapgadgetwidget.cpp */, - 65B366A7121C2620003EAD18 /* opmapgadgetwidget.h */, - 65B366A8121C2620003EAD18 /* opmapplugin.cpp */, - 65B366A9121C2620003EAD18 /* opmapplugin.h */, - ); - path = opmap; - sourceTree = ""; - }; - 65B3666D121C2620003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B3666E121C2620003EAD18 /* Blank.psd */, - 65B3666F121C2620003EAD18 /* Blank_Pressed.psd */, - 65B36670121C2620003EAD18 /* button_bar.png */, - 65B36671121C2620003EAD18 /* circle.png */, - 65B36672121C2620003EAD18 /* combobox_down_arrow.png */, - 65B36673121C2620003EAD18 /* gcs.png */, - 65B36674121C2620003EAD18 /* go.png */, - 65B36675121C2620003EAD18 /* hold.png */, - 65B36676121C2620003EAD18 /* home.png */, - 65B36677121C2620003EAD18 /* hover.png */, - 65B36678121C2620003EAD18 /* left_but.png */, - 65B36679121C2620003EAD18 /* minus.png */, - 65B3667A121C2620003EAD18 /* minus2.png */, - 65B3667B121C2620003EAD18 /* next_waypoint.png */, - 65B3667C121C2620003EAD18 /* ok.png */, - 65B3667D121C2620003EAD18 /* pause.png */, - 65B3667E121C2620003EAD18 /* plus.png */, - 65B3667F121C2620003EAD18 /* plus2.png */, - 65B36680121C2620003EAD18 /* prev_waypoint.png */, - 65B36681121C2620003EAD18 /* right_but.png */, - 65B36682121C2620003EAD18 /* stop.png */, - 65B36683121C2620003EAD18 /* uav.png */, - 65B36684121C2620003EAD18 /* uav_heading.png */, - 65B36685121C2620003EAD18 /* uav_trail.png */, - 65B36686121C2620003EAD18 /* uav_trail_clear.png */, - 65B36687121C2620003EAD18 /* waypoint.png */, - 65B36688121C2620003EAD18 /* waypoint_marker1.png */, - 65B36689121C2620003EAD18 /* waypoint_marker2.png */, - ); - path = images; - sourceTree = ""; - }; - 65B366AA121C2620003EAD18 /* pfd */ = { - isa = PBXGroup; - children = ( - 65B366AB121C2620003EAD18 /* images */, - 65B366AD121C2620003EAD18 /* pfd.pro */, - 65B366AE121C2620003EAD18 /* pfd.qrc */, - 65B366AF121C2620003EAD18 /* pfd_dependencies.pri */, - 65B366B0121C2620003EAD18 /* pfdgadget.cpp */, - 65B366B1121C2620003EAD18 /* pfdgadget.h */, - 65B366B2121C2620003EAD18 /* PFDGadget.pluginspec */, - 65B366B3121C2620003EAD18 /* pfdgadgetconfiguration.cpp */, - 65B366B4121C2620003EAD18 /* pfdgadgetconfiguration.h */, - 65B366B5121C2620003EAD18 /* pfdgadgetfactory.cpp */, - 65B366B6121C2620003EAD18 /* pfdgadgetfactory.h */, - 65B366B7121C2620003EAD18 /* pfdgadgetoptionspage.cpp */, - 65B366B8121C2620003EAD18 /* pfdgadgetoptionspage.h */, - 65B366B9121C2620003EAD18 /* pfdgadgetoptionspage.ui */, - 65B366BA121C2620003EAD18 /* pfdgadgetwidget.cpp */, - 65B366BB121C2620003EAD18 /* pfdgadgetwidget.h */, - 65B366BC121C2620003EAD18 /* pfdplugin.cpp */, - 65B366BD121C2620003EAD18 /* pfdplugin.h */, - ); - path = pfd; - sourceTree = ""; - }; - 65B366AB121C2620003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B366AC121C2620003EAD18 /* pfd-default.svg */, - ); - path = images; - sourceTree = ""; - }; - 65B366BF121C2620003EAD18 /* rawhid */ = { - isa = PBXGroup; - children = ( - 65B366C0121C2620003EAD18 /* pjrc_rawhid.h */, - 65B366C1121C2620003EAD18 /* pjrc_rawhid_mac.cpp */, - 65B366C2121C2620003EAD18 /* pjrc_rawhid_unix.cpp */, - 65B366C3121C2620003EAD18 /* pjrc_rawhid_win.cpp */, - 65B366C4121C2620003EAD18 /* rawhid.cpp */, - 65B366C5121C2620003EAD18 /* rawhid.h */, - 65B366C6121C2620003EAD18 /* RawHID.pluginspec */, - 65B366C7121C2620003EAD18 /* rawhid.pri */, - 65B366C8121C2620003EAD18 /* rawhid.pro */, - 65B366C9121C2620003EAD18 /* rawhid_const.h */, - 65B366CA121C2620003EAD18 /* rawhid_dependencies.pri */, - 65B366CB121C2620003EAD18 /* rawhid_global.h */, - 65B366CC121C2620003EAD18 /* rawhidplugin.cpp */, - 65B366CD121C2620003EAD18 /* rawhidplugin.h */, - ); - path = rawhid; - sourceTree = ""; - }; - 65B366CE121C2620003EAD18 /* scope */ = { - isa = PBXGroup; - children = ( - 65B366CF121C2620003EAD18 /* plotdata.cpp */, - 65B366D0121C2620003EAD18 /* plotdata.h */, - 65B366D1121C2620003EAD18 /* scope.pro */, - 65B366D2121C2620003EAD18 /* scopegadget.cpp */, - 65B366D3121C2620003EAD18 /* scopegadget.h */, - 65B366D4121C2620003EAD18 /* ScopeGadget.pluginspec */, - 65B366D5121C2620003EAD18 /* scopegadgetconfiguration.cpp */, - 65B366D6121C2620003EAD18 /* scopegadgetconfiguration.h */, - 65B366D7121C2620003EAD18 /* scopegadgetfactory.cpp */, - 65B366D8121C2620003EAD18 /* scopegadgetfactory.h */, - 65B366D9121C2620003EAD18 /* scopegadgetoptionspage.cpp */, - 65B366DA121C2620003EAD18 /* scopegadgetoptionspage.h */, - 65B366DB121C2620003EAD18 /* scopegadgetoptionspage.ui */, - 65B366DC121C2620003EAD18 /* scopegadgetwidget.cpp */, - 65B366DD121C2620003EAD18 /* scopegadgetwidget.h */, - 65B366DE121C2620003EAD18 /* scopeplugin.cpp */, - 65B366DF121C2620003EAD18 /* scopeplugin.h */, - ); - path = scope; - sourceTree = ""; - }; - 65B366E0121C2620003EAD18 /* serialconnection */ = { - isa = PBXGroup; - children = ( - 65B366E1121C2620003EAD18 /* Serial.pluginspec */, - 65B366E2121C2620003EAD18 /* serial.pri */, - 65B366E3121C2620003EAD18 /* serial_dependencies.pri */, - 65B366E4121C2620003EAD18 /* serial_global.h */, - 65B366E5121C2620003EAD18 /* serialconnection.pro */, - 65B366E6121C2620003EAD18 /* serialplugin.cpp */, - 65B366E7121C2620003EAD18 /* serialplugin.h */, - ); - path = serialconnection; - sourceTree = ""; - }; - 65B366E8121C2620003EAD18 /* systemhealth */ = { - isa = PBXGroup; - children = ( - 65B366E9121C2620003EAD18 /* systemhealth.pro */, - 65B366EA121C2620003EAD18 /* systemhealth_dependencies.pri */, - 65B366EB121C2620003EAD18 /* systemhealthgadget.cpp */, - 65B366EC121C2620003EAD18 /* systemhealthgadget.h */, - 65B366ED121C2620003EAD18 /* SystemHealthGadget.pluginspec */, - 65B366EE121C2620003EAD18 /* systemhealthgadgetconfiguration.cpp */, - 65B366EF121C2620003EAD18 /* systemhealthgadgetconfiguration.h */, - 65B366F0121C2620003EAD18 /* systemhealthgadgetfactory.cpp */, - 65B366F1121C2620003EAD18 /* systemhealthgadgetfactory.h */, - 65B366F2121C2620003EAD18 /* systemhealthgadgetoptionspage.cpp */, - 65B366F3121C2620003EAD18 /* systemhealthgadgetoptionspage.h */, - 65B366F4121C2620003EAD18 /* systemhealthgadgetoptionspage.ui */, - 65B366F5121C2620003EAD18 /* systemhealthgadgetwidget.cpp */, - 65B366F6121C2620003EAD18 /* systemhealthgadgetwidget.h */, - 65B366F7121C2620003EAD18 /* systemhealthplugin.cpp */, - 65B366F8121C2620003EAD18 /* systemhealthplugin.h */, - ); - path = systemhealth; - sourceTree = ""; - }; - 65B366F9121C2620003EAD18 /* uavobjectbrowser */ = { - isa = PBXGroup; - children = ( - 65B366FA121C2620003EAD18 /* browseritemdelegate.cpp */, - 65B366FB121C2620003EAD18 /* browseritemdelegate.h */, - 65B366FC121C2620003EAD18 /* browserplugin.cpp */, - 65B366FD121C2620003EAD18 /* browserplugin.h */, - 65B366FE121C2620003EAD18 /* fieldtreeitem.cpp */, - 65B366FF121C2620003EAD18 /* fieldtreeitem.h */, - 65B36700121C2620003EAD18 /* treeitem.cpp */, - 65B36701121C2620003EAD18 /* treeitem.h */, - 65B36702121C2620003EAD18 /* uavobjectbrowser.cpp */, - 65B36703121C2620003EAD18 /* uavobjectbrowser.h */, - 65B36704121C2620003EAD18 /* UAVObjectBrowser.pluginspec */, - 65B36705121C2620003EAD18 /* uavobjectbrowser.pro */, - 65B36706121C2620003EAD18 /* uavobjectbrowser.ui */, - 65B36707121C2620003EAD18 /* uavobjectbrowser_dependencies.pri */, - 65B36708121C2620003EAD18 /* uavobjectbrowserconfiguration.cpp */, - 65B36709121C2620003EAD18 /* uavobjectbrowserconfiguration.h */, - 65B3670A121C2620003EAD18 /* uavobjectbrowserfactory.cpp */, - 65B3670B121C2620003EAD18 /* uavobjectbrowserfactory.h */, - 65B3670C121C2620003EAD18 /* uavobjectbrowseroptionspage.cpp */, - 65B3670D121C2620003EAD18 /* uavobjectbrowseroptionspage.h */, - 65B3670E121C2620003EAD18 /* uavobjectbrowseroptionspage.ui */, - 65B3670F121C2620003EAD18 /* uavobjectbrowserwidget.cpp */, - 65B36710121C2620003EAD18 /* uavobjectbrowserwidget.h */, - 65B36711121C2620003EAD18 /* uavobjecttreemodel.cpp */, - 65B36712121C2620003EAD18 /* uavobjecttreemodel.h */, - ); - path = uavobjectbrowser; - sourceTree = ""; - }; - 65B36713121C2620003EAD18 /* uavobjects */ = { - isa = PBXGroup; - children = ( - 65B36714121C2620003EAD18 /* actuatorcommand.cpp */, - 65B36715121C2620003EAD18 /* actuatorcommand.h */, - 65B36716121C2620003EAD18 /* actuatorcommand.py */, - 65B36717121C2620003EAD18 /* actuatordesired.cpp */, - 65B36718121C2620003EAD18 /* actuatordesired.h */, - 65B36719121C2620003EAD18 /* actuatordesired.py */, - 65B3671A121C2620003EAD18 /* actuatorsettings.cpp */, - 65B3671B121C2620003EAD18 /* actuatorsettings.h */, - 65B3671C121C2620003EAD18 /* actuatorsettings.py */, - 65B3671D121C2620003EAD18 /* ahrsstatus.cpp */, - 65B3671E121C2620003EAD18 /* ahrsstatus.h */, - 65B3671F121C2620003EAD18 /* ahrsstatus.py */, - 65B36720121C2620003EAD18 /* altitudeactual.cpp */, - 65B36721121C2620003EAD18 /* altitudeactual.h */, - 65B36722121C2620003EAD18 /* altitudeactual.py */, - 65B36723121C2620003EAD18 /* attitudeactual.cpp */, - 65B36724121C2620003EAD18 /* attitudeactual.h */, - 65B36725121C2620003EAD18 /* attitudeactual.py */, - 65B36726121C2620003EAD18 /* attitudedesired.cpp */, - 65B36727121C2620003EAD18 /* attitudedesired.h */, - 65B36728121C2620003EAD18 /* attitudedesired.py */, - 65B36729121C2620003EAD18 /* attituderaw.cpp */, - 65B3672A121C2620003EAD18 /* attituderaw.h */, - 65B3672B121C2620003EAD18 /* attituderaw.py */, - 65B3672C121C2620003EAD18 /* attitudesettings.cpp */, - 65B3672D121C2620003EAD18 /* attitudesettings.h */, - 65B3672E121C2620003EAD18 /* attitudesettings.py */, - 65B3672F121C2620003EAD18 /* exampleobject1.cpp */, - 65B36730121C2620003EAD18 /* exampleobject1.h */, - 65B36731121C2620003EAD18 /* exampleobject1.py */, - 65B36732121C2620003EAD18 /* exampleobject2.cpp */, - 65B36733121C2620003EAD18 /* exampleobject2.h */, - 65B36734121C2620003EAD18 /* exampleobject2.py */, - 65B36735121C2620003EAD18 /* examplesettings.cpp */, - 65B36736121C2620003EAD18 /* examplesettings.h */, - 65B36737121C2620003EAD18 /* examplesettings.py */, - 65B36738121C2620003EAD18 /* flightbatterystate.cpp */, - 65B36739121C2620003EAD18 /* flightbatterystate.h */, - 65B3673A121C2620003EAD18 /* flightbatterystate.py */, - 65B3673B121C2620003EAD18 /* flightsituationactual.cpp */, - 65B3673C121C2620003EAD18 /* flightsituationactual.h */, - 65B3673D121C2620003EAD18 /* flightsituationactual.py */, - 65B3673E121C2620003EAD18 /* flighttelemetrystats.cpp */, - 65B3673F121C2620003EAD18 /* flighttelemetrystats.h */, - 65B36740121C2620003EAD18 /* flighttelemetrystats.py */, - 65B36741121C2620003EAD18 /* gcstelemetrystats.cpp */, - 65B36742121C2620003EAD18 /* gcstelemetrystats.h */, - 65B36743121C2620003EAD18 /* gcstelemetrystats.py */, - 65B36744121C2620003EAD18 /* manualcontrolcommand.cpp */, - 65B36745121C2620003EAD18 /* manualcontrolcommand.h */, - 65B36746121C2620003EAD18 /* manualcontrolcommand.py */, - 65B36747121C2620003EAD18 /* manualcontrolsettings.cpp */, - 65B36748121C2620003EAD18 /* manualcontrolsettings.h */, - 65B36749121C2620003EAD18 /* manualcontrolsettings.py */, - 65B3674A121C2620003EAD18 /* navigationdesired.cpp */, - 65B3674B121C2620003EAD18 /* navigationdesired.h */, - 65B3674C121C2620003EAD18 /* navigationdesired.py */, - 65B3674D121C2620003EAD18 /* navigationsettings.cpp */, - 65B3674E121C2620003EAD18 /* navigationsettings.h */, - 65B3674F121C2620003EAD18 /* navigationsettings.py */, - 65B36750121C2620003EAD18 /* objectpersistence.cpp */, - 65B36751121C2620003EAD18 /* objectpersistence.h */, - 65B36752121C2620003EAD18 /* objectpersistence.py */, - 65B36753121C2620003EAD18 /* positionactual.cpp */, - 65B36754121C2620003EAD18 /* positionactual.h */, - 65B36755121C2620003EAD18 /* positionactual.py */, - 65B36756121C2620003EAD18 /* stabilizationsettings.cpp */, - 65B36757121C2620003EAD18 /* stabilizationsettings.h */, - 65B36758121C2620003EAD18 /* stabilizationsettings.py */, - 65B36759121C2620003EAD18 /* systemalarms.cpp */, - 65B3675A121C2620003EAD18 /* systemalarms.h */, - 65B3675B121C2620003EAD18 /* systemalarms.py */, - 65B3675C121C2620003EAD18 /* systemsettings.cpp */, - 65B3675D121C2620003EAD18 /* systemsettings.h */, - 65B3675E121C2620003EAD18 /* systemsettings.py */, - 65B3675F121C2620003EAD18 /* systemstats.cpp */, - 65B36760121C2620003EAD18 /* systemstats.h */, - 65B36761121C2620003EAD18 /* systemstats.py */, - 65B36762121C2620003EAD18 /* telemetrysettings.cpp */, - 65B36763121C2620003EAD18 /* telemetrysettings.h */, - 65B36764121C2620003EAD18 /* telemetrysettings.py */, - 65B36765121C2620003EAD18 /* tests */, - 65B3676A121C2620003EAD18 /* uavdataobject.cpp */, - 65B3676B121C2620003EAD18 /* uavdataobject.h */, - 65B3676C121C2620003EAD18 /* uavmetaobject.cpp */, - 65B3676D121C2620003EAD18 /* uavmetaobject.h */, - 65B3676E121C2620003EAD18 /* uavobject.cpp */, - 65B3676F121C2620003EAD18 /* uavobject.h */, - 65B36770121C2620003EAD18 /* uavobject.py */, - 65B36771121C2620003EAD18 /* uavobjectfield.cpp */, - 65B36772121C2620003EAD18 /* uavobjectfield.h */, - 65B36773121C2620003EAD18 /* uavobjectmanager.cpp */, - 65B36774121C2620003EAD18 /* uavobjectmanager.h */, - 65B36775121C2620003EAD18 /* UAVObjects.pluginspec */, - 65B36776121C2620003EAD18 /* uavobjects.pri */, - 65B36777121C2620003EAD18 /* uavobjects.pro */, - 65B36778121C2620003EAD18 /* uavobjects_dependencies.pri */, - 65B36779121C2620003EAD18 /* uavobjects_global.h */, - 65B3677A121C2620003EAD18 /* uavobjectsinit.cpp */, - 65B3677B121C2620003EAD18 /* uavobjectsinit.h */, - 65B3677C121C2620003EAD18 /* uavobjectsinittemplate.cpp */, - 65B3677D121C2620003EAD18 /* uavobjectsplugin.cpp */, - 65B3677E121C2620003EAD18 /* uavobjectsplugin.h */, - 65B3677F121C2620003EAD18 /* uavobjecttemplate.cpp */, - 65B36780121C2620003EAD18 /* uavobjecttemplate.h */, - 65B36781121C2620003EAD18 /* uavobjecttemplate.py */, - ); - path = uavobjects; - sourceTree = ""; - }; - 65B36765121C2620003EAD18 /* tests */ = { - isa = PBXGroup; - children = ( - 65B36766121C2620003EAD18 /* main.cpp */, - 65B36767121C2620003EAD18 /* uavobjectstest.cpp */, - 65B36768121C2620003EAD18 /* uavobjectstest.h */, - 65B36769121C2620003EAD18 /* uavobjectstest.pro */, - ); - path = tests; - sourceTree = ""; - }; - 65B36782121C2620003EAD18 /* uavtalk */ = { - isa = PBXGroup; - children = ( - 65B36783121C2620003EAD18 /* telemetry.cpp */, - 65B36784121C2620003EAD18 /* telemetry.h */, - 65B36785121C2620003EAD18 /* telemetrymanager.cpp */, - 65B36786121C2620003EAD18 /* telemetrymanager.h */, - 65B36787121C2620003EAD18 /* telemetrymonitor.cpp */, - 65B36788121C2620003EAD18 /* telemetrymonitor.h */, - 65B36789121C2620003EAD18 /* uavtalk.cpp */, - 65B3678A121C2620003EAD18 /* uavtalk.h */, - 65B3678B121C2620003EAD18 /* UAVTalk.pluginspec */, - 65B3678C121C2620003EAD18 /* uavtalk.pri */, - 65B3678D121C2620003EAD18 /* uavtalk.pro */, - 65B3678E121C2620003EAD18 /* uavtalk_dependencies.pri */, - 65B3678F121C2620003EAD18 /* uavtalk_global.h */, - 65B36790121C2620003EAD18 /* uavtalkplugin.cpp */, - 65B36791121C2620003EAD18 /* uavtalkplugin.h */, - ); - path = uavtalk; - sourceTree = ""; - }; - 65B36792121C2620003EAD18 /* uploader */ = { - isa = PBXGroup; - children = ( - 65B36793121C2620003EAD18 /* Uploader.pluginspec */, - 65B36794121C2620003EAD18 /* uploader.pro */, - 65B36795121C2620003EAD18 /* uploadergadget.cpp */, - 65B36796121C2620003EAD18 /* uploadergadget.h */, - 65B36797121C2620003EAD18 /* uploadergadgetconfiguration.cpp */, - 65B36798121C2620003EAD18 /* uploadergadgetconfiguration.h */, - 65B36799121C2620003EAD18 /* uploadergadgetfactory.cpp */, - 65B3679A121C2620003EAD18 /* uploadergadgetfactory.h */, - 65B3679B121C2620003EAD18 /* uploadergadgetoptionspage.cpp */, - 65B3679C121C2620003EAD18 /* uploadergadgetoptionspage.h */, - 65B3679D121C2620003EAD18 /* uploadergadgetwidget.cpp */, - 65B3679E121C2620003EAD18 /* uploadergadgetwidget.h */, - 65B3679F121C2620003EAD18 /* uploaderplugin.cpp */, - 65B367A0121C2620003EAD18 /* uploaderplugin.h */, - ); - path = uploader; - sourceTree = ""; - }; - 65B367A1121C2620003EAD18 /* welcome */ = { - isa = PBXGroup; - children = ( - 65B367A2121C2620003EAD18 /* communitywelcomepage.cpp */, - 65B367A3121C2620003EAD18 /* communitywelcomepage.h */, - 65B367A4121C2620003EAD18 /* communitywelcomepagewidget.cpp */, - 65B367A5121C2620003EAD18 /* communitywelcomepagewidget.h */, - 65B367A6121C2620003EAD18 /* communitywelcomepagewidget.ui */, - 65B367A7121C2620003EAD18 /* images */, - 65B367BB121C2620003EAD18 /* rssfetcher.cpp */, - 65B367BC121C2620003EAD18 /* rssfetcher.h */, - 65B367BD121C2620003EAD18 /* Welcome.pluginspec */, - 65B367BE121C2620003EAD18 /* welcome.pri */, - 65B367BF121C2620003EAD18 /* welcome.pro */, - 65B367C0121C2620003EAD18 /* welcome.qrc */, - 65B367C1121C2620003EAD18 /* welcome_dependencies.pri */, - 65B367C2121C2620003EAD18 /* welcome_global.h */, - 65B367C3121C2620003EAD18 /* welcomemode.cpp */, - 65B367C4121C2620003EAD18 /* welcomemode.h */, - 65B367C5121C2620003EAD18 /* welcomemode.ui */, - 65B367C6121C2620003EAD18 /* welcomeplugin.cpp */, - 65B367C7121C2620003EAD18 /* welcomeplugin.h */, - ); - path = welcome; - sourceTree = ""; - }; - 65B367A7121C2620003EAD18 /* images */ = { - isa = PBXGroup; - children = ( - 65B367A8121C2620003EAD18 /* arrow-left.png */, - 65B367A9121C2620003EAD18 /* arrow-right.png */, - 65B367AA121C2620003EAD18 /* background_center_frame.png */, - 65B367AB121C2620003EAD18 /* btn_26.png */, - 65B367AC121C2620003EAD18 /* btn_26_hover.png */, - 65B367AD121C2620003EAD18 /* btn_26_pressed.png */, - 65B367AE121C2620003EAD18 /* btn_27.png */, - 65B367AF121C2620003EAD18 /* btn_27_hover.png */, - 65B367B0121C2620003EAD18 /* center_frame_header.png */, - 65B367B1121C2620003EAD18 /* combobox_arrow.png */, - 65B367B2121C2620003EAD18 /* feedback-bar-background.png */, - 65B367B3121C2620003EAD18 /* feedback_arrow.png */, - 65B367B4121C2620003EAD18 /* feedback_arrow_hover.png */, - 65B367B5121C2620003EAD18 /* list_bullet_arrow.png */, - 65B367B6121C2620003EAD18 /* mode_project.png */, - 65B367B7121C2620003EAD18 /* nokia_logo.png */, - 65B367B8121C2620003EAD18 /* product_logo.png */, - 65B367B9121C2620003EAD18 /* qt_logo.png */, - 65B367BA121C2620003EAD18 /* rc_combined.png */, - ); - path = images; - sourceTree = ""; - }; - 65B367C9121C2620003EAD18 /* shared */ = { - isa = PBXGroup; - children = ( - 65B367CA121C2620003EAD18 /* namespace_global.h */, - 65B367CB121C2620003EAD18 /* qtlockedfile */, - 65B367D3121C2620003EAD18 /* qtsingleapplication */, - 65B367DE121C2620003EAD18 /* scriptwrapper */, - 65B367E3121C2620003EAD18 /* uavobjectdefinition */, - ); - path = shared; - sourceTree = ""; - }; - 65B367CB121C2620003EAD18 /* qtlockedfile */ = { - isa = PBXGroup; - children = ( - 65B367CC121C2620003EAD18 /* namespace.patch */, - 65B367CD121C2620003EAD18 /* qtlockedfile.cpp */, - 65B367CE121C2620003EAD18 /* qtlockedfile.h */, - 65B367CF121C2620003EAD18 /* qtlockedfile.pri */, - 65B367D0121C2620003EAD18 /* qtlockedfile_unix.cpp */, - 65B367D1121C2620003EAD18 /* qtlockedfile_win.cpp */, - 65B367D2121C2620003EAD18 /* README.txt */, - ); - path = qtlockedfile; - sourceTree = ""; - }; - 65B367D3121C2620003EAD18 /* qtsingleapplication */ = { - isa = PBXGroup; - children = ( - 65B367D4121C2620003EAD18 /* namespace.patch */, - 65B367D5121C2620003EAD18 /* qtlocalpeer.cpp */, - 65B367D6121C2620003EAD18 /* qtlocalpeer.h */, - 65B367D7121C2620003EAD18 /* qtsingleapplication.cpp */, - 65B367D8121C2620003EAD18 /* qtsingleapplication.h */, - 65B367D9121C2620003EAD18 /* qtsingleapplication.pri */, - 65B367DA121C2620003EAD18 /* qtsinglecoreapplication.cpp */, - 65B367DB121C2620003EAD18 /* qtsinglecoreapplication.h */, - 65B367DC121C2620003EAD18 /* qtsinglecoreapplication.pri */, - 65B367DD121C2620003EAD18 /* README.txt */, - ); - path = qtsingleapplication; - sourceTree = ""; - }; - 65B367DE121C2620003EAD18 /* scriptwrapper */ = { - isa = PBXGroup; - children = ( - 65B367DF121C2620003EAD18 /* interface_wrap_helpers.h */, - 65B367E0121C2620003EAD18 /* README */, - 65B367E1121C2620003EAD18 /* scriptwrapper.pri */, - 65B367E2121C2620003EAD18 /* wrap_helpers.h */, - ); - path = scriptwrapper; - sourceTree = ""; - }; - 65B367E3121C2620003EAD18 /* uavobjectdefinition */ = { - isa = PBXGroup; - children = ( - 65D2CA841248F9A400B1E7D6 /* mixersettings.xml */, - 65D2CA851248F9A400B1E7D6 /* mixerstatus.xml */, - 655268BC121FBD2900410C6E /* ahrscalibration.xml */, - 659ED317122226B60011010E /* ahrssettings.xml */, - 65B367E7121C2620003EAD18 /* ahrsstatus.xml */, - 65B367E4121C2620003EAD18 /* actuatorcommand.xml */, - 65B367E5121C2620003EAD18 /* actuatordesired.xml */, - 65B367E6121C2620003EAD18 /* actuatorsettings.xml */, - 65B367E9121C2620003EAD18 /* attitudeactual.xml */, - 65B367EA121C2620003EAD18 /* attitudedesired.xml */, - 65B367EB121C2620003EAD18 /* attituderaw.xml */, - 65209A1812208B0600453371 /* baroaltitude.xml */, - 65B367F0121C2620003EAD18 /* flightbatterystate.xml */, - 65B367F2121C2620003EAD18 /* flighttelemetrystats.xml */, - 65B367F3121C2620003EAD18 /* gcstelemetrystats.xml */, - 65209A1912208B0600453371 /* gpsposition.xml */, - 65322D3B122841F60046CD7C /* gpstime.xml */, - 65345C871288668B00A5E4E8 /* guidancesettings.xml */, - 657CEEAD121DB6C8007A1FBE /* homelocation.xml */, - 65B367F4121C2620003EAD18 /* manualcontrolcommand.xml */, - 65B367F5121C2620003EAD18 /* manualcontrolsettings.xml */, - 65B367F8121C2620003EAD18 /* objectpersistence.xml */, - 65B367F9121C2620003EAD18 /* positionactual.xml */, - 65EA2E171273C55200636061 /* ratedesired.xml */, - 65B367FA121C2620003EAD18 /* stabilizationsettings.xml */, - 65B367FB121C2620003EAD18 /* systemalarms.xml */, - 65B367FC121C2620003EAD18 /* systemsettings.xml */, - 65B367FD121C2620003EAD18 /* systemstats.xml */, - 65B367FE121C2620003EAD18 /* telemetrysettings.xml */, - 65408AA812BB1648004DACC5 /* i2cstats.xml */, - 656268C612DC1923007B0A0F /* nedaccel.xml */, - ); - path = uavobjectdefinition; - sourceTree = ""; - }; - 65B7E6AC120DF1CD000C1123 /* AHRS */ = { - isa = PBXGroup; - children = ( - 6509C7E912CA57DC002E5DC2 /* insgps16state.c */, - 6502584212CA4D2600583CDF /* insgps13state.c */, - 65FC66AA123F30F100B04F74 /* ahrs_timer.c */, - 65B7E6AE120DF1E2000C1123 /* ahrs.c */, - 65B7E6AF120DF1E2000C1123 /* inc */, - 65B7E6B6120DF1E2000C1123 /* Makefile */, - 65B7E6B7120DF1E2000C1123 /* pios_board.c */, - ); - name = AHRS; - sourceTree = ""; - }; - 65B7E6AF120DF1E2000C1123 /* inc */ = { - isa = PBXGroup; - children = ( - 65FC66AB123F312A00B04F74 /* ahrs_timer.h */, - 6543304F121980300063F913 /* insgps.h */, - 65B7E6B0120DF1E2000C1123 /* ahrs.h */, - 65B7E6B1120DF1E2000C1123 /* ahrs_fsm.h */, - 65B7E6B4120DF1E2000C1123 /* pios_config.h */, - ); - name = inc; - path = ../../AHRS/inc; - sourceTree = SOURCE_ROOT; - }; 65C35E4E12EFB2F3004811C2 /* shared */ = { isa = PBXGroup; children = ( - 65C35E4F12EFB2F3004811C2 /* uavobjectdefinition */, + 65E466BC14E244020075459C /* uavobjectdefinition */, ); name = shared; path = ../../../shared; sourceTree = SOURCE_ROOT; }; - 65C35E4F12EFB2F3004811C2 /* uavobjectdefinition */ = { - isa = PBXGroup; - children = ( - 65E8C788139AA2A800E1F979 /* accessorydesired.xml */, - 65C35E5012EFB2F3004811C2 /* actuatorcommand.xml */, - 65C35E5112EFB2F3004811C2 /* actuatordesired.xml */, - 65C35E5212EFB2F3004811C2 /* actuatorsettings.xml */, - 65C35E5312EFB2F3004811C2 /* ahrscalibration.xml */, - 65C35E5412EFB2F3004811C2 /* ahrssettings.xml */, - 65C35E5512EFB2F3004811C2 /* ahrsstatus.xml */, - 65C35E5612EFB2F3004811C2 /* attitudeactual.xml */, - 65C35E5812EFB2F3004811C2 /* attituderaw.xml */, - 65E410AE12F65AEA00725888 /* attitudesettings.xml */, - 65C35E5912EFB2F3004811C2 /* baroaltitude.xml */, - 655B1A8E13B2FC0900B0E48D /* camerastabsettings.xml */, - 652C8568132B632A00BFCC70 /* firmwareiapobj.xml */, - 65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */, - 65C35E5D12EFB2F3004811C2 /* flightplancontrol.xml */, - 65C35E5E12EFB2F3004811C2 /* flightplansettings.xml */, - 65C35E5F12EFB2F3004811C2 /* flightplanstatus.xml */, - 65C35E6012EFB2F3004811C2 /* flighttelemetrystats.xml */, - 65078B09136FCEE600536549 /* flightstatus.xml */, - 65C35E6112EFB2F3004811C2 /* gcstelemetrystats.xml */, - 65C35E6212EFB2F3004811C2 /* gpsposition.xml */, - 65C35E6312EFB2F3004811C2 /* gpssatellites.xml */, - 65C35E6412EFB2F3004811C2 /* gpstime.xml */, - 65C35E6512EFB2F3004811C2 /* guidancesettings.xml */, - 65C35E6612EFB2F3004811C2 /* homelocation.xml */, - 65E6D80713E3A4D0002A557A /* hwsettings.xml */, - 65C35E6712EFB2F3004811C2 /* i2cstats.xml */, - 65C35E6812EFB2F3004811C2 /* manualcontrolcommand.xml */, - 65C35E6912EFB2F3004811C2 /* manualcontrolsettings.xml */, - 65C35E6A12EFB2F3004811C2 /* mixersettings.xml */, - 65C35E6B12EFB2F3004811C2 /* mixerstatus.xml */, - 65C35E6C12EFB2F3004811C2 /* nedaccel.xml */, - 65C35E6D12EFB2F3004811C2 /* objectpersistence.xml */, - 65C35E6E12EFB2F3004811C2 /* positionactual.xml */, - 65C35E6F12EFB2F3004811C2 /* positiondesired.xml */, - 65C35E7012EFB2F3004811C2 /* ratedesired.xml */, - 65FAB8CF147FFD76000FF8B2 /* receiveractivity.xml */, - 652C856A132B6EA600BFCC70 /* sonaraltitude.xml */, - 6536D47B1307962C0042A298 /* stabilizationdesired.xml */, - 65C35E7112EFB2F3004811C2 /* stabilizationsettings.xml */, - 65C35E7212EFB2F3004811C2 /* systemalarms.xml */, - 65C35E7312EFB2F3004811C2 /* systemsettings.xml */, - 65C35E7412EFB2F3004811C2 /* systemstats.xml */, - 65C35E7512EFB2F3004811C2 /* taskinfo.xml */, - 65C35E7612EFB2F3004811C2 /* telemetrysettings.xml */, - 65C35E7712EFB2F3004811C2 /* velocityactual.xml */, - 65C35E7812EFB2F3004811C2 /* velocitydesired.xml */, - 65C35E7912EFB2F3004811C2 /* watchdogstatus.xml */, - 65DEA79113F2143B00095B06 /* cameradesired.xml */, - ); - path = uavobjectdefinition; - sourceTree = ""; - }; - 65C35EA212F0A834004811C2 /* inc */ = { - isa = PBXGroup; - children = ( - 65C35EA312F0A834004811C2 /* eventdispatcher.h */, - 65C35EA412F0A834004811C2 /* uavobjectmanager.h */, - 65C35EA512F0A834004811C2 /* uavobjectsinit.h */, - 65C35EA612F0A834004811C2 /* uavobjecttemplate.h */, - 65C35EA712F0A834004811C2 /* utlist.h */, - ); - path = inc; - sourceTree = ""; - }; - 65C35F6512F0DC2D004811C2 /* Attitude */ = { - isa = PBXGroup; - children = ( - 65C35F6612F0DC2D004811C2 /* attitude.c */, - 65C35F6712F0DC2D004811C2 /* inc */, - ); - path = Attitude; - sourceTree = ""; - }; - 65C35F6712F0DC2D004811C2 /* inc */ = { - isa = PBXGroup; - children = ( - 65C35F6812F0DC2D004811C2 /* attitude.h */, - ); - path = inc; - sourceTree = ""; - }; - 65C9903B13A871B90082BD60 /* CameraStab */ = { - isa = PBXGroup; - children = ( - 65C9903C13A871B90082BD60 /* camerastab.c */, - 65C9903D13A871B90082BD60 /* inc */, - ); - path = CameraStab; - sourceTree = ""; - }; - 65C9903D13A871B90082BD60 /* inc */ = { - isa = PBXGroup; - children = ( - 65C9903E13A871B90082BD60 /* camerastab.h */, - ); - path = inc; - sourceTree = ""; - }; - 65E6DF7012E02E8E00058553 /* CopterControl */ = { - isa = PBXGroup; - children = ( - 65E6DF7112E02E8E00058553 /* Makefile */, - 65E6DF7212E02E8E00058553 /* System */, - ); - name = CopterControl; - path = ../../CopterControl; - sourceTree = SOURCE_ROOT; - }; - 65E6DF7212E02E8E00058553 /* System */ = { - isa = PBXGroup; - children = ( - 65E6DF7312E02E8E00058553 /* alarms.c */, - 65E6DF7412E02E8E00058553 /* coptercontrol.c */, - 65E6DF7512E02E8E00058553 /* inc */, - 65E6DF7E12E02E8E00058553 /* pios_board.c */, - 65E6DF7F12E02E8E00058553 /* pios_board_posix.c */, - 65E6DF8012E02E8E00058553 /* taskmonitor.c */, - ); - path = System; - sourceTree = ""; - }; - 65E6DF7512E02E8E00058553 /* inc */ = { - isa = PBXGroup; - children = ( - 65E6DF7612E02E8E00058553 /* alarms.h */, - 65E6DF7712E02E8E00058553 /* FreeRTOSConfig.h */, - 65E6DF7812E02E8E00058553 /* op_config.h */, - 65E6DF7912E02E8E00058553 /* openpilot.h */, - 65E6DF7A12E02E8E00058553 /* pios_board_posix.h */, - 65E6DF7B12E02E8E00058553 /* pios_config.h */, - 65E6DF7C12E02E8E00058553 /* pios_config_posix.h */, - 65E6DF7D12E02E8E00058553 /* taskmonitor.h */, - ); - path = inc; - sourceTree = ""; - }; - 65E6DF9012E0313E00058553 /* PipXtreme */ = { - isa = PBXGroup; - children = ( - 65E6DF9112E0313E00058553 /* aes.c */, - 65E6E04412E0313F00058553 /* crc.c */, - 65E6E04512E0313F00058553 /* gpio_in.c */, - 65E6E04612E0313F00058553 /* inc */, - 65E6E05612E0313F00058553 /* main.c */, - 65E6E05712E0313F00058553 /* Makefile */, - 65E6E05812E0313F00058553 /* packet_handler.c */, - 65E6E05912E0313F00058553 /* pios_board.c */, - 65E6E05A12E0313F00058553 /* pios_usb_hid_desc.c */, - 65E6E05B12E0313F00058553 /* rfm22b.c */, - 65E6E05C12E0313F00058553 /* saved_settings.c */, - 65E6E05D12E0313F00058553 /* stopwatch.c */, - 65E6E05E12E0313F00058553 /* transparent_comms.c */, - 65E6E05F12E0313F00058553 /* uavtalk_comms.c */, - 65E6E06012E0313F00058553 /* watchdog.c */, - ); - name = PipXtreme; - path = ../../PipXtreme; - sourceTree = SOURCE_ROOT; - }; - 65E6E04612E0313F00058553 /* inc */ = { - isa = PBXGroup; - children = ( - 65E6E04712E0313F00058553 /* aes.h */, - 65E6E04812E0313F00058553 /* crc.h */, - 65E6E04912E0313F00058553 /* gpio_in.h */, - 65E6E04A12E0313F00058553 /* main.h */, - 65E6E04B12E0313F00058553 /* packet_handler.h */, - 65E6E04C12E0313F00058553 /* pios_config.h */, - 65E6E04D12E0313F00058553 /* pios_usb.h */, - 65E6E04E12E0313F00058553 /* pios_usb_hid_desc.h */, - 65E6E04F12E0313F00058553 /* rfm22b.h */, - 65E6E05012E0313F00058553 /* saved_settings.h */, - 65E6E05112E0313F00058553 /* stopwatch.h */, - 65E6E05212E0313F00058553 /* transparent_comms.h */, - 65E6E05312E0313F00058553 /* uavtalk_comms.h */, - 65E6E05412E0313F00058553 /* usb_conf.h */, - 65E6E05512E0313F00058553 /* watchdog.h */, - ); - path = inc; - sourceTree = ""; - }; - 65E8EF1E11EEA61E00BBF654 /* OpenPilot */ = { - isa = PBXGroup; - children = ( - 6536D4881307AB950042A298 /* UAVObjects.inc */, - 65E8EF1F11EEA61E00BBF654 /* Makefile */, - 65E8EF2011EEA61E00BBF654 /* Makefile.posix */, - 65E8EF5B11EEA61E00BBF654 /* System */, - 65E8EF6811EEA61E00BBF654 /* Tests */, - ); - name = OpenPilot; - path = ../../OpenPilot; - sourceTree = SOURCE_ROOT; - }; - 65E8EF5B11EEA61E00BBF654 /* System */ = { - isa = PBXGroup; - children = ( - 65E8EF5C11EEA61E00BBF654 /* alarms.c */, - 65E8EF5D11EEA61E00BBF654 /* inc */, - 65E8EF6511EEA61E00BBF654 /* openpilot.c */, - 65E8EF6611EEA61E00BBF654 /* pios_board.c */, - 65E8EF6711EEA61E00BBF654 /* pios_board_posix.c */, - 6589A983131DE24F006BD67C /* taskmonitor.c */, - ); - name = System; - path = ../../OpenPilot/System; - sourceTree = SOURCE_ROOT; - }; - 65E8EF5D11EEA61E00BBF654 /* inc */ = { - isa = PBXGroup; - children = ( - 6589A972131DDE93006BD67C /* FreeRTOSConfig.h */, - 65E8EF5E11EEA61E00BBF654 /* alarms.h */, - 65E8EF5F11EEA61E00BBF654 /* op_config.h */, - 65E8EF6011EEA61E00BBF654 /* openpilot.h */, - 65E8EF6111EEA61E00BBF654 /* pios_board.h */, - 65E8EF6211EEA61E00BBF654 /* pios_board_posix.h */, - 65E8EF6311EEA61E00BBF654 /* pios_config.h */, - 65E8EF6411EEA61E00BBF654 /* pios_config_posix.h */, - ); - name = inc; - path = ../../OpenPilot/System/inc; - sourceTree = SOURCE_ROOT; - }; - 65E8EF6811EEA61E00BBF654 /* Tests */ = { - isa = PBXGroup; - children = ( - 65E8EF6911EEA61E00BBF654 /* test_BMP085.c */, - 65E8EF6A11EEA61E00BBF654 /* test_common.c */, - 65E8EF6B11EEA61E00BBF654 /* test_cpuload.c */, - 65E8EF6C11EEA61E00BBF654 /* test_i2c_PCF8570.c */, - 65E8EF6D11EEA61E00BBF654 /* test_uavobjects.c */, - ); - name = Tests; - path = ../../OpenPilot/Tests; - sourceTree = SOURCE_ROOT; - }; - 65E8F02F11EFF25C00BBF654 /* PiOS */ = { - isa = PBXGroup; - children = ( - 65632DF41251650300469B77 /* Boards */, - 65E8F03011EFF25C00BBF654 /* Common */, - 65E8F03811EFF25C00BBF654 /* inc */, - 65E8F05711EFF25C00BBF654 /* pios.h */, - 65E8F05811EFF25C00BBF654 /* STM32F10x */, - ); - name = PiOS; - path = ../../PiOS; - sourceTree = SOURCE_ROOT; - }; - 65E8F03011EFF25C00BBF654 /* Common */ = { - isa = PBXGroup; - children = ( - 654612D812B5E9A900B719D0 /* pios_iap.c */, - 65E8F03111EFF25C00BBF654 /* pios_bmp085.c */, - 65E8F03211EFF25C00BBF654 /* pios_com.c */, - 65E8F03311EFF25C00BBF654 /* pios_hmc5843.c */, - 65E8F03411EFF25C00BBF654 /* pios_opahrs.c */, - 65E8F03511EFF25C00BBF654 /* pios_opahrs_proto.c */, - 65E8F03611EFF25C00BBF654 /* pios_sdcard.c */, - 65E8F03711EFF25C00BBF654 /* printf-stdarg.c */, - 6528CCB412E406B800CF5144 /* pios_adxl345.c */, - 6512D60712ED4CB8008175E5 /* pios_flash_w25x.c */, - 65FF4D5E137EDEC100146BE4 /* pios_flashfs_objlist.c */, - 6562BE1713CCAD0600C823E8 /* pios_rcvr.c */, - 65E8C743139A6D0900E1F979 /* pios_crc.c */, - ); - name = Common; - path = ../../PiOS/Common; - sourceTree = SOURCE_ROOT; - }; - 65E8F03811EFF25C00BBF654 /* inc */ = { - isa = PBXGroup; - children = ( - 6528CCE212E40F6700CF5144 /* pios_adxl345.h */, - 65E8C745139A6D1A00E1F979 /* pios_crc.h */, - 65E8F03A11EFF25C00BBF654 /* pios_adc.h */, - 65E6E09912E037C800058553 /* pios_adc_priv.h */, - 65E8F03B11EFF25C00BBF654 /* pios_bmp085.h */, - 65E8F03C11EFF25C00BBF654 /* pios_com.h */, - 65E8F03D11EFF25C00BBF654 /* pios_com_priv.h */, - 65E8F03E11EFF25C00BBF654 /* pios_debug.h */, - 65E8F03F11EFF25C00BBF654 /* pios_delay.h */, - 65E8F04011EFF25C00BBF654 /* pios_exti.h */, - 6512D60512ED4CA2008175E5 /* pios_flash_w25x.h */, - 65FF4D61137EFA4F00146BE4 /* pios_flashfs_objlist.h */, - 65E8F04111EFF25C00BBF654 /* pios_gpio.h */, - 65E8F04211EFF25C00BBF654 /* pios_hmc5843.h */, - 65E8F04311EFF25C00BBF654 /* pios_i2c.h */, - 6526645A122DF972006F9A3C /* pios_i2c_priv.h */, - 65E8F04411EFF25C00BBF654 /* pios_irq.h */, - 65E8F04511EFF25C00BBF654 /* pios_led.h */, - 65E8F04611EFF25C00BBF654 /* pios_opahrs.h */, - 65E8F04711EFF25C00BBF654 /* pios_opahrs_proto.h */, - 65E8F04811EFF25C00BBF654 /* pios_ppm.h */, - 65E8F04911EFF25C00BBF654 /* pios_pwm.h */, - 657FF86A12EA8BFB00801617 /* pios_pwm_priv.h */, - 65643CAC1413322000A32F59 /* pios_rcvr.h */, - 65643CAB1413322000A32F59 /* pios_rcvr_priv.h */, - 6589A9E2131DF1C7006BD67C /* pios_rtc.h */, - 65643CAD1413322000A32F59 /* pios_rtc_priv.h */, - 65643CAE1413322000A32F59 /* pios_sbus_priv.h */, - 65643CAF1413322000A32F59 /* pios_sbus.h */, - 65E8F04A11EFF25C00BBF654 /* pios_sdcard.h */, - 65E8F04B11EFF25C00BBF654 /* pios_servo.h */, - 65FBE14412E7C98100176B5A /* pios_servo_priv.h */, - 65E8F04C11EFF25C00BBF654 /* pios_dsm.h */, - 65643CB01413322000A32F59 /* pios_dsm_priv.h */, - 65E8F04D11EFF25C00BBF654 /* pios_spi.h */, - 65E8F04E11EFF25C00BBF654 /* pios_spi_priv.h */, - 65E8F04F11EFF25C00BBF654 /* pios_stm32.h */, - 65E8F05011EFF25C00BBF654 /* pios_sys.h */, - 65E8F05111EFF25C00BBF654 /* pios_usart.h */, - 65E8F05211EFF25C00BBF654 /* pios_usart_priv.h */, - 65E8F05311EFF25C00BBF654 /* pios_usb.h */, - 65E8F05511EFF25C00BBF654 /* pios_usb_hid.h */, - 651CF9EF120B700D00EEFD70 /* pios_usb_hid_desc.h */, - 651CF9F0120B700D00EEFD70 /* pios_usb_hid_istr.h */, - 651CF9F1120B700D00EEFD70 /* pios_usb_hid_prop.h */, - 651CF9F2120B700D00EEFD70 /* pios_usb_hid_pwr.h */, - 6526645B122DF972006F9A3C /* pios_wdg.h */, - 651CF9F3120B700D00EEFD70 /* usb_conf.h */, - 65E8F05611EFF25C00BBF654 /* stm32f10x_conf.h */, - ); - name = inc; - path = ../../PiOS/inc; - sourceTree = SOURCE_ROOT; - }; - 65E8F05811EFF25C00BBF654 /* STM32F10x */ = { - isa = PBXGroup; - children = ( - 6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */, - 6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */, - 65E8F05911EFF25C00BBF654 /* Libraries */, - 65E8F0D811EFF25C00BBF654 /* link_stm32f10x_HD.ld */, - 65E8F0DB11EFF25C00BBF654 /* link_stm32f10x_MD.ld */, - 65E8F0DC11EFF25C00BBF654 /* pios_adc.c */, - 65E8F0DD11EFF25C00BBF654 /* pios_debug.c */, - 65E8F0DE11EFF25C00BBF654 /* pios_delay.c */, - 65E8F0DF11EFF25C00BBF654 /* pios_exti.c */, - 65E8F0E011EFF25C00BBF654 /* pios_gpio.c */, - 65E8F0E111EFF25C00BBF654 /* pios_i2c.c */, - 65E8F0E211EFF25C00BBF654 /* pios_irq.c */, - 65E8F0E311EFF25C00BBF654 /* pios_led.c */, - 65E8F0E411EFF25C00BBF654 /* pios_ppm.c */, - 65E8F0E511EFF25C00BBF654 /* pios_pwm.c */, - 6589A9DB131DEE76006BD67C /* pios_rtc.c */, - 65643CBA141350C200A32F59 /* pios_sbus.c */, - 65E8F0E611EFF25C00BBF654 /* pios_servo.c */, - 65E8F0E711EFF25C00BBF654 /* pios_dsm.c */, - 65E8F0E811EFF25C00BBF654 /* pios_spi.c */, - 65E8F0E911EFF25C00BBF654 /* pios_sys.c */, - 65643CB91413456D00A32F59 /* pios_tim.c */, - 65E8F0EA11EFF25C00BBF654 /* pios_usart.c */, - 65E8F0ED11EFF25C00BBF654 /* pios_usb_hid.c */, - 651CF9E5120B5D8300EEFD70 /* pios_usb_hid_desc.c */, - 651CF9E6120B5D8300EEFD70 /* pios_usb_hid_istr.c */, - 651CF9E7120B5D8300EEFD70 /* pios_usb_hid_prop.c */, - 651CF9E8120B5D8300EEFD70 /* pios_usb_hid_pwr.c */, - 65003B31121249CA00C183DD /* pios_wdg.c */, - 65E8F0EE11EFF25C00BBF654 /* startup_stm32f10x_HD.S */, - 65E8F0F111EFF25C00BBF654 /* startup_stm32f10x_MD.S */, - ); - name = STM32F10x; - path = ../../PiOS/STM32F10x; - sourceTree = SOURCE_ROOT; - }; - 65E8F05911EFF25C00BBF654 /* Libraries */ = { - isa = PBXGroup; - children = ( - 65E8F05A11EFF25C00BBF654 /* CMSIS */, - 65E8F06B11EFF25C00BBF654 /* dosfs */, - 65E8F07111EFF25C00BBF654 /* FreeRTOS */, - 65E8F08D11EFF25C00BBF654 /* msd */, - 65E8F09911EFF25C00BBF654 /* STM32_USB-FS-Device_Driver */, - 65E8F0A911EFF25C00BBF654 /* STM32F10x_StdPeriph_Driver */, - ); - name = Libraries; - path = ../../PiOS/STM32F10x/Libraries; - sourceTree = SOURCE_ROOT; - }; - 65E8F05A11EFF25C00BBF654 /* CMSIS */ = { - isa = PBXGroup; - children = ( - 65E8F05B11EFF25C00BBF654 /* Core */, - 65E8F06A11EFF25C00BBF654 /* License.doc */, - ); - name = CMSIS; - path = ../../PiOS/STM32F10x/Libraries/CMSIS; - sourceTree = SOURCE_ROOT; - }; - 65E8F05B11EFF25C00BBF654 /* Core */ = { - isa = PBXGroup; - children = ( - 65E8F05C11EFF25C00BBF654 /* CM3 */, - 65E8F06811EFF25C00BBF654 /* Documentation */, - ); - name = Core; - path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core; - sourceTree = SOURCE_ROOT; - }; - 65E8F05C11EFF25C00BBF654 /* CM3 */ = { - isa = PBXGroup; - children = ( - 65E8F05D11EFF25C00BBF654 /* core_cm3.c */, - 65E8F05E11EFF25C00BBF654 /* core_cm3.h */, - 65E8F05F11EFF25C00BBF654 /* startup */, - 65E8F06511EFF25C00BBF654 /* stm32f10x.h */, - 65E8F06611EFF25C00BBF654 /* system_stm32f10x.c */, - 65E8F06711EFF25C00BBF654 /* system_stm32f10x.h */, - ); - name = CM3; - path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3; - sourceTree = SOURCE_ROOT; - }; - 65E8F05F11EFF25C00BBF654 /* startup */ = { - isa = PBXGroup; - children = ( - 65E8F06011EFF25C00BBF654 /* gcc */, - ); - name = startup; - path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup; - sourceTree = SOURCE_ROOT; - }; - 65E8F06011EFF25C00BBF654 /* gcc */ = { - isa = PBXGroup; - children = ( - 65E8F06111EFF25C00BBF654 /* startup_stm32f10x_cl.s */, - 65E8F06211EFF25C00BBF654 /* startup_stm32f10x_hd.s */, - 65E8F06311EFF25C00BBF654 /* startup_stm32f10x_ld.s */, - 65E8F06411EFF25C00BBF654 /* startup_stm32f10x_md.s */, - ); - name = gcc; - path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc; - sourceTree = SOURCE_ROOT; - }; - 65E8F06811EFF25C00BBF654 /* Documentation */ = { - isa = PBXGroup; - children = ( - 65E8F06911EFF25C00BBF654 /* CMSIS_Core.htm */, - ); - name = Documentation; - path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/Documentation; - sourceTree = SOURCE_ROOT; - }; - 65E8F06B11EFF25C00BBF654 /* dosfs */ = { - isa = PBXGroup; - children = ( - 65E8F06C11EFF25C00BBF654 /* dfs_sdcard.c */, - 65E8F06D11EFF25C00BBF654 /* dosfs.c */, - 65E8F06E11EFF25C00BBF654 /* dosfs.h */, - 65E8F06F11EFF25C00BBF654 /* README.txt */, - 65E8F07011EFF25C00BBF654 /* README_1st.txt */, - ); - name = dosfs; - path = ../../PiOS/STM32F10x/Libraries/dosfs; - sourceTree = SOURCE_ROOT; - }; - 65E8F07111EFF25C00BBF654 /* FreeRTOS */ = { - isa = PBXGroup; - children = ( - 65E8F07211EFF25C00BBF654 /* Source */, - ); - name = FreeRTOS; - path = ../../PiOS/STM32F10x/Libraries/FreeRTOS; - sourceTree = SOURCE_ROOT; - }; - 65E8F07211EFF25C00BBF654 /* Source */ = { - isa = PBXGroup; - children = ( - 65E8F07311EFF25C00BBF654 /* croutine.c */, - 65E8F07411EFF25C00BBF654 /* include */, - 65E8F07F11EFF25C00BBF654 /* list.c */, - 65E8F08011EFF25C00BBF654 /* portable */, - 65E8F08A11EFF25C00BBF654 /* queue.c */, - 65E8F08B11EFF25C00BBF654 /* readme.txt */, - 65E8F08C11EFF25C00BBF654 /* tasks.c */, - ); - name = Source; - path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source; - sourceTree = SOURCE_ROOT; - }; - 65E8F07411EFF25C00BBF654 /* include */ = { - isa = PBXGroup; - children = ( - 65E8F07511EFF25C00BBF654 /* croutine.h */, - 65E8F07611EFF25C00BBF654 /* FreeRTOS.h */, - 65E8F07711EFF25C00BBF654 /* list.h */, - 65E8F07811EFF25C00BBF654 /* mpu_wrappers.h */, - 65E8F07911EFF25C00BBF654 /* portable.h */, - 65E8F07A11EFF25C00BBF654 /* projdefs.h */, - 65E8F07B11EFF25C00BBF654 /* queue.h */, - 65E8F07C11EFF25C00BBF654 /* semphr.h */, - 65E8F07D11EFF25C00BBF654 /* StackMacros.h */, - 65E8F07E11EFF25C00BBF654 /* task.h */, - ); - name = include; - path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include; - sourceTree = SOURCE_ROOT; - }; - 65E8F08011EFF25C00BBF654 /* portable */ = { - isa = PBXGroup; - children = ( - 65E8F08111EFF25C00BBF654 /* GCC */, - 65E8F08511EFF25C00BBF654 /* MemMang */, - 65E8F08911EFF25C00BBF654 /* readme.txt */, - ); - name = portable; - path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable; - sourceTree = SOURCE_ROOT; - }; - 65E8F08111EFF25C00BBF654 /* GCC */ = { - isa = PBXGroup; - children = ( - 65E8F08211EFF25C00BBF654 /* ARM_CM3 */, - ); - name = GCC; - path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC; - sourceTree = SOURCE_ROOT; - }; - 65E8F08211EFF25C00BBF654 /* ARM_CM3 */ = { - isa = PBXGroup; - children = ( - 65E8F08311EFF25C00BBF654 /* port.c */, - 65E8F08411EFF25C00BBF654 /* portmacro.h */, - ); - name = ARM_CM3; - path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3; - sourceTree = SOURCE_ROOT; - }; - 65E8F08511EFF25C00BBF654 /* MemMang */ = { - isa = PBXGroup; - children = ( - 65E8F08611EFF25C00BBF654 /* heap_1.c */, - 65E8F08711EFF25C00BBF654 /* heap_2.c */, - 65E8F08811EFF25C00BBF654 /* heap_3.c */, - ); - name = MemMang; - path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang; - sourceTree = SOURCE_ROOT; - }; - 65E8F08D11EFF25C00BBF654 /* msd */ = { - isa = PBXGroup; - children = ( - 65E8F08E11EFF25C00BBF654 /* msd.c */, - 65E8F08F11EFF25C00BBF654 /* msd.h */, - 65E8F09011EFF25C00BBF654 /* msd_bot.c */, - 65E8F09111EFF25C00BBF654 /* msd_bot.h */, - 65E8F09211EFF25C00BBF654 /* msd_desc.c */, - 65E8F09311EFF25C00BBF654 /* msd_desc.h */, - 65E8F09411EFF25C00BBF654 /* msd_memory.c */, - 65E8F09511EFF25C00BBF654 /* msd_memory.h */, - 65E8F09611EFF25C00BBF654 /* msd_scsi.c */, - 65E8F09711EFF25C00BBF654 /* msd_scsi.h */, - 65E8F09811EFF25C00BBF654 /* msd_scsi_data.c */, - ); - name = msd; - path = ../../PiOS/STM32F10x/Libraries/msd; - sourceTree = SOURCE_ROOT; - }; - 65E8F09911EFF25C00BBF654 /* STM32_USB-FS-Device_Driver */ = { - isa = PBXGroup; - children = ( - 65E8F09A11EFF25C00BBF654 /* inc */, - 65E8F0A311EFF25C00BBF654 /* src */, - ); - name = "STM32_USB-FS-Device_Driver"; - path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver"; - sourceTree = SOURCE_ROOT; - }; - 65E8F09A11EFF25C00BBF654 /* inc */ = { - isa = PBXGroup; - children = ( - 65E8F09B11EFF25C00BBF654 /* usb_core.h */, - 65E8F09C11EFF25C00BBF654 /* usb_def.h */, - 65E8F09D11EFF25C00BBF654 /* usb_init.h */, - 65E8F09E11EFF25C00BBF654 /* usb_int.h */, - 65E8F09F11EFF25C00BBF654 /* usb_lib.h */, - 65E8F0A011EFF25C00BBF654 /* usb_mem.h */, - 65E8F0A111EFF25C00BBF654 /* usb_regs.h */, - 65E8F0A211EFF25C00BBF654 /* usb_type.h */, - ); - name = inc; - path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc"; - sourceTree = SOURCE_ROOT; - }; - 65E8F0A311EFF25C00BBF654 /* src */ = { - isa = PBXGroup; - children = ( - 65E8F0A411EFF25C00BBF654 /* usb_core.c */, - 65E8F0A511EFF25C00BBF654 /* usb_init.c */, - 65E8F0A611EFF25C00BBF654 /* usb_int.c */, - 65E8F0A711EFF25C00BBF654 /* usb_mem.c */, - 65E8F0A811EFF25C00BBF654 /* usb_regs.c */, - ); - name = src; - path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src"; - sourceTree = SOURCE_ROOT; - }; - 65E8F0A911EFF25C00BBF654 /* STM32F10x_StdPeriph_Driver */ = { - isa = PBXGroup; - children = ( - 65E8F0AA11EFF25C00BBF654 /* inc */, - 65E8F0C111EFF25C00BBF654 /* src */, - ); - name = STM32F10x_StdPeriph_Driver; - path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver; - sourceTree = SOURCE_ROOT; - }; - 65E8F0AA11EFF25C00BBF654 /* inc */ = { - isa = PBXGroup; - children = ( - 65E8F0AB11EFF25C00BBF654 /* misc.h */, - 65E8F0AC11EFF25C00BBF654 /* stm32f10x_adc.h */, - 65E8F0AD11EFF25C00BBF654 /* stm32f10x_bkp.h */, - 65E8F0AE11EFF25C00BBF654 /* stm32f10x_can.h */, - 65E8F0AF11EFF25C00BBF654 /* stm32f10x_crc.h */, - 65E8F0B011EFF25C00BBF654 /* stm32f10x_dac.h */, - 65E8F0B111EFF25C00BBF654 /* stm32f10x_dbgmcu.h */, - 65E8F0B211EFF25C00BBF654 /* stm32f10x_dma.h */, - 65E8F0B311EFF25C00BBF654 /* stm32f10x_exti.h */, - 65E8F0B411EFF25C00BBF654 /* stm32f10x_flash.h */, - 65E8F0B511EFF25C00BBF654 /* stm32f10x_fsmc.h */, - 65E8F0B611EFF25C00BBF654 /* stm32f10x_gpio.h */, - 65E8F0B711EFF25C00BBF654 /* stm32f10x_i2c.h */, - 65E8F0B811EFF25C00BBF654 /* stm32f10x_iwdg.h */, - 65E8F0B911EFF25C00BBF654 /* stm32f10x_pwr.h */, - 65E8F0BA11EFF25C00BBF654 /* stm32f10x_rcc.h */, - 65E8F0BB11EFF25C00BBF654 /* stm32f10x_rtc.h */, - 65E8F0BC11EFF25C00BBF654 /* stm32f10x_sdio.h */, - 65E8F0BD11EFF25C00BBF654 /* stm32f10x_spi.h */, - 65E8F0BE11EFF25C00BBF654 /* stm32f10x_tim.h */, - 65E8F0BF11EFF25C00BBF654 /* stm32f10x_usart.h */, - 65E8F0C011EFF25C00BBF654 /* stm32f10x_wwdg.h */, - ); - name = inc; - path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc; - sourceTree = SOURCE_ROOT; - }; - 65E8F0C111EFF25C00BBF654 /* src */ = { - isa = PBXGroup; - children = ( - 65E8F0C211EFF25C00BBF654 /* misc.c */, - 65E8F0C311EFF25C00BBF654 /* stm32f10x_adc.c */, - 65E8F0C411EFF25C00BBF654 /* stm32f10x_bkp.c */, - 65E8F0C511EFF25C00BBF654 /* stm32f10x_can.c */, - 65E8F0C611EFF25C00BBF654 /* stm32f10x_crc.c */, - 65E8F0C711EFF25C00BBF654 /* stm32f10x_dac.c */, - 65E8F0C811EFF25C00BBF654 /* stm32f10x_dbgmcu.c */, - 65E8F0C911EFF25C00BBF654 /* stm32f10x_dma.c */, - 65E8F0CA11EFF25C00BBF654 /* stm32f10x_exti.c */, - 65E8F0CB11EFF25C00BBF654 /* stm32f10x_flash.c */, - 65E8F0CC11EFF25C00BBF654 /* stm32f10x_fsmc.c */, - 65E8F0CD11EFF25C00BBF654 /* stm32f10x_gpio.c */, - 65E8F0CE11EFF25C00BBF654 /* stm32f10x_i2c.c */, - 65E8F0CF11EFF25C00BBF654 /* stm32f10x_iwdg.c */, - 65E8F0D011EFF25C00BBF654 /* stm32f10x_pwr.c */, - 65E8F0D111EFF25C00BBF654 /* stm32f10x_rcc.c */, - 65E8F0D211EFF25C00BBF654 /* stm32f10x_rtc.c */, - 65E8F0D311EFF25C00BBF654 /* stm32f10x_sdio.c */, - 65E8F0D411EFF25C00BBF654 /* stm32f10x_spi.c */, - 65E8F0D511EFF25C00BBF654 /* stm32f10x_tim.c */, - 65E8F0D611EFF25C00BBF654 /* stm32f10x_usart.c */, - 65E8F0D711EFF25C00BBF654 /* stm32f10x_wwdg.c */, - ); - name = src; - path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src; - sourceTree = SOURCE_ROOT; - }; - 65F93B9012EE09280047DB36 /* PipXtreme */ = { - isa = PBXGroup; - children = ( - 65F93C3912EE09280047DB36 /* aes.c */, - 65F93C3A12EE09280047DB36 /* Build */, - 65F93CEC12EE09290047DB36 /* crc.c */, - 65F93CED12EE09290047DB36 /* gpio_in.c */, - 65F93CEE12EE09290047DB36 /* inc */, - 65F93CFE12EE09290047DB36 /* main.c */, - 65F93CFF12EE09290047DB36 /* Makefile */, - 65F93D0012EE09290047DB36 /* packet_handler.c */, - 65F93D0112EE09290047DB36 /* pios_board.c */, - 65F93D0212EE09290047DB36 /* pios_usb_hid_desc.c */, - 65F93D0312EE09290047DB36 /* rfm22b.c */, - 65F93D0412EE09290047DB36 /* saved_settings.c */, - 65F93D0512EE09290047DB36 /* stopwatch.c */, - 65F93D0612EE09290047DB36 /* transparent_comms.c */, - 65F93D0712EE09290047DB36 /* uavtalk_comms.c */, - 65F93D0812EE09290047DB36 /* watchdog.c */, - ); - name = PipXtreme; - path = ../../PipXtreme; - sourceTree = SOURCE_ROOT; - }; - 65F93C3A12EE09280047DB36 /* Build */ = { - isa = PBXGroup; - children = ( - 65F93C3B12EE09280047DB36 /* aes.lst */, - 65F93C3C12EE09280047DB36 /* aes.o */, - 65F93C3D12EE09280047DB36 /* buffer.lst */, - 65F93C3E12EE09280047DB36 /* buffer.o */, - 65F93C3F12EE09280047DB36 /* core_cm3.lst */, - 65F93C4012EE09280047DB36 /* core_cm3.o */, - 65F93C4112EE09280047DB36 /* crc.lst */, - 65F93C4212EE09280047DB36 /* crc.o */, - 65F93C4312EE09280047DB36 /* dep */, - 65F93C7C12EE09280047DB36 /* fifo_buffer.lst */, - 65F93C7D12EE09280047DB36 /* fifo_buffer.o */, - 65F93C7E12EE09280047DB36 /* gpio_in.lst */, - 65F93C7F12EE09280047DB36 /* gpio_in.o */, - 65F93C8012EE09280047DB36 /* main.lst */, - 65F93C8112EE09280047DB36 /* main.o */, - 65F93C8212EE09280047DB36 /* misc.lst */, - 65F93C8312EE09280047DB36 /* misc.o */, - 65F93C8412EE09290047DB36 /* packet_handler.lst */, - 65F93C8512EE09290047DB36 /* packet_handler.o */, - 65F93C8612EE09290047DB36 /* pios_adc.lst */, - 65F93C8712EE09290047DB36 /* pios_adc.o */, - 65F93C8812EE09290047DB36 /* pios_board.lst */, - 65F93C8912EE09290047DB36 /* pios_board.o */, - 65F93C8A12EE09290047DB36 /* pios_com.lst */, - 65F93C8B12EE09290047DB36 /* pios_com.o */, - 65F93C8C12EE09290047DB36 /* pios_delay.lst */, - 65F93C8D12EE09290047DB36 /* pios_delay.o */, - 65F93C8E12EE09290047DB36 /* pios_gpio.lst */, - 65F93C8F12EE09290047DB36 /* pios_gpio.o */, - 65F93C9012EE09290047DB36 /* pios_irq.lst */, - 65F93C9112EE09290047DB36 /* pios_irq.o */, - 65F93C9212EE09290047DB36 /* pios_led.lst */, - 65F93C9312EE09290047DB36 /* pios_led.o */, - 65F93C9412EE09290047DB36 /* pios_spi.lst */, - 65F93C9512EE09290047DB36 /* pios_spi.o */, - 65F93C9612EE09290047DB36 /* pios_sys.lst */, - 65F93C9712EE09290047DB36 /* pios_sys.o */, - 65F93C9812EE09290047DB36 /* pios_usart.lst */, - 65F93C9912EE09290047DB36 /* pios_usart.o */, - 65F93C9A12EE09290047DB36 /* pios_usb_hid.lst */, - 65F93C9B12EE09290047DB36 /* pios_usb_hid.o */, - 65F93C9C12EE09290047DB36 /* pios_usb_hid_desc.lst */, - 65F93C9D12EE09290047DB36 /* pios_usb_hid_desc.o */, - 65F93C9E12EE09290047DB36 /* pios_usb_hid_istr.lst */, - 65F93C9F12EE09290047DB36 /* pios_usb_hid_istr.o */, - 65F93CA012EE09290047DB36 /* pios_usb_hid_prop.lst */, - 65F93CA112EE09290047DB36 /* pios_usb_hid_prop.o */, - 65F93CA212EE09290047DB36 /* pios_usb_hid_pwr.lst */, - 65F93CA312EE09290047DB36 /* pios_usb_hid_pwr.o */, - 65F93CA412EE09290047DB36 /* pios_wdg.lst */, - 65F93CA512EE09290047DB36 /* pios_wdg.o */, - 65F93CA612EE09290047DB36 /* PipXtreme.bin */, - 65F93CA712EE09290047DB36 /* PipXtreme.elf */, - 65F93CA812EE09290047DB36 /* PipXtreme.hex */, - 65F93CA912EE09290047DB36 /* PipXtreme.lss */, - 65F93CAA12EE09290047DB36 /* PipXtreme.map */, - 65F93CAB12EE09290047DB36 /* PipXtreme.sym */, - 65F93CAC12EE09290047DB36 /* printf-stdarg.lst */, - 65F93CAD12EE09290047DB36 /* printf-stdarg.o */, - 65F93CAE12EE09290047DB36 /* rfm22b.lst */, - 65F93CAF12EE09290047DB36 /* rfm22b.o */, - 65F93CB012EE09290047DB36 /* saved_settings.lst */, - 65F93CB112EE09290047DB36 /* saved_settings.o */, - 65F93CB212EE09290047DB36 /* startup_stm32f10x_MD.lst */, - 65F93CB312EE09290047DB36 /* startup_stm32f10x_MD.o */, - 65F93CB412EE09290047DB36 /* stm32f10x_adc.lst */, - 65F93CB512EE09290047DB36 /* stm32f10x_adc.o */, - 65F93CB612EE09290047DB36 /* stm32f10x_bkp.lst */, - 65F93CB712EE09290047DB36 /* stm32f10x_bkp.o */, - 65F93CB812EE09290047DB36 /* stm32f10x_crc.lst */, - 65F93CB912EE09290047DB36 /* stm32f10x_crc.o */, - 65F93CBA12EE09290047DB36 /* stm32f10x_dac.lst */, - 65F93CBB12EE09290047DB36 /* stm32f10x_dac.o */, - 65F93CBC12EE09290047DB36 /* stm32f10x_dbgmcu.lst */, - 65F93CBD12EE09290047DB36 /* stm32f10x_dbgmcu.o */, - 65F93CBE12EE09290047DB36 /* stm32f10x_dma.lst */, - 65F93CBF12EE09290047DB36 /* stm32f10x_dma.o */, - 65F93CC012EE09290047DB36 /* stm32f10x_exti.lst */, - 65F93CC112EE09290047DB36 /* stm32f10x_exti.o */, - 65F93CC212EE09290047DB36 /* stm32f10x_flash.lst */, - 65F93CC312EE09290047DB36 /* stm32f10x_flash.o */, - 65F93CC412EE09290047DB36 /* stm32f10x_gpio.lst */, - 65F93CC512EE09290047DB36 /* stm32f10x_gpio.o */, - 65F93CC612EE09290047DB36 /* stm32f10x_i2c.lst */, - 65F93CC712EE09290047DB36 /* stm32f10x_i2c.o */, - 65F93CC812EE09290047DB36 /* stm32f10x_iwdg.lst */, - 65F93CC912EE09290047DB36 /* stm32f10x_iwdg.o */, - 65F93CCA12EE09290047DB36 /* stm32f10x_pwr.lst */, - 65F93CCB12EE09290047DB36 /* stm32f10x_pwr.o */, - 65F93CCC12EE09290047DB36 /* stm32f10x_rcc.lst */, - 65F93CCD12EE09290047DB36 /* stm32f10x_rcc.o */, - 65F93CCE12EE09290047DB36 /* stm32f10x_rtc.lst */, - 65F93CCF12EE09290047DB36 /* stm32f10x_rtc.o */, - 65F93CD012EE09290047DB36 /* stm32f10x_spi.lst */, - 65F93CD112EE09290047DB36 /* stm32f10x_spi.o */, - 65F93CD212EE09290047DB36 /* stm32f10x_tim.lst */, - 65F93CD312EE09290047DB36 /* stm32f10x_tim.o */, - 65F93CD412EE09290047DB36 /* stm32f10x_usart.lst */, - 65F93CD512EE09290047DB36 /* stm32f10x_usart.o */, - 65F93CD612EE09290047DB36 /* stopwatch.lst */, - 65F93CD712EE09290047DB36 /* stopwatch.o */, - 65F93CD812EE09290047DB36 /* system_stm32f10x.lst */, - 65F93CD912EE09290047DB36 /* system_stm32f10x.o */, - 65F93CDA12EE09290047DB36 /* transparent_comms.lst */, - 65F93CDB12EE09290047DB36 /* transparent_comms.o */, - 65F93CDC12EE09290047DB36 /* uavtalk_comms.lst */, - 65F93CDD12EE09290047DB36 /* uavtalk_comms.o */, - 65F93CDE12EE09290047DB36 /* usb_core.lst */, - 65F93CDF12EE09290047DB36 /* usb_core.o */, - 65F93CE012EE09290047DB36 /* usb_init.lst */, - 65F93CE112EE09290047DB36 /* usb_init.o */, - 65F93CE212EE09290047DB36 /* usb_int.lst */, - 65F93CE312EE09290047DB36 /* usb_int.o */, - 65F93CE412EE09290047DB36 /* usb_mem.lst */, - 65F93CE512EE09290047DB36 /* usb_mem.o */, - 65F93CE612EE09290047DB36 /* usb_regs.lst */, - 65F93CE712EE09290047DB36 /* usb_regs.o */, - 65F93CE812EE09290047DB36 /* usb_sil.lst */, - 65F93CE912EE09290047DB36 /* usb_sil.o */, - 65F93CEA12EE09290047DB36 /* watchdog.lst */, - 65F93CEB12EE09290047DB36 /* watchdog.o */, - ); - path = Build; - sourceTree = ""; - }; - 65F93C4312EE09280047DB36 /* dep */ = { - isa = PBXGroup; - children = ( - 65F93C4412EE09280047DB36 /* aes.o.d */, - 65F93C4512EE09280047DB36 /* buffer.o.d */, - 65F93C4612EE09280047DB36 /* core_cm3.o.d */, - 65F93C4712EE09280047DB36 /* crc.o.d */, - 65F93C4812EE09280047DB36 /* fifo_buffer.o.d */, - 65F93C4912EE09280047DB36 /* gpio_in.o.d */, - 65F93C4A12EE09280047DB36 /* main.o.d */, - 65F93C4B12EE09280047DB36 /* misc.o.d */, - 65F93C4C12EE09280047DB36 /* packet_handler.o.d */, - 65F93C4D12EE09280047DB36 /* pios_adc.o.d */, - 65F93C4E12EE09280047DB36 /* pios_board.o.d */, - 65F93C4F12EE09280047DB36 /* pios_com.o.d */, - 65F93C5012EE09280047DB36 /* pios_delay.o.d */, - 65F93C5112EE09280047DB36 /* pios_gpio.o.d */, - 65F93C5212EE09280047DB36 /* pios_irq.o.d */, - 65F93C5312EE09280047DB36 /* pios_led.o.d */, - 65F93C5412EE09280047DB36 /* pios_spi.o.d */, - 65F93C5512EE09280047DB36 /* pios_sys.o.d */, - 65F93C5612EE09280047DB36 /* pios_usart.o.d */, - 65F93C5712EE09280047DB36 /* pios_usb_hid.o.d */, - 65F93C5812EE09280047DB36 /* pios_usb_hid_desc.o.d */, - 65F93C5912EE09280047DB36 /* pios_usb_hid_istr.o.d */, - 65F93C5A12EE09280047DB36 /* pios_usb_hid_prop.o.d */, - 65F93C5B12EE09280047DB36 /* pios_usb_hid_pwr.o.d */, - 65F93C5C12EE09280047DB36 /* pios_wdg.o.d */, - 65F93C5D12EE09280047DB36 /* printf-stdarg.o.d */, - 65F93C5E12EE09280047DB36 /* rfm22b.o.d */, - 65F93C5F12EE09280047DB36 /* saved_settings.o.d */, - 65F93C6012EE09280047DB36 /* stm32f10x_adc.o.d */, - 65F93C6112EE09280047DB36 /* stm32f10x_bkp.o.d */, - 65F93C6212EE09280047DB36 /* stm32f10x_crc.o.d */, - 65F93C6312EE09280047DB36 /* stm32f10x_dac.o.d */, - 65F93C6412EE09280047DB36 /* stm32f10x_dbgmcu.o.d */, - 65F93C6512EE09280047DB36 /* stm32f10x_dma.o.d */, - 65F93C6612EE09280047DB36 /* stm32f10x_exti.o.d */, - 65F93C6712EE09280047DB36 /* stm32f10x_flash.o.d */, - 65F93C6812EE09280047DB36 /* stm32f10x_gpio.o.d */, - 65F93C6912EE09280047DB36 /* stm32f10x_i2c.o.d */, - 65F93C6A12EE09280047DB36 /* stm32f10x_iwdg.o.d */, - 65F93C6B12EE09280047DB36 /* stm32f10x_pwr.o.d */, - 65F93C6C12EE09280047DB36 /* stm32f10x_rcc.o.d */, - 65F93C6D12EE09280047DB36 /* stm32f10x_rtc.o.d */, - 65F93C6E12EE09280047DB36 /* stm32f10x_spi.o.d */, - 65F93C6F12EE09280047DB36 /* stm32f10x_tim.o.d */, - 65F93C7012EE09280047DB36 /* stm32f10x_usart.o.d */, - 65F93C7112EE09280047DB36 /* stopwatch.o.d */, - 65F93C7212EE09280047DB36 /* system_stm32f10x.o.d */, - 65F93C7312EE09280047DB36 /* transparent_comms.o.d */, - 65F93C7412EE09280047DB36 /* uavtalk_comms.o.d */, - 65F93C7512EE09280047DB36 /* usb_core.o.d */, - 65F93C7612EE09280047DB36 /* usb_init.o.d */, - 65F93C7712EE09280047DB36 /* usb_int.o.d */, - 65F93C7812EE09280047DB36 /* usb_mem.o.d */, - 65F93C7912EE09280047DB36 /* usb_regs.o.d */, - 65F93C7A12EE09280047DB36 /* usb_sil.o.d */, - 65F93C7B12EE09280047DB36 /* watchdog.o.d */, - ); - path = dep; - sourceTree = ""; - }; - 65F93CEE12EE09290047DB36 /* inc */ = { - isa = PBXGroup; - children = ( - 65F93CEF12EE09290047DB36 /* aes.h */, - 65F93CF012EE09290047DB36 /* crc.h */, - 65F93CF112EE09290047DB36 /* gpio_in.h */, - 65F93CF212EE09290047DB36 /* main.h */, - 65F93CF312EE09290047DB36 /* packet_handler.h */, - 65F93CF412EE09290047DB36 /* pios_config.h */, - 65F93CF512EE09290047DB36 /* pios_usb.h */, - 65F93CF612EE09290047DB36 /* pios_usb_hid_desc.h */, - 65F93CF712EE09290047DB36 /* rfm22b.h */, - 65F93CF812EE09290047DB36 /* saved_settings.h */, - 65F93CF912EE09290047DB36 /* stopwatch.h */, - 65F93CFA12EE09290047DB36 /* transparent_comms.h */, - 65F93CFB12EE09290047DB36 /* uavtalk_comms.h */, - 65F93CFC12EE09290047DB36 /* usb_conf.h */, - 65F93CFD12EE09290047DB36 /* watchdog.h */, - ); - path = inc; - sourceTree = ""; - }; - 65FF4BB313791C3300146BE4 /* Bootloaders */ = { - isa = PBXGroup; - children = ( - 65FF4BB413791C3300146BE4 /* AHRS */, - 65FF4BC413791C3300146BE4 /* BootloaderUpdater */, - 65FF4BCB13791C3300146BE4 /* CopterControl */, - 65FF4BD513791C3300146BE4 /* OpenPilot */, - 65FF4BE213791C3300146BE4 /* PipXtreme */, - ); - name = Bootloaders; - path = ../../Bootloaders; - sourceTree = SOURCE_ROOT; - }; - 65FF4BB413791C3300146BE4 /* AHRS */ = { - isa = PBXGroup; - children = ( - 65FF4BB513791C3300146BE4 /* ahrs_slave_test.c */, - 65FF4BB613791C3300146BE4 /* ahrs_spi_program.c */, - 65FF4BB713791C3300146BE4 /* ahrs_spi_program_master.c */, - 65FF4BB813791C3300146BE4 /* ahrs_spi_program_slave.c */, - 65FF4BB913791C3300146BE4 /* bl_fsm.c */, - 65FF4BBA13791C3300146BE4 /* inc */, - 65FF4BC113791C3300146BE4 /* main.c */, - 65FF4BC213791C3300146BE4 /* Makefile */, - 65FF4BC313791C3300146BE4 /* pios_board.c */, - ); - path = AHRS; - sourceTree = ""; - }; - 65FF4BBA13791C3300146BE4 /* inc */ = { - isa = PBXGroup; - children = ( - 65FF4BBB13791C3300146BE4 /* ahrs_bl.h */, - 65FF4BBC13791C3300146BE4 /* ahrs_spi_program.h */, - 65FF4BBD13791C3300146BE4 /* ahrs_spi_program_master.h */, - 65FF4BBE13791C3300146BE4 /* ahrs_spi_program_slave.h */, - 65FF4BBF13791C3300146BE4 /* bl_fsm.h */, - 65FF4BC013791C3300146BE4 /* pios_config.h */, - ); - path = inc; - sourceTree = ""; - }; - 65FF4BC413791C3300146BE4 /* BootloaderUpdater */ = { - isa = PBXGroup; - children = ( - 65FF4BC513791C3300146BE4 /* inc */, - 65FF4BC713791C3300146BE4 /* main.c */, - 65FF4BC813791C3300146BE4 /* Makefile */, - 65FF4BC913791C3300146BE4 /* pios_board.c */, - 65FF4BCA13791C3300146BE4 /* test.bin */, - ); - path = BootloaderUpdater; - sourceTree = ""; - }; - 65FF4BC513791C3300146BE4 /* inc */ = { - isa = PBXGroup; - children = ( - 65FF4BC613791C3300146BE4 /* pios_config.h */, - ); - path = inc; - sourceTree = ""; - }; - 65FF4BCB13791C3300146BE4 /* CopterControl */ = { - isa = PBXGroup; - children = ( - 65FF4BCC13791C3300146BE4 /* inc */, - 65FF4BD113791C3300146BE4 /* main.c */, - 65FF4BD213791C3300146BE4 /* Makefile */, - 65FF4BD313791C3300146BE4 /* op_dfu.c */, - 65FF4BD413791C3300146BE4 /* pios_board.c */, - ); - path = CopterControl; - sourceTree = ""; - }; - 65FF4BCC13791C3300146BE4 /* inc */ = { - isa = PBXGroup; - children = ( - 65FF4BCD13791C3300146BE4 /* common.h */, - 65FF4BCE13791C3300146BE4 /* op_dfu.h */, - 65FF4BCF13791C3300146BE4 /* pios_config.h */, - 65FF4BD013791C3300146BE4 /* pios_usb.h */, - ); - path = inc; - sourceTree = ""; - }; - 65FF4BD513791C3300146BE4 /* OpenPilot */ = { - isa = PBXGroup; - children = ( - 65FF4BD613791C3300146BE4 /* inc */, - 65FF4BDC13791C3300146BE4 /* main.c */, - 65FF4BDD13791C3300146BE4 /* Makefile */, - 65FF4BDE13791C3300146BE4 /* op_dfu.c */, - 65FF4BDF13791C3300146BE4 /* pios_board.c */, - 65FF4BE013791C3300146BE4 /* ssp.c */, - 65FF4BE113791C3300146BE4 /* ssp_timer.c */, - ); - path = OpenPilot; - sourceTree = ""; - }; - 65FF4BD613791C3300146BE4 /* inc */ = { - isa = PBXGroup; - children = ( - 65FF4BD713791C3300146BE4 /* common.h */, - 65FF4BD813791C3300146BE4 /* op_dfu.h */, - 65FF4BD913791C3300146BE4 /* pios_config.h */, - 65FF4BDA13791C3300146BE4 /* pios_usb.h */, - 65FF4BDB13791C3300146BE4 /* ssp.h */, - ); - path = inc; - sourceTree = ""; - }; - 65FF4BE213791C3300146BE4 /* PipXtreme */ = { - isa = PBXGroup; - children = ( - 65FF4BE313791C3300146BE4 /* inc */, - 65FF4BE813791C3300146BE4 /* main.c */, - 65FF4BE913791C3300146BE4 /* Makefile */, - 65FF4BEA13791C3300146BE4 /* op_dfu.c */, - 65FF4BEB13791C3300146BE4 /* pios_board.c */, - ); - path = PipXtreme; - sourceTree = ""; - }; - 65FF4BE313791C3300146BE4 /* inc */ = { - isa = PBXGroup; - children = ( - 65FF4BE413791C3300146BE4 /* common.h */, - 65FF4BE513791C3300146BE4 /* op_dfu.h */, - 65FF4BE613791C3300146BE4 /* pios_config.h */, - 65FF4BE713791C3300146BE4 /* pios_usb.h */, - ); - path = inc; - sourceTree = ""; - }; - C6A0FF2B0290797F04C91782 /* Documentation */ = { - isa = PBXGroup; - children = ( - ); - name = Documentation; - sourceTree = ""; - }; /* End PBXGroup section */ /* Begin PBXLegacyTarget section */ diff --git a/flight/Project/Windows USB/OpenPilot-CDC.inf b/flight/Project/Windows USB/OpenPilot-CDC.inf new file mode 100644 index 000000000..7b799c8b0 --- /dev/null +++ b/flight/Project/Windows USB/OpenPilot-CDC.inf @@ -0,0 +1,35 @@ +[Version] +Signature="$Windows NT$" +Class=Ports +ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318} +Provider=%ProviderName% +DriverVer=10/15/2009,1.0.0.0 + +[MANUFACTURER] +%ProviderName%=DeviceList, NTx86, NTamd64 + +[DeviceList.NTx86] +%CopterControl%= DriverInstall,USB\VID_20A0&PID_415b&MI_00 +%PipXtreme%= DriverInstall,USB\VID_20A0&PID_415c&MI_00 + +[DeviceList.NTamd64] +%CopterControl%= DriverInstall,USB\VID_20A0&PID_415b&MI_00 +%PipXtreme%= DriverInstall,USB\VID_20A0&PID_415c&MI_00 + +[DriverInstall] +include=mdmcpq.inf +CopyFiles=FakeModemCopyFileSection +AddReg=LowerFilterAddReg,SerialPropPageAddReg + +[DriverInstall.Services] +include = mdmcpq.inf +AddService = usbser, 0x00000002, LowerFilter_Service_Inst + +; This adds the serial port property tab to the device properties dialog +[SerialPropPageAddReg] +HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider" + +[Strings] +ProviderName = "CDC Driver" +CopterControl = "OpenPilot CDC Driver" +PipXtreme = "OpenPilot CDC Driver" diff --git a/flight/Project/gdb/ahrs b/flight/Project/gdb/ahrs deleted file mode 100644 index 152723139..000000000 --- a/flight/Project/gdb/ahrs +++ /dev/null @@ -1,38 +0,0 @@ -define connect - target remote localhost:3334 - monitor cortex_m3 vector_catch all - file ./build/ahrs/AHRS.elf -end -#monitor reset halt - -define hook-step - monitor cortex_m3 maskisr on -end -define hookpost-step - monitor cortex_m3 maskisr off -end - -define hook-stepi - monitor cortex_m3 maskisr on -end - -define hookpost-stepi - monitor cortex_m3 maskisr off -end - -define hook-next - monitor cortex_m3 maskisr on -end - -define hookpost-next - monitor cortex_m3 maskisr off -end - -define hook-finish - monitor cortex_m3 maskisr on -end - -define hookpost-finish - monitor cortex_m3 maskisr off -end - diff --git a/flight/Project/gdb/bl_revolution b/flight/Project/gdb/bl_revolution new file mode 100644 index 000000000..362e273dc --- /dev/null +++ b/flight/Project/gdb/bl_revolution @@ -0,0 +1,4 @@ +define connect + target remote localhost:3333 + file ./build/bl_revolution/bl_revolution.elf +end diff --git a/flight/Project/gdb/revolution b/flight/Project/gdb/revolution new file mode 100644 index 000000000..058f43809 --- /dev/null +++ b/flight/Project/gdb/revolution @@ -0,0 +1,4 @@ +define connect + target remote localhost:3333 + file ./build/fw_revolution/fw_revolution.elf +end diff --git a/flight/RemoteSystemsTempFiles/.project b/flight/RemoteSystemsTempFiles/.project new file mode 100644 index 000000000..5447a64fa --- /dev/null +++ b/flight/RemoteSystemsTempFiles/.project @@ -0,0 +1,12 @@ + + + RemoteSystemsTempFiles + + + + + + + org.eclipse.rse.ui.remoteSystemsTempNature + + diff --git a/flight/OpenPilot/Makefile b/flight/Revolution/Makefile similarity index 63% rename from flight/OpenPilot/Makefile rename to flight/Revolution/Makefile index 96be8ff31..ce8a45b6d 100644 --- a/flight/OpenPilot/Makefile +++ b/flight/Revolution/Makefile @@ -1,26 +1,26 @@ - ##### - # Project: OpenPilot - # - # - # Makefile for OpenPilot project build PiOS and the AP. - # - # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. - # - # - # This program is free software; you can redistribute it and/or modify - # it under the terms of the GNU General Public License as published by - # the Free Software Foundation; either version 3 of the License, or - # (at your option) any later version. - # - # This program is distributed in the hope that it will be useful, but - # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - # for more details. - # - # You should have received a copy of the GNU General Public License along - # with this program; if not, write to the Free Software Foundation, Inc., - # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - ##### +##### +# Project: OpenPilot INS +# +# +# Makefile for OpenPilot INS project +# +# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. +# +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, but +# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +# for more details. +# +# You should have received a copy of the GNU General Public License along +# with this program; if not, write to the Free Software Foundation, Inc., +# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) TOP := $(realpath $(WHEREAMI)/../../) @@ -34,23 +34,12 @@ TARGET := fw_$(BOARD_NAME) OUTDIR := $(TOP)/build/$(TARGET) # Set developer code and compile options -# Set to YES to compile for debugging -DEBUG ?= YES - -# Include objects that are just nice information to show -DIAGNOSTICS ?= YES -DIAG_TASKS ?= YES - -# Set to YES to use the Servo output pins for debugging via scope or logic analyser -ENABLE_DEBUG_PINS ?= NO - -# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs -ENABLE_AUX_UART ?= NO +# Set to YES for debugging +DEBUG ?= NO # Set to YES when using Code Sourcery toolchain -CODE_SOURCERY ?= YES +CODE_SOURCERY ?= NO -# Remove command is different for Code Sourcery on Windows ifeq ($(CODE_SOURCERY), YES) REMOVE_CMD = cs-rm else @@ -59,16 +48,14 @@ endif FLASH_TOOL = OPENOCD - # List of modules to include -OPTMODULES = CameraStab GPS -MODULES = Actuator ManualControl Altitude AHRSComms Stabilization Guidance FirmwareIAP -PYMODULES = FlightPlan -#MODULES = Telemetry Example -#MODULES = Telemetry MK/MKSerial -#MODULES = Telemetry -#MODULES += Osd/OsdEtStd +MODULES = Sensors Attitude/revolution ManualControl Stabilization Altitude/revolution Actuator GPS FirmwareIAP +MODULES += AltitudeHold +MODULES += CameraStab MODULES += Telemetry +#MODULES += OveroSync +PYMODULES = +#FlightPlan # Paths OPSYSTEM = ./System @@ -77,32 +64,24 @@ OPUAVTALK = ../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc OPUAVOBJ = ../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -OPTESTS = ./Tests -OPMODULEDIR = ../Modules -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = $(FLIGHTLIB)/inc PIOS = ../PiOS PIOSINC = $(PIOS)/inc -PIOSSTM32F10X = $(PIOS)/STM32F10x +OPMODULEDIR = ../Modules +FLIGHTLIB = ../Libraries +FLIGHTLIBINC = ../Libraries/inc +PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards -APPLIBDIR = $(PIOSSTM32F10X)/Libraries +PIOSCOMMONLIB = $(PIOSCOMMON)/Libraries +APPLIBDIR = $(PIOSSTM32F4XX)/Libraries STMLIBDIR = $(APPLIBDIR) -STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver -STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver +STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc -STMUSBSRCDIR = $(STMUSBDIR)/src -STMUSBINCDIR = $(STMUSBDIR)/inc -CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 -DOSFSDIR = $(APPLIBDIR)/dosfs -MSDDIR = $(APPLIBDIR)/msd -RTOSDIR = $(APPLIBDIR)/FreeRTOS -RTOSSRCDIR = $(RTOSDIR)/Source -RTOSINCDIR = $(RTOSSRCDIR)/include -DOXYGENDIR = ../Doc/Doxygen -AHRSBOOTLOADER = ../Bootloaders/AHRS/ -AHRSBOOTLOADERINC = $(AHRSBOOTLOADER)/inc +OPUAVOBJ = ../UAVObjects +OPUAVOBJINC = $(OPUAVOBJ)/inc +BOOT = ../Bootloaders/INS +BOOTINC = $(BOOT)/inc PYMITE = $(FLIGHTLIB)/PyMite PYMITELIB = $(PYMITE)/lib PYMITEPLAT = $(PYMITE)/platform/openpilot @@ -114,14 +93,18 @@ PYMITEINC += $(OUTDIR) FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans HWDEFSINC = ../board_hw_defs/$(BOARD_NAME) - UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight +SRC = +# optional component libraries +include $(PIOSCOMMONLIB)/FreeRTOS/library.mk +#include $(PIOSCOMMONLIB)/dosfs/library.mk +include $(PIOSCOMMONLIB)/msheap/library.mk + + # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files -ifndef TESTAPP - ## PyMite files and modules SRC += $(OUTDIR)/pmlib_img.c SRC += $(OUTDIR)/pmlib_nat.c @@ -133,139 +116,48 @@ PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} SRC += $(PYSRC) ## MODULES -SRC += ${foreach MOD, ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} ## OPENPILOT CORE: SRC += ${OPMODULEDIR}/System/systemmod.c -SRC += $(OPSYSTEM)/openpilot.c +SRC += $(OPSYSTEM)/revolution.c SRC += $(OPSYSTEM)/pios_board.c +SRC += $(OPSYSTEM)/pios_usb_board_data.c SRC += $(OPSYSTEM)/alarms.c SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c -else -## TESTCODE -SRC += $(OPTESTS)/test_common.c -SRC += $(OPTESTS)/$(TESTAPP).c -endif +#ifeq ($(DEBUG),YES) +SRC += $(OPSYSTEM)/dcc_stdio.c +SRC += $(OPSYSTEM)/cm3_fault_handlers.c +#endif +SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += $(FLIGHTLIB)/fifo_buffer.c +SRC += $(FLIGHTLIB)/WorldMagModel.c +SRC += $(FLIGHTLIB)/insgps13state.c +SRC += $(FLIGHTLIB)/taskmonitor.c -## UAVOBJECTS -ifndef TESTAPP -#include $(UAVOBJSYNTHDIR)/Makefile.inc -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) -endif +## PIOS Hardware (STM32F4xx) +include $(PIOS)/STM32F4xx/library.mk -## PIOS Hardware (STM32F10x) -SRC += $(PIOSSTM32F10X)/pios_sys.c -SRC += $(PIOSSTM32F10X)/pios_led.c -SRC += $(PIOSSTM32F10X)/pios_delay.c -SRC += $(PIOSSTM32F10X)/pios_usart.c -SRC += $(PIOSSTM32F10X)/pios_irq.c -SRC += $(PIOSSTM32F10X)/pios_adc.c -SRC += $(PIOSSTM32F10X)/pios_servo.c -SRC += $(PIOSSTM32F10X)/pios_i2c.c -SRC += $(PIOSSTM32F10X)/pios_spi.c -SRC += $(PIOSSTM32F10X)/pios_ppm.c -SRC += $(PIOSSTM32F10X)/pios_pwm.c -SRC += $(PIOSSTM32F10X)/pios_dsm.c -SRC += $(PIOSSTM32F10X)/pios_sbus.c -SRC += $(PIOSSTM32F10X)/pios_tim.c -SRC += $(PIOSSTM32F10X)/pios_debug.c -SRC += $(PIOSSTM32F10X)/pios_gpio.c -SRC += $(PIOSSTM32F10X)/pios_exti.c -SRC += $(PIOSSTM32F10X)/pios_rtc.c -SRC += $(PIOSSTM32F10X)/pios_wdg.c - - -# PIOS USB related files (seperated to make code maintenance more easy) -SRC += $(PIOSSTM32F10X)/pios_usb.c -SRC += $(PIOSSTM32F10X)/pios_usbhook.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid.c -SRC += $(PIOSSTM32F10X)/pios_usb_cdc.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c -SRC += $(OPSYSTEM)/pios_usb_board_data.c +## PIOS Hardware (Common) +SRC += $(PIOSCOMMON)/pios_mpu6000.c +SRC += $(PIOSCOMMON)/pios_bma180.c +SRC += $(PIOSCOMMON)/pios_l3gd20.c +SRC += $(PIOSCOMMON)/pios_hmc5883.c +SRC += $(PIOSCOMMON)/pios_ms5611.c +SRC += $(PIOSCOMMON)/pios_crc.c +SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_rcvr.c +SRC += $(PIOSCOMMON)/pios_flash_jedec.c +SRC += $(PIOSCOMMON)/pios_flashfs_objlist.c +SRC += $(PIOSCOMMON)/printf-stdarg.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c -## PIOS Hardware (Common) -SRC += $(PIOSCOMMON)/pios_crc.c -SRC += $(PIOSCOMMON)/pios_sdcard.c -SRC += $(PIOSCOMMON)/pios_com.c -SRC += $(PIOSCOMMON)/pios_bmp085.c -SRC += $(PIOSCOMMON)/pios_hcsr04.c -SRC += $(PIOSCOMMON)/pios_i2c_esc.c -SRC += $(PIOSCOMMON)/pios_iap.c -SRC += $(PIOSCOMMON)/pios_bl_helper.c -SRC += $(PIOSCOMMON)/pios_rcvr.c -SRC += $(PIOSCOMMON)/printf-stdarg.c -SRC += $(FLIGHTLIB)/ahrs_spi_comm.c -SRC += $(FLIGHTLIB)/ahrs_comm_objects.c -## Libraries for flight calculations -SRC += $(FLIGHTLIB)/fifo_buffer.c -SRC += $(FLIGHTLIB)/WorldMagModel.c -SRC += $(FLIGHTLIB)/CoordinateConversions.c -SRC += $(FLIGHTLIB)/taskmonitor.c - -## CMSIS for STM32 -SRC += $(CMSISDIR)/core_cm3.c -SRC += $(CMSISDIR)/system_stm32f10x.c - -## Used parts of the STM-Library -SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c -SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c -SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c -SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c -SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c -SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c -SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c -SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c -SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c -SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c -SRC += $(STMSPDSRCDIR)/stm32f10x_iwdg.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c -SRC += $(STMSPDSRCDIR)/misc.c - -## STM32 USB Library -SRC += $(STMUSBSRCDIR)/usb_core.c -SRC += $(STMUSBSRCDIR)/usb_init.c -SRC += $(STMUSBSRCDIR)/usb_int.c -SRC += $(STMUSBSRCDIR)/usb_mem.c -SRC += $(STMUSBSRCDIR)/usb_regs.c -SRC += $(STMUSBSRCDIR)/usb_sil.c - -## RTOS -SRC += $(RTOSSRCDIR)/list.c -SRC += $(RTOSSRCDIR)/queue.c -SRC += $(RTOSSRCDIR)/tasks.c - -## RTOS Portable -SRC += $(RTOSSRCDIR)/portable/GCC/ARM_CM3/port.c -SRC += $(RTOSSRCDIR)/portable/MemMang/heap_2.c - -## Dosfs file system -SRC += $(DOSFSDIR)/dosfs.c -SRC += $(DOSFSDIR)/dfs_sdcard.c - -## AHRS boot loader comms -SRC += $(AHRSBOOTLOADER)/ahrs_spi_program_master.c -SRC += $(AHRSBOOTLOADER)/ahrs_spi_program.c - -## Mass Storage Device -#SRC += $(MSDDIR)/msd.c -#SRC += $(MSDDIR)/msd_bot.c -#SRC += $(MSDDIR)/msd_desc.c -#SRC += $(MSDDIR)/msd_memory.c -#SRC += $(MSDDIR)/msd_scsi.c -#SRC += $(MSDDIR)/msd_scsi_data.c +include ./UAVObjects.inc +SRC += $(UAVOBJSRC) # List C source files here which must be compiled in ARM-Mode (no -mthumb). # use file-extension c for "c-only"-files @@ -288,40 +180,46 @@ CPPSRCARM = # Even though the DOS/Win* filesystem matches both .s and .S the same, # it will preserve the spelling of the filenames, and gcc itself does # care about how the name is spelled on its command-line. -ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S + # List Assembler source files here which must be assembled in ARM-Mode.. ASRCARM = # List any extra directories to look for include files here. # Each directory must be seperated by a space. -EXTRAINCDIRS = $(OPSYSTEM) +EXTRAINCDIRS += $(PIOS) +EXTRAINCDIRS += $(PIOSINC) EXTRAINCDIRS += $(OPSYSTEMINC) EXTRAINCDIRS += $(OPUAVTALK) EXTRAINCDIRS += $(OPUAVTALKINC) EXTRAINCDIRS += $(OPUAVOBJ) EXTRAINCDIRS += $(OPUAVOBJINC) EXTRAINCDIRS += $(UAVOBJSYNTHDIR) -EXTRAINCDIRS += $(PIOS) -EXTRAINCDIRS += $(PIOSINC) EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(PIOSSTM32F10X) +EXTRAINCDIRS += $(PIOSSTM32F4XX) EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) EXTRAINCDIRS += $(STMSPDINCDIR) -EXTRAINCDIRS += $(STMUSBINCDIR) EXTRAINCDIRS += $(CMSISDIR) -EXTRAINCDIRS += $(DOSFSDIR) -EXTRAINCDIRS += $(MSDDIR) -EXTRAINCDIRS += $(RTOSINCDIR) -EXTRAINCDIRS += $(APPLIBDIR) -EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3 -EXTRAINCDIRS += $(AHRSBOOTLOADERINC) +EXTRAINCDIRS += $(OPUAVSYNTHDIR) +EXTRAINCDIRS += $(BOOTINC) EXTRAINCDIRS += $(PYMITEINC) EXTRAINCDIRS += $(HWDEFSINC) -EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc +# Generate intermediate code +gencode: ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h +$(PYSRC): gencode + +PYTHON = python + +# Generate code for PyMite +${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) + @echo $(MSG_PYMITEINIT) $(call toprel, $@) + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) + @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py +EXTRAINCDIRS += ${foreach MOD, ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc # List any extra directories to look for library files here. # Also add directories where the linker should search for @@ -338,18 +236,33 @@ EXTRA_LIBDIRS = EXTRA_LIBS = # Path to Linker-Scripts -LINKERSCRIPTPATH = $(PIOSSTM32F10X) +LINKERSCRIPTPATH = $(PIOSSTM32F4XX) # Optimization level, can be [0, 1, 2, 3, s]. # 0 = turn off optimization. s = optimize for size. # (Note: 3 is not always the best optimization level. See avr-libc FAQ.) ifeq ($(DEBUG),YES) -OPT = 0 +CFLAGS += -O0 +CFLAGS += -DGENERAL_COV +CFLAGS += -finstrument-functions -ffixed-r10 else -OPT = s +CFLAGS += -Os endif + + +# common architecture-specific flags from the device-specific library makefile +CFLAGS += $(ARCHFLAGS) + +CFLAGS += -DDIAGNOSTICS +CFLAGS += -DDIAG_TASKS + +# This is not the best place for these. Really should abstract out +# to the board file or something +CFLAGS += -DSTM32F4XX +CFLAGS += -DMEM_SIZE=1024000000 + # Output format. (can be ihex or binary or both) # binary to create a load-image in raw-binary format i.e. for SAM-BA, # ihex to create a load-image in Intel hex format @@ -362,18 +275,10 @@ DEBUGF = dwarf-2 # Place project-specific -D (define) and/or # -U options for C here. -CDEFS = -DSTM32F10X_$(MODEL) +CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ) +CDEFS += -DSYSCLK_FREQ=$(SYSCLK_FREQ) CDEFS += -DUSE_STDPERIPH_DRIVER CDEFS += -DUSE_$(BOARD) -ifeq ($(ENABLE_DEBUG_PINS), YES) -CDEFS += -DPIOS_ENABLE_DEBUG_PINS -endif -ifeq ($(ENABLE_AUX_UART), YES) -CDEFS += -DPIOS_ENABLE_AUX_UART -endif - -# Declare all non-optional modules as built-in to force inclusion -CDEFS += ${foreach MOD, ${MODULES}, -DMODULE_$(MOD)_BUILTIN } # Place project-specific -D and/or -U options for # Assembler with preprocessor here. @@ -400,20 +305,10 @@ CSTANDARD = -std=gnu99 # # Flags for C and C++ (arm-elf-gcc/arm-elf-g++) -ifeq ($(DEBUG),YES) -CFLAGS += -DDEBUG -endif - -ifeq ($(DIAGNOSTICS),YES) -CFLAGS += -DDIAGNOSTICS -endif - -ifeq ($(DIAG_TASKS),YES) -CFLAGS += -DDIAG_TASKS -endif - CFLAGS += -g$(DEBUGF) -CFLAGS += -O$(OPT) + +CFLAGS += -ffast-math + CFLAGS += -mcpu=$(MCU) CFLAGS += $(CDEFS) CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. @@ -425,7 +320,7 @@ CFLAGS += -fpromote-loop-indices endif CFLAGS += -Wall -CFLAGS += -Werror +#CFLAGS += -Werror CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) # Compiler flags to generate dependency files: CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d @@ -437,7 +332,7 @@ CONLYFLAGS += $(CSTANDARD) # Assembler flags. # -Wa,...: tell GCC to pass this to the assembler. # -ahlns: create listing -ASFLAGS = -mcpu=$(MCU) -mthumb -I. -x assembler-with-cpp +ASFLAGS = $(ARCHFLAGS) -mthumb -I. -x assembler-with-cpp ASFLAGS += $(ADEFS) ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) @@ -455,13 +350,13 @@ LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) LDFLAGS += $(MATH_LIB) LDFLAGS += -lc -lgcc -# Set linker-script name depending on selected submodel name -LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_memory.ld -LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_sections.ld +#Linker scripts +LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) + # Define programs and commands. REMOVE = $(REMOVE_CMD) -f -PYTHON = python +PYHON = python # List of all source files. ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) @@ -493,14 +388,6 @@ endif endif endif -# Generate intermediate code - -# Generate code for PyMite -${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) - @echo $(MSG_PYMITEINIT) $(call toprel, $@) - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) - @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py # Link: create ELF output file from object files. $(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ))) @@ -534,14 +421,14 @@ $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin $(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino opfw -elf: $(OUTDIR)/$(TARGET).elf -lss: $(OUTDIR)/$(TARGET).lss -sym: $(OUTDIR)/$(TARGET).sym -hex: $(OUTDIR)/$(TARGET).hex -bin: $(OUTDIR)/$(TARGET).bin +elf: $(OUTDIR)/$(TARGET).elf +lss: $(OUTDIR)/$(TARGET).lss +sym: $(OUTDIR)/$(TARGET).sym +hex: $(OUTDIR)/$(TARGET).hex +bin: $(OUTDIR)/$(TARGET).bin bino: $(OUTDIR)/$(TARGET).bin.o opfw: $(OUTDIR)/$(TARGET).opfw @@ -574,8 +461,6 @@ clean_list : $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).sym $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).lss $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin.o - $(V1) $(REMOVE) $(wildcard $(OUTDIR)/*.c) - $(V1) $(REMOVE) $(wildcard $(OUTDIR)/*.h) $(V1) $(REMOVE) $(ALLOBJ) $(V1) $(REMOVE) $(LSTFILES) $(V1) $(REMOVE) $(DEPFILES) @@ -584,7 +469,6 @@ clean_list : $(V1) $(REMOVE) $(CPPSRC:.cpp=.s) $(V1) $(REMOVE) $(CPPSRCARM:.cpp=.s) - # Create output files directory # all known MS Windows OS define the ComSpec environment variable ifdef ComSpec @@ -597,7 +481,7 @@ endif ifdef ComSpec -include $(shell md $(subst /,\\,$(OUTDIR))\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) else --include $(shell mkdir -p $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) +-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) endif # Listing of phony targets. diff --git a/flight/OpenPilot/System/alarms.c b/flight/Revolution/System/alarms.c similarity index 100% rename from flight/OpenPilot/System/alarms.c rename to flight/Revolution/System/alarms.c diff --git a/flight/Revolution/System/cm3_fault_handlers.c b/flight/Revolution/System/cm3_fault_handlers.c new file mode 100644 index 000000000..af26e2ad9 --- /dev/null +++ b/flight/Revolution/System/cm3_fault_handlers.c @@ -0,0 +1,87 @@ +/* + * cm3_fault_handlers.c + * + * Created on: Apr 24, 2011 + * Author: msmith + */ + +#include +#include "dcc_stdio.h" +#ifdef STM32F4XX +# include "stm32f4xx.h" +#endif +#ifdef STM32F2XX +# include "stm32f2xx.h" +#endif + +#define FAULT_TRAMPOLINE(_vec) \ +__attribute__((naked, no_instrument_function)) \ +void \ +_vec##_Handler(void) \ +{ \ + __asm( ".syntax unified\n" \ + "MOVS R0, #4 \n" \ + "MOV R1, LR \n" \ + "TST R0, R1 \n" \ + "BEQ 1f \n" \ + "MRS R0, PSP \n" \ + "B " #_vec "_Handler2 \n" \ + "1: \n" \ + "MRS R0, MSP \n" \ + "B " #_vec "_Handler2 \n" \ + ".syntax divided\n"); \ +} \ +struct hack + +struct cm3_frame { + uint32_t r0; + uint32_t r1; + uint32_t r2; + uint32_t r3; + uint32_t r12; + uint32_t lr; + uint32_t pc; + uint32_t psr; +}; + +FAULT_TRAMPOLINE(HardFault); +FAULT_TRAMPOLINE(BusFault); +FAULT_TRAMPOLINE(UsageFault); + +/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */ +#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg)) + +void +HardFault_Handler2(struct cm3_frame *frame) +{ + dbg_write_str("\nHARD FAULT"); + dbg_write_hex32(frame->pc); + dbg_write_char('\n'); + dbg_write_hex32(SCB_REG(HFSR)); + dbg_write_char('\n'); + for (;;); +} + +void +BusFault_Handler2(struct cm3_frame *frame) +{ + dbg_write_str("\nBUS FAULT"); + dbg_write_hex32(frame->pc); + dbg_write_char('\n'); + dbg_write_hex32(SCB_REG(CFSR)); + dbg_write_char('\n'); + dbg_write_hex32(SCB_REG(BFAR)); + dbg_write_char('\n'); + for (;;); +} + +void +UsageFault_Handler2(struct cm3_frame *frame) +{ + dbg_write_str("\nUSAGE FAULT"); + dbg_write_hex32(frame->pc); + dbg_write_char('\n'); + dbg_write_hex32(SCB_REG(CFSR)); + dbg_write_char('\n'); + for (;;); +} diff --git a/flight/Revolution/System/dcc_stdio.c b/flight/Revolution/System/dcc_stdio.c new file mode 100644 index 000000000..bf5bd85ad --- /dev/null +++ b/flight/Revolution/System/dcc_stdio.c @@ -0,0 +1,149 @@ +/*************************************************************************** + * Copyright (C) 2008 by Dominic Rath * + * Dominic.Rath@gmx.de * + * Copyright (C) 2008 by Spencer Oliver * + * spen@spen-soft.co.uk * + * Copyright (C) 2008 by Frederik Kriewtz * + * frederik@kriewitz.eu * + * * + * This program is free software; you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation; either version 2 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * You should have received a copy of the GNU General Public License * + * along with this program; if not, write to the * + * Free Software Foundation, Inc., * + * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. * + ***************************************************************************/ + +#include "dcc_stdio.h" + +#define TARGET_REQ_TRACEMSG 0x00 +#define TARGET_REQ_DEBUGMSG_ASCII 0x01 +#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8)) +#define TARGET_REQ_DEBUGCHAR 0x02 + +/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel + * DCRDR[7:0] is used by target for status + * DCRDR[15:8] is used by target for write buffer + * DCRDR[23:16] is used for by host for status + * DCRDR[31:24] is used for by host for write buffer */ + +#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8)) + +#define BUSY 1 + +void dbg_write(unsigned long dcc_data) +{ + int len = 4; + + while (len--) + { + /* wait for data ready */ + while (NVIC_DBG_DATA_R & BUSY); + + /* write our data and set write flag - tell host there is data*/ + NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY); + dcc_data >>= 8; + } +} + +void dbg_trace_point(unsigned long number) +{ + dbg_write(TARGET_REQ_TRACEMSG | (number << 8)); +} + +void dbg_write_u32(const unsigned long *val, long len) +{ + dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16)); + + while (len > 0) + { + dbg_write(*val); + + val++; + len--; + } +} + +void dbg_write_u16(const unsigned short *val, long len) +{ + unsigned long dcc_data; + + dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16)); + + while (len > 0) + { + dcc_data = val[0] + | ((len > 1) ? val[1] << 16: 0x0000); + + dbg_write(dcc_data); + + val += 2; + len -= 2; + } +} + +void dbg_write_u8(const unsigned char *val, long len) +{ + unsigned long dcc_data; + + dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16)); + + while (len > 0) + { + dcc_data = val[0] + | ((len > 1) ? val[1] << 8 : 0x00) + | ((len > 2) ? val[2] << 16 : 0x00) + | ((len > 3) ? val[3] << 24 : 0x00); + + dbg_write(dcc_data); + + val += 4; + len -= 4; + } +} + +void dbg_write_str(const char *msg) +{ + long len; + unsigned long dcc_data; + + for (len = 0; msg[len] && (len < 65536); len++); + + dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16)); + + while (len > 0) + { + dcc_data = msg[0] + | ((len > 1) ? msg[1] << 8 : 0x00) + | ((len > 2) ? msg[2] << 16 : 0x00) + | ((len > 3) ? msg[3] << 24 : 0x00); + dbg_write(dcc_data); + + msg += 4; + len -= 4; + } +} + +void dbg_write_char(char msg) +{ + dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16)); +} + +void dbg_write_hex32(const unsigned long val) +{ + static const char hextab[] = { + '0', '1', '2', '3', '4', '5', '6', '7', + '8', '9', 'a', 'b', 'c', 'd', 'e', 'f' + }; + + for (int shift = 28; shift >= 0; shift -= 4) + dbg_write_char(hextab[(val >> shift) & 0xf]); +} diff --git a/flight/Revolution/System/inc/FreeRTOSConfig.h b/flight/Revolution/System/inc/FreeRTOSConfig.h new file mode 100644 index 000000000..72d6e288a --- /dev/null +++ b/flight/Revolution/System/inc/FreeRTOSConfig.h @@ -0,0 +1,103 @@ + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html. + *----------------------------------------------------------*/ + +/** + * @addtogroup PIOS PIOS + * @{ + * @addtogroup FreeRTOS FreeRTOS + * @{ + */ + +/* Notes: We use 5 task priorities */ + +#define configCPU_CLOCK_HZ (SYSCLK_FREQ) // really the NVIC clock ... +#define configTICK_RATE_HZ ((portTickType )1000) +#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5) +#define configMINIMAL_STACK_SIZE ((unsigned short)512) +#define configTOTAL_HEAP_SIZE ((size_t)(180 * 1024)) // this is minimum, not total +#define configMAX_TASK_NAME_LEN (16) + +#define configUSE_PREEMPTION 1 +#define configUSE_IDLE_HOOK 1 +#define configUSE_TICK_HOOK 0 +#define configUSE_TRACE_FACILITY 0 +#define configUSE_16_BIT_TICKS 0 +#define configIDLE_SHOULD_YIELD 0 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 0 +#define configUSE_ALTERNATIVE_API 0 +#define configCHECK_FOR_STACK_OVERFLOW 2 +#define configQUEUE_REGISTRY_SIZE 10 + +#define configUSE_TIMERS 1 +#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES - 1) /* run timers at max priority */ +#define configTIMER_QUEUE_LENGTH 10 +#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +//#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ + +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 1 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 1 +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 1 + +/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 +(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ +#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ + +/* This is the value being used as per the ST library which permits 16 +priority values, 0 to 15. This must correspond to the +configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest +NVIC value of 255. */ +#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 + +/* Enable run time stats collection */ +#define configGENERATE_RUN_TIME_STATS 1 +#define INCLUDE_uxTaskGetRunTime 1 + +/* + * Once we move to CMSIS2 we can at least use: + * + * CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; + * + * (still nothing for the DWT registers, surprisingly) + */ +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \ + do { \ + (*(unsigned long *)0xe000edfc) |= (1<<24); /* DEMCR |= DEMCR_TRCENA */ \ + (*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */ \ + } while(0) +#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004) /* DWT_CYCCNT */ + + +/** + * @} + */ + +#endif /* FREERTOS_CONFIG_H */ diff --git a/flight/Revolution/System/inc/alarms.h b/flight/Revolution/System/inc/alarms.h new file mode 100644 index 000000000..9fb047dca --- /dev/null +++ b/flight/Revolution/System/inc/alarms.h @@ -0,0 +1,50 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file alarms.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the alarm library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ALARMS_H +#define ALARMS_H + +#include "systemalarms.h" +#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED + +int32_t AlarmsInitialize(void); +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); +void AlarmsDefaultAll(); +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); +void AlarmsClearAll(); +int32_t AlarmsHasWarnings(); +int32_t AlarmsHasErrors(); +int32_t AlarmsHasCritical(); + +#endif // ALARMS_H + +/** + * @} + * @} + */ diff --git a/flight/Revolution/System/inc/dcc_stdio.h b/flight/Revolution/System/inc/dcc_stdio.h new file mode 100644 index 000000000..dbfd39342 --- /dev/null +++ b/flight/Revolution/System/inc/dcc_stdio.h @@ -0,0 +1,36 @@ +/*************************************************************************** + * Copyright (C) 2008 by Dominic Rath * + * Dominic.Rath@gmx.de * + * Copyright (C) 2008 by Spencer Oliver * + * spen@spen-soft.co.uk * + * * + * This program is free software; you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation; either version 2 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * You should have received a copy of the GNU General Public License * + * along with this program; if not, write to the * + * Free Software Foundation, Inc., * + * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. * + ***************************************************************************/ + +#ifndef DCC_STDIO_H +#define DCC_STDIO_H + +void dbg_trace_point(unsigned long number); + +void dbg_write_u32(const unsigned long *val, long len); +void dbg_write_u16(const unsigned short *val, long len); +void dbg_write_u8(const unsigned char *val, long len); + +void dbg_write_str(const char *msg); +void dbg_write_char(char msg); +void dbg_write_hex32(const unsigned long val); + +#endif /* DCC_STDIO_H */ diff --git a/flight/AHRS/inc/ahrs_timer.h b/flight/Revolution/System/inc/op_config.h similarity index 71% rename from flight/AHRS/inc/ahrs_timer.h rename to flight/Revolution/System/inc/op_config.h index aaddf5769..97910f392 100644 --- a/flight/AHRS/inc/ahrs_timer.h +++ b/flight/Revolution/System/inc/op_config.h @@ -1,45 +1,39 @@ -/** - ****************************************************************************** - * @addtogroup AHRS AHRS Control - * @brief The AHRS Modules perform - * - * @{ - * @addtogroup AHRS_TIMER - * @brief Sets up a simple timer that can be polled to estimate idle time - * @{ - * - * - * @file ahrs.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief INSGPS Test Program - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file op_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief OpenPilot configuration header. + * Compile time config for OpenPilot Application + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OP_CONFIG_H +#define OP_CONFIG_H + +#endif /* OP_CONFIG_H */ +/** + * @} + * @} */ - -#ifndef AHRS_TIMER -#define AHRS_TIMER - -#include - -#define TIMER_RATE (8e6 / 128) - -void timer_start(); -uint32_t timer_count(); -uint32_t timer_rate(); - -#endif diff --git a/flight/Revolution/System/inc/openpilot.h b/flight/Revolution/System/inc/openpilot.h new file mode 100644 index 000000000..59ae76fd4 --- /dev/null +++ b/flight/Revolution/System/inc/openpilot.h @@ -0,0 +1,53 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file openpilot.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main OpenPilot header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OPENPILOT_H +#define OPENPILOT_H + + +/* PIOS Includes */ +#include + +/* OpenPilot Libraries */ +#include "op_config.h" +#include "utlist.h" +#include "uavobjectmanager.h" +#include "eventdispatcher.h" +#include "alarms.h" +#include "taskmonitor.h" +#include "uavtalk.h" + +/* Global Functions */ +void OpenPilotInit(void); + +#endif /* OPENPILOT_H */ +/** + * @} + * @} + */ diff --git a/flight/Revolution/System/inc/pios_config.h b/flight/Revolution/System/inc/pios_config.h new file mode 100644 index 000000000..3043ea630 --- /dev/null +++ b/flight/Revolution/System/inc/pios_config.h @@ -0,0 +1,117 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * In particular, pios_config.h is where you define which PiOS libraries + * and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* Major features */ +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_BL_HELPER + +/* Enable/Disable PiOS Modules */ +//#define PIOS_INCLUDE_ADC +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_I2C +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_SERVO +#define PIOS_INCLUDE_SPI +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_USART +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +//#define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_RTC +#define PIOS_INCLUDE_WDG + +/* Select the sensors to include */ +#define PIOS_INCLUDE_BMA180 +#define PIOS_INCLUDE_HMC5883 +#define PIOS_INCLUDE_MPU6000 +#define PIOS_MPU6000_ACCEL +#define PIOS_INCLUDE_L3GD20 +#define PIOS_INCLUDE_MS5611 +//#define PIOS_INCLUDE_HCSR04 +#define PIOS_FLASH_ON_ACCEL /* true for second revo */ +#define FLASH_FREERTOS +/* Com systems to include */ +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_COM_TELEM +#define PIOS_INCLUDE_COM_AUX +#define PIOS_INCLUDE_COM_AUXSBUS +#define PIOS_INCLUDE_COM_FLEXI + +#define PIOS_INCLUDE_GPS +#define PIOS_OVERO_SPI +/* Supported receiver interfaces */ +#define PIOS_INCLUDE_RCVR +#define PIOS_INCLUDE_DSM +//#define PIOS_INCLUDE_SBUS +#define PIOS_INCLUDE_PPM +#define PIOS_INCLUDE_PWM +//#define PIOS_INCLUDE_GCSRCVR + +#define PIOS_INCLUDE_SETTINGS +#define PIOS_INCLUDE_FLASH +/* A really shitty setting saving implementation */ +#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS + +/* Other Interfaces */ +//#define PIOS_INCLUDE_I2C_ESC + +/* Flags that alter behaviors - mostly to lower resources for CC */ +#define PIOS_INCLUDE_INITCALL /* Include init call structures */ +#define PIOS_TELEM_PRIORITY_QUEUE /* Enable a priority queue in telemetry */ +#define PIOS_QUATERNION_STABILIZATION /* Stabilization options */ +//#define PIOS_GPS_SETS_HOMELOCATION /* GPS options */ + +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 4000 +#define HEAP_LIMIT_CRITICAL 1000 +#define IRQSTACK_LIMIT_WARNING 150 +#define IRQSTACK_LIMIT_CRITICAL 80 +#define CPULOAD_LIMIT_WARNING 80 +#define CPULOAD_LIMIT_CRITICAL 95 + +// This actually needs calibrating +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (8379692) + +#define REVOLUTION + +#endif /* PIOS_CONFIG_H */ +/** + * @} + * @} + */ diff --git a/flight/OpenPilot/System/inc/pios_usb_board_data.h b/flight/Revolution/System/inc/pios_usb_board_data.h similarity index 91% rename from flight/OpenPilot/System/inc/pios_usb_board_data.h rename to flight/Revolution/System/inc/pios_usb_board_data.h index 08fc3423b..dbd111134 100644 --- a/flight/OpenPilot/System/inc/pios_usb_board_data.h +++ b/flight/Revolution/System/inc/pios_usb_board_data.h @@ -37,9 +37,9 @@ #define PIOS_USB_BOARD_EP_NUM 4 -#include "pios_usb_defs.h" /* struct usb_* */ +#include "pios_usb_defs.h" /* USB_* macros */ -#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_OPENPILOT_MAIN -#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_OPENPILOT_MAIN, USB_OP_BOARD_MODE_FW) +#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_REVOLUTION +#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_REVOLUTION, USB_OP_BOARD_MODE_FW) #endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/Revolution/System/pios_board.c b/flight/Revolution/System/pios_board.c new file mode 100644 index 000000000..705463186 --- /dev/null +++ b/flight/Revolution/System/pios_board.c @@ -0,0 +1,833 @@ +/** + ****************************************************************************** + * @addtogroup Revolution Revolution configuration files + * @{ + * @brief Configures the revolution board + * @{ + * + * @file pios_board.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Defines board specific static initializers for hardware for the Revolution board. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include + +#include +#include +#include "hwsettings.h" +#include "manualcontrolsettings.h" + +#include "board_hw_defs.c" + +/** + * Sensor configurations + */ +#if defined(PIOS_INCLUDE_HMC5883) +#include "pios_hmc5883.h" +static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = { + .vector = PIOS_HMC5883_IRQHandler, + .line = EXTI_Line5, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI9_5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line5, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static const struct pios_hmc5883_cfg pios_hmc5883_cfg = { + .exti_cfg = &pios_exti_hmc5883_cfg, + .M_ODR = PIOS_HMC5883_ODR_75, + .Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL, + .Gain = PIOS_HMC5883_GAIN_1_9, + .Mode = PIOS_HMC5883_MODE_CONTINUOUS, + +}; +#endif /* PIOS_INCLUDE_HMC5883 */ + +/** + * Configuration for the MS5611 chip + */ +#if defined(PIOS_INCLUDE_MS5611) +#include "pios_ms5611.h" +static const struct pios_ms5611_cfg pios_ms5611_cfg = { + .oversampling = 1, +}; +#endif /* PIOS_INCLUDE_MS5611 */ + +/** + * Configuration for the BMA180 chip + */ +#if defined(PIOS_INCLUDE_BMA180) +#include "pios_bma180.h" +static const struct pios_exti_cfg pios_exti_bma180_cfg __exti_config = { + .vector = PIOS_BMA180_IRQHandler, + .line = EXTI_Line4, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line4, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; +static const struct pios_bma180_cfg pios_bma180_cfg = { + .exti_cfg = &pios_exti_bma180_cfg, + .bandwidth = BMA_BW_600HZ, + .range = BMA_RANGE_8G, +}; +#endif /* PIOS_INCLUDE_BMA180 */ + +/** + * Configuration for the MPU6000 chip + */ +#if defined(PIOS_INCLUDE_MPU6000) +#include "pios_mpu6000.h" +static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = { + .vector = PIOS_MPU6000_IRQHandler, + .line = EXTI_Line8, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI9_5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line8, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static const struct pios_mpu6000_cfg pios_mpu6000_cfg = { + .exti_cfg = &pios_exti_mpu6000_cfg, + .Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT, + // Clock at 8 khz, downsampled by 8 for 1khz + .Smpl_rate_div = 7, + .interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD, + .interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY, + .User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN, + .Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK, + .accel_range = PIOS_MPU6000_ACCEL_8G, + .gyro_range = PIOS_MPU6000_SCALE_500_DEG, + .filter = PIOS_MPU6000_LOWPASS_256_HZ +}; +#endif /* PIOS_INCLUDE_MPU6000 */ + +/** + * Configuration for L3GD20 chip + */ +#if defined(PIOS_INCLUDE_L3GD20) +#include "pios_l3gd20.h" +static const struct pios_exti_cfg pios_exti_l3gd20_cfg __exti_config = { + .vector = PIOS_L3GD20_IRQHandler, + .line = EXTI_Line8, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI9_5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line8, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static const struct pios_l3gd20_cfg pios_l3gd20_cfg = { + .exti_cfg = &pios_exti_l3gd20_cfg, + .range = PIOS_L3GD20_SCALE_500_DEG, +}; +#endif /* PIOS_INCLUDE_L3GD20 */ + + +static const struct flashfs_cfg flashfs_m25p_cfg = { + .table_magic = 0x85FB3D35, + .obj_magic = 0x3015A371, + .obj_table_start = 0x00000010, + .obj_table_end = 0x00010000, + .sector_size = 0x00010000, + .chip_size = 0x00200000, +}; + +static const struct pios_flash_jedec_cfg flash_m25p_cfg = { + .sector_erase = 0xD8, + .chip_erase = 0xC7 +}; + +/* One slot per selectable receiver group. + * eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS + * NOTE: No slot in this map for NONE. + */ +uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; + +#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 +#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 + +#define PIOS_COM_GPS_RX_BUF_LEN 32 + +#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 +#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 + +#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 +#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 + +#define PIOS_COM_AUX_RX_BUF_LEN 512 +#define PIOS_COM_AUX_TX_BUF_LEN 512 + +uint32_t pios_com_aux_id = 0; +uint32_t pios_com_gps_id = 0; +uint32_t pios_com_telem_usb_id = 0; +uint32_t pios_com_telem_rf_id = 0; +uint32_t pios_com_bridge_id = 0; + +/* + * Setup a com port based on the passed cfg, driver and buffer sizes. tx size of -1 make the port rx only + */ +static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len, + const struct pios_com_driver *com_driver, uint32_t *pios_com_id) +{ + uint32_t pios_usart_id; + if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) { + PIOS_Assert(0); + } + + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(rx_buf_len); + PIOS_Assert(rx_buffer); + if(tx_buf_len!= -1){ // this is the case for rx/tx ports + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(tx_buf_len); + PIOS_Assert(tx_buffer); + + if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, + rx_buffer, rx_buf_len, + tx_buffer, tx_buf_len)) { + PIOS_Assert(0); + } + } + else{ //rx only port + if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, + rx_buffer, rx_buf_len, + NULL, 0)) { + PIOS_Assert(0); + } + } +} + +static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, + const struct pios_com_driver *pios_usart_com_driver,enum pios_dsm_proto *proto, + ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) +{ + uint32_t pios_usart_dsm_id; + if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_dsm_id; + if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, + pios_usart_dsm_id, *proto, *bind)) { + PIOS_Assert(0); + } + + uint32_t pios_dsm_rcvr_id; + if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; +} + +/** + * PIOS_Board_Init() + * initializes all the core subsystems on this specific hardware + * called from System/openpilot.c + */ + +#include + +void PIOS_Board_Init(void) { + + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + /* Delay system */ + PIOS_DELAY_Init(); + + PIOS_LED_Init(&pios_led_cfg); + + /* Set up the SPI interface to the accelerometer*/ + if (PIOS_SPI_Init(&pios_spi_accel_id, &pios_spi_accel_cfg)) { + PIOS_DEBUG_Assert(0); + } + + /* Set up the SPI interface to the gyro */ + if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) { + PIOS_DEBUG_Assert(0); + } +#if !defined(PIOS_FLASH_ON_ACCEL) + /* Set up the SPI interface to the flash */ + if (PIOS_SPI_Init(&pios_spi_flash_id, &pios_spi_flash_cfg)) { + PIOS_DEBUG_Assert(0); + } + PIOS_Flash_Jedec_Init(pios_spi_flash_id, 0, &flash_m25p_cfg); +#else + PIOS_Flash_Jedec_Init(pios_spi_accel_id, 1, &flash_m25p_cfg); +#endif + PIOS_FLASHFS_Init(&flashfs_m25p_cfg); + +#if defined(PIOS_OVERO_SPI) + /* Set up the SPI interface to the gyro */ + if (PIOS_SPI_Init(&pios_spi_overo_id, &pios_spi_overo_cfg)) { + PIOS_DEBUG_Assert(0); + } +#endif + + /* Initialize UAVObject libraries */ + EventDispatcherInitialize(); + UAVObjInitialize(); + + HwSettingsInitialize(); + +#if defined(PIOS_INCLUDE_RTC) + PIOS_RTC_Init(&pios_rtc_main_cfg); +#endif + + /* Initialize the alarms library */ + AlarmsInitialize(); + + /* Initialize the task monitor library */ + TaskMonitorInitialize(); + + /* Set up pulse timers */ + PIOS_TIM_InitClock(&tim_1_cfg); + PIOS_TIM_InitClock(&tim_3_cfg); + PIOS_TIM_InitClock(&tim_4_cfg); + PIOS_TIM_InitClock(&tim_5_cfg); + PIOS_TIM_InitClock(&tim_9_cfg); + PIOS_TIM_InitClock(&tim_10_cfg); + PIOS_TIM_InitClock(&tim_11_cfg); + + /* IAP System Setup */ + PIOS_IAP_Init(); + uint16_t boot_count = PIOS_IAP_ReadBootCount(); + if (boot_count < 3) { + PIOS_IAP_WriteBootCount(++boot_count); + AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT); + } else { + /* Too many failed boot attempts, force hwsettings to defaults */ + HwSettingsSetDefaults(HwSettingsHandle(), 0); + AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); + } + + + //PIOS_IAP_Init(); + +#if defined(PIOS_INCLUDE_USB) + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + /* Flags to determine if various USB interfaces are advertised */ + bool usb_hid_present = false; + bool usb_cdc_present = false; + + uint8_t hwsettings_usb_devicetype; + HwSettingsUSB_DeviceTypeGet(&hwsettings_usb_devicetype); + + switch (hwsettings_usb_devicetype) { + case HWSETTINGS_USB_DEVICETYPE_HIDONLY: + if (PIOS_USB_DESC_HID_ONLY_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; + break; + case HWSETTINGS_USB_DEVICETYPE_HIDVCP: + if (PIOS_USB_DESC_HID_CDC_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; + usb_cdc_present = true; + break; + case HWSETTINGS_USB_DEVICETYPE_VCPONLY: + break; + default: + PIOS_Assert(0); + } + + uint32_t pios_usb_id; + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); + +#if defined(PIOS_INCLUDE_USB_CDC) + + uint8_t hwsettings_usb_vcpport; + /* Configure the USB VCP port */ + HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport); + + if (!usb_cdc_present) { + /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ + hwsettings_usb_vcpport = HWSETTINGS_USB_VCPPORT_DISABLED; + } + + switch (hwsettings_usb_vcpport) { + case HWSETTINGS_USB_VCPPORT_DISABLED: + break; + case HWSETTINGS_USB_VCPPORT_USBTELEMETRY: +#if defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usb_cdc_cfg, PIOS_COM_TELEM_USB_RX_BUF_LEN, PIOS_COM_TELEM_USB_TX_BUF_LEN, &pios_usb_cdc_com_driver, &pios_com_telem_usb_id); +#endif /* PIOS_INCLUDE_COM */ + break; + case HWSETTINGS_USB_VCPPORT_COMBRIDGE: +#if defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usb_cdc_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usb_cdc_com_driver, &pios_com_vcp_id); +#endif /* PIOS_INCLUDE_COM */ + break; + } +#endif /* PIOS_INCLUDE_USB_CDC */ + +#if defined(PIOS_INCLUDE_USB_HID) + /* Configure the usb HID port */ + uint8_t hwsettings_usb_hidport; + HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport); + + if (!usb_hid_present) { + /* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */ + hwsettings_usb_hidport = HWSETTINGS_USB_HIDPORT_DISABLED; + } + + switch (hwsettings_usb_hidport) { + case HWSETTINGS_USB_HIDPORT_DISABLED: + break; + case HWSETTINGS_USB_HIDPORT_USBTELEMETRY: +#if defined(PIOS_INCLUDE_COM) + { + uint32_t pios_usb_hid_id; + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, + rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_COM */ + break; + } + +#endif /* PIOS_INCLUDE_USB_HID */ + + if (usb_hid_present || usb_cdc_present) { + PIOS_USBHOOK_Activate(); + } +#endif /* PIOS_INCLUDE_USB */ + + /* Configure IO ports */ + uint8_t hwsettings_DSMxBind; + HwSettingsDSMxBindGet(&hwsettings_DSMxBind); + + /* Configure Telemetry port */ + uint8_t hwsettings_rv_telemetryport; + HwSettingsRV_TelemetryPortGet(&hwsettings_rv_telemetryport); + + switch (hwsettings_rv_telemetryport){ + case HWSETTINGS_RV_TELEMETRYPORT_DISABLED: + break; + case HWSETTINGS_RV_TELEMETRYPORT_TELEMETRY: + PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); + break; + case HWSETTINGS_RV_TELEMETRYPORT_COMAUX: + PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + break; + case HWSETTINGS_RV_TELEMETRYPORT_COMBRIDGE: + PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + + } /* hwsettings_rv_telemetryport */ + + /* Configure GPS port */ + uint8_t hwsettings_rv_gpsport; + HwSettingsRV_GPSPortGet(&hwsettings_rv_gpsport); + switch (hwsettings_rv_gpsport){ + case HWSETTINGS_RV_GPSPORT_DISABLED: + break; + + case HWSETTINGS_RV_GPSPORT_TELEMETRY: + PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); + break; + + case HWSETTINGS_RV_GPSPORT_GPS: + PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); + break; + + case HWSETTINGS_RV_GPSPORT_COMAUX: + PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + break; + + case HWSETTINGS_RV_GPSPORT_COMBRIDGE: + PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + }/* hwsettings_rv_gpsport */ + + /* Configure AUXPort */ + uint8_t hwsettings_rv_auxport; + HwSettingsRV_AuxPortGet(&hwsettings_rv_auxport); + + switch (hwsettings_rv_auxport) { + case HWSETTINGS_RV_AUXPORT_DISABLED: + break; + + case HWSETTINGS_RV_AUXPORT_TELEMETRY: + PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); + break; + + case HWSETTINGS_RV_AUXPORT_DSM2: + case HWSETTINGS_RV_AUXPORT_DSMX10BIT: + case HWSETTINGS_RV_AUXPORT_DSMX11BIT: + { + enum pios_dsm_proto proto; + switch (hwsettings_rv_auxport) { + case HWSETTINGS_RV_AUXPORT_DSM2: + proto = PIOS_DSM_PROTO_DSM2; + break; + case HWSETTINGS_RV_AUXPORT_DSMX10BIT: + proto = PIOS_DSM_PROTO_DSMX10BIT; + break; + case HWSETTINGS_RV_AUXPORT_DSMX11BIT: + proto = PIOS_DSM_PROTO_DSMX11BIT; + break; + default: + PIOS_Assert(0); + break; + } + //TODO: Define the various Channelgroup for Revo dsm inputs and handle here + PIOS_Board_configure_dsm(&pios_usart_dsm_aux_cfg, &pios_dsm_aux_cfg, + &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); + } + break; + case HWSETTINGS_RV_AUXPORT_COMAUX: + PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + break; + case HWSETTINGS_RV_AUXPORT_COMBRIDGE: + PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + } /* hwsettings_rv_auxport */ + /* Configure AUXSbusPort */ + //TODO: ensure that the serial invertion pin is setted correctly + uint8_t hwsettings_rv_auxsbusport; + HwSettingsRV_AuxSBusPortGet(&hwsettings_rv_auxsbusport); + + switch (hwsettings_rv_auxsbusport) { + case HWSETTINGS_RV_AUXSBUSPORT_DISABLED: + break; + case HWSETTINGS_RV_AUXSBUSPORT_SBUS: +#ifdef PIOS_INCLUDE_SBUS + { + uint32_t pios_usart_sbus_id; + if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_auxsbus_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_sbus_id; + if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { + PIOS_Assert(0); + } + + uint32_t pios_sbus_rcvr_id; + if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; + + } +#endif /* PIOS_INCLUDE_SBUS */ + break; + + case HWSETTINGS_RV_AUXSBUSPORT_DSM2: + case HWSETTINGS_RV_AUXSBUSPORT_DSMX10BIT: + case HWSETTINGS_RV_AUXSBUSPORT_DSMX11BIT: + { + enum pios_dsm_proto proto; + switch (hwsettings_rv_auxsbusport) { + case HWSETTINGS_RV_AUXSBUSPORT_DSM2: + proto = PIOS_DSM_PROTO_DSM2; + break; + case HWSETTINGS_RV_AUXSBUSPORT_DSMX10BIT: + proto = PIOS_DSM_PROTO_DSMX10BIT; + break; + case HWSETTINGS_RV_AUXSBUSPORT_DSMX11BIT: + proto = PIOS_DSM_PROTO_DSMX11BIT; + break; + default: + PIOS_Assert(0); + break; + } + //TODO: Define the various Channelgroup for Revo dsm inputs and handle here + PIOS_Board_configure_dsm(&pios_usart_dsm_auxsbus_cfg, &pios_dsm_auxsbus_cfg, + &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); + } + break; + case HWSETTINGS_RV_AUXSBUSPORT_COMAUX: + PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + break; + case HWSETTINGS_RV_AUXSBUSPORT_COMBRIDGE: + PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + } /* hwsettings_rv_auxport */ + + /* Configure FlexiPort */ + + uint8_t hwsettings_rv_flexiport; + HwSettingsRV_FlexiPortGet(&hwsettings_rv_flexiport); + + switch (hwsettings_rv_flexiport) { + case HWSETTINGS_RV_FLEXIPORT_DISABLED: + break; + case HWSETTINGS_RV_FLEXIPORT_I2C: +//TODO: Enable I2C +#if defined(PIOS_INCLUDE_I2C) +/* + { + if (PIOS_I2C_Init(&pios_i2c_flexi_adapter_id, &pios_i2c_flexi_adapter_cfg)) { + PIOS_Assert(0); + } + } +*/ +#endif /* PIOS_INCLUDE_I2C */ + break; + + case HWSETTINGS_RV_FLEXIPORT_DSM2: + case HWSETTINGS_RV_FLEXIPORT_DSMX10BIT: + case HWSETTINGS_RV_FLEXIPORT_DSMX11BIT: + { + enum pios_dsm_proto proto; + switch (hwsettings_rv_flexiport) { + case HWSETTINGS_RV_FLEXIPORT_DSM2: + proto = PIOS_DSM_PROTO_DSM2; + break; + case HWSETTINGS_RV_FLEXIPORT_DSMX10BIT: + proto = PIOS_DSM_PROTO_DSMX10BIT; + break; + case HWSETTINGS_RV_FLEXIPORT_DSMX11BIT: + proto = PIOS_DSM_PROTO_DSMX11BIT; + break; + default: + PIOS_Assert(0); + break; + } + //TODO: Define the various Channelgroup for Revo dsm inputs and handle here + PIOS_Board_configure_dsm(&pios_usart_dsm_flexi_cfg, &pios_dsm_flexi_cfg, + &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); + } + break; + case HWSETTINGS_RV_FLEXIPORT_COMAUX: + PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + break; + case HWSETTINGS_RV_FLEXIPORT_COMBRIDGE: + PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + } /* hwsettings_rv_flexiport */ + + + /* Configure the receiver port*/ + uint8_t hwsettings_rcvrport; + HwSettingsRV_RcvrPortGet(&hwsettings_rcvrport); + // + switch (hwsettings_rcvrport){ + case HWSETTINGS_RV_RCVRPORT_DISABLED: + break; + case HWSETTINGS_RV_RCVRPORT_PWM: +#if defined(PIOS_INCLUDE_PWM) + { + /* Set up the receiver port. Later this should be optional */ + uint32_t pios_pwm_id; + PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); + + uint32_t pios_pwm_rcvr_id; + if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PWM */ + break; + case HWSETTINGS_RV_RCVRPORT_PPM: + case HWSETTINGS_RV_RCVRPORT_PPMOUTPUTS: +#if defined(PIOS_INCLUDE_PPM) + { + uint32_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + + uint32_t pios_ppm_rcvr_id; + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PPM */ + case HWSETTINGS_RV_RCVRPORT_OUTPUTS: + + break; + } + +#if defined(PIOS_INCLUDE_GCSRCVR) + GCSReceiverInitialize(); + uint32_t pios_gcsrcvr_id; + PIOS_GCSRCVR_Init(&pios_gcsrcvr_id); + uint32_t pios_gcsrcvr_rcvr_id; + if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; +#endif /* PIOS_INCLUDE_GCSRCVR */ + +#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS + switch (hwsettings_rcvrport) { + case HWSETTINGS_RV_RCVRPORT_DISABLED: + case HWSETTINGS_RV_RCVRPORT_PWM: + case HWSETTINGS_RV_RCVRPORT_PPM: + /* Set up the servo outputs */ + PIOS_Servo_Init(&pios_servo_cfg); + break; + case HWSETTINGS_RV_RCVRPORT_PPMOUTPUTS: + case HWSETTINGS_RV_RCVRPORT_OUTPUTS: + //PIOS_Servo_Init(&pios_servo_rcvr_cfg); + //TODO: Prepare the configurations on board_hw_defs and handle here: + PIOS_Servo_Init(&pios_servo_cfg); + break; + } +#else + PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); +#endif + + if (PIOS_I2C_Init(&pios_i2c_mag_adapter_id, &pios_i2c_mag_adapter_cfg)) { + PIOS_DEBUG_Assert(0); + } + + if (PIOS_I2C_Init(&pios_i2c_pressure_adapter_id, &pios_i2c_pressure_adapter_cfg)) { + PIOS_DEBUG_Assert(0); + } + + PIOS_DELAY_WaitmS(50); + +#if defined(PIOS_INCLUDE_HMC5883) + PIOS_HMC5883_Init(&pios_hmc5883_cfg); +#endif + +#if defined(PIOS_INCLUDE_MS5611) + PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_pressure_adapter_id); +#endif + + switch(bdinfo->board_rev) { + case 0x01: +#if defined(PIOS_INCLUDE_L3GD20) + PIOS_L3GD20_Init(pios_spi_gyro_id, 0, &pios_l3gd20_cfg); + PIOS_Assert(PIOS_L3GD20_Test() == 0); +#endif +#if defined(PIOS_INCLUDE_BMA180) + PIOS_BMA180_Init(pios_spi_accel_id, 0, &pios_bma180_cfg); + PIOS_Assert(PIOS_BMA180_Test() == 0); +#endif + break; + case 0x02: +#if defined(PIOS_INCLUDE_MPU6000) + PIOS_MPU6000_Init(pios_spi_gyro_id,0, &pios_mpu6000_cfg); +#endif + break; + default: + PIOS_DEBUG_Assert(0); + } + +} + +/** + * @} + * @} + */ + diff --git a/flight/PipXtreme/pios_usb_board_data.c b/flight/Revolution/System/pios_usb_board_data.c similarity index 96% rename from flight/PipXtreme/pios_usb_board_data.c rename to flight/Revolution/System/pios_usb_board_data.c index 3e41e5ac9..823496c29 100644 --- a/flight/PipXtreme/pios_usb_board_data.c +++ b/flight/Revolution/System/pios_usb_board_data.c @@ -32,18 +32,19 @@ #include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ #include "pios_usbhook.h" /* PIOS_USBHOOK_* */ -static const uint8_t usb_product_id[20] = { +static const uint8_t usb_product_id[22] = { sizeof(usb_product_id), USB_DESC_TYPE_STRING, - 'P', 0, - 'i', 0, - 'p', 0, - 'X', 0, + 'R', 0, + 'e', 0, + 'v', 0, + 'o', 0, + 'l', 0, + 'u', 0, 't', 0, - 'r', 0, - 'e', 0, - 'm', 0, - 'e', 0, + 'i', 0, + 'o', 0, + 'n', 0, }; static uint8_t usb_serial_number[52] = { diff --git a/flight/Revolution/System/revolution.c b/flight/Revolution/System/revolution.c new file mode 100644 index 000000000..54f98ca03 --- /dev/null +++ b/flight/Revolution/System/revolution.c @@ -0,0 +1,143 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @brief These files are the core system files of OpenPilot. + * They are the ground layer just above PiOS. In practice, OpenPilot actually starts + * in the main() function of openpilot.c + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @brief This is where the OP firmware starts. Those files also define the compile-time + * options of the firmware. + * @{ + * @file openpilot.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Sets up and runs main OpenPilot tasks. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* OpenPilot Includes */ +#include "openpilot.h" +#include "uavobjectsinit.h" +#include "systemmod.h" + +/* Task Priorities */ +#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) + +/* Global Variables */ + +/* Local Variables */ +#define INCLUDE_TEST_TASKS 0 +#if INCLUDE_TEST_TASKS +static uint8_t sdcard_available; +#endif +FILEINFO File; +char Buffer[1024]; +uint32_t Cache; + +/* Function Prototypes */ +#if INCLUDE_TEST_TASKS +static void TaskTick(void *pvParameters); +static void TaskTesting(void *pvParameters); +static void TaskHIDTest(void *pvParameters); +static void TaskServos(void *pvParameters); +static void TaskSDCard(void *pvParameters); +#endif +int32_t CONSOLE_Parse(uint8_t port, char c); +void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value); + +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void Stack_Change(void); +static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change"))); + +/* Local Variables */ +#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority +#define INIT_TASK_STACK (1024 / 4) // XXX this seems excessive +static xTaskHandle initTaskHandle; + +/* Function Prototypes */ +static void initTask(void *parameters); + +/* Prototype of generated InitModules() function */ +extern void InitModules(void); + +/** +* OpenPilot Main function: +* +* Initialize PiOS
+* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
+* Start FreeRTOS Scheduler (vTaskStartScheduler)
+* If something goes wrong, blink LED1 and LED2 every 100ms +* +*/ +int main() +{ + int result; + + /* NOTE: Do NOT modify the following start-up sequence */ + /* Any new initialization functions should be added in OpenPilotInit() */ + vPortInitialiseBlocks(); + + /* Brings up System using CMSIS functions, enables the LEDs. */ + PIOS_SYS_Init(); + + /* For Revolution we use a FreeRTOS task to bring up the system so we can */ + /* always rely on FreeRTOS primitive */ + result = xTaskCreate(initTask, (const signed char *)"init", + INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY, + &initTaskHandle); + PIOS_Assert(result == pdPASS); + + /* Start the FreeRTOS scheduler */ + vTaskStartScheduler(); + + /* If all is well we will never reach here as the scheduler will now be running. */ + /* Do some PIOS_LED_HEARTBEAT to user that something bad just happened */ + PIOS_LED_Off(PIOS_LED_HEARTBEAT); \ + for(;;) { \ + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ + PIOS_DELAY_WaitmS(100); \ + }; + + return 0; +} +/** + * Initialisation task. + * + * Runs board and module initialisation, then terminates. + */ +void +initTask(void *parameters) +{ + /* board driver init */ + PIOS_Board_Init(); + + /* Initialize modules */ + MODULE_INITIALISE_ALL; + + /* terminate this task */ + vTaskDelete(NULL); +} + +/** + * @} + * @} + */ + diff --git a/flight/OpenPilot/UAVObjects.inc b/flight/Revolution/UAVObjects.inc similarity index 85% rename from flight/OpenPilot/UAVObjects.inc rename to flight/Revolution/UAVObjects.inc index 8d5c5409f..d91eb9c17 100644 --- a/flight/OpenPilot/UAVObjects.inc +++ b/flight/Revolution/UAVObjects.inc @@ -28,11 +28,13 @@ UAVOBJSRCFILENAMES += accessorydesired UAVOBJSRCFILENAMES += actuatorcommand UAVOBJSRCFILENAMES += actuatordesired UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += ahrscalibration -UAVOBJSRCFILENAMES += ahrssettings -UAVOBJSRCFILENAMES += ahrsstatus +UAVOBJSRCFILENAMES += altholdsmoothed +UAVOBJSRCFILENAMES += attitudesettings UAVOBJSRCFILENAMES += attitudeactual -UAVOBJSRCFILENAMES += attituderaw +UAVOBJSRCFILENAMES += gyros +UAVOBJSRCFILENAMES += gyrosbias +UAVOBJSRCFILENAMES += accels +UAVOBJSRCFILENAMES += magnetometer UAVOBJSRCFILENAMES += baroaltitude UAVOBJSRCFILENAMES += flightbatterysettings UAVOBJSRCFILENAMES += firmwareiapobj @@ -54,9 +56,11 @@ UAVOBJSRCFILENAMES += mixersettings UAVOBJSRCFILENAMES += mixerstatus UAVOBJSRCFILENAMES += nedaccel UAVOBJSRCFILENAMES += objectpersistence +UAVOBJSRCFILENAMES += overosyncstats UAVOBJSRCFILENAMES += positionactual UAVOBJSRCFILENAMES += positiondesired UAVOBJSRCFILENAMES += ratedesired +UAVOBJSRCFILENAMES += revocalibration UAVOBJSRCFILENAMES += sonaraltitude UAVOBJSRCFILENAMES += stabilizationdesired UAVOBJSRCFILENAMES += stabilizationsettings @@ -72,6 +76,8 @@ UAVOBJSRCFILENAMES += hwsettings UAVOBJSRCFILENAMES += receiveractivity UAVOBJSRCFILENAMES += cameradesired UAVOBJSRCFILENAMES += camerastabsettings +UAVOBJSRCFILENAMES += altitudeholdsettings +UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/AHRS/Makefile b/flight/SimPosix/Makefile similarity index 56% rename from flight/AHRS/Makefile rename to flight/SimPosix/Makefile index 17559cf58..9c3a8cdcf 100644 --- a/flight/AHRS/Makefile +++ b/flight/SimPosix/Makefile @@ -1,29 +1,32 @@ - ##### - # Project: OpenPilot AHRS - # - # - # Makefile for OpenPilot AHRS project - # - # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. - # - # - # This program is free software; you can redistribute it and/or modify - # it under the terms of the GNU General Public License as published by - # the Free Software Foundation; either version 3 of the License, or - # (at your option) any later version. - # - # This program is distributed in the hope that it will be useful, but - # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - # for more details. - # - # You should have received a copy of the GNU General Public License along - # with this program; if not, write to the Free Software Foundation, Inc., - # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - ##### +##### +# Project: OpenPilot INS +# +# +# Makefile for OpenPilot INS project +# +# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. +# +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, but +# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +# for more details. +# +# You should have received a copy of the GNU General Public License along +# with this program; if not, write to the Free Software Foundation, Inc., +# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) TOP := $(realpath $(WHEREAMI)/../../) + +override TCHAIN_PREFIX := +override THUMB := include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -38,7 +41,7 @@ OUTDIR := $(TOP)/build/$(TARGET) DEBUG ?= NO # Set to YES when using Code Sourcery toolchain -CODE_SOURCERY ?= YES +CODE_SOURCERY ?= NO ifeq ($(CODE_SOURCERY), YES) REMOVE_CMD = cs-rm @@ -48,89 +51,107 @@ endif FLASH_TOOL = OPENOCD +# List of modules to include +MODULES = ManualControl Stabilization GPS +MODULES += CameraStab +MODULES += Telemetry +#MODULES += OveroSync +PYMODULES = +#FlightPlan + # Paths -AHRS = ./ -AHRSINC = $(AHRS)/inc -PIOS = ../PiOS -PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = ../Libraries/inc -PIOSSTM32F10X = $(PIOS)/STM32F10x -PIOSCOMMON = $(PIOS)/Common -PIOSBOARDS = $(PIOS)/Boards -APPLIBDIR = $(PIOSSTM32F10X)/Libraries -STMLIBDIR = $(APPLIBDIR) -STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver -STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver -STMSPDSRCDIR = $(STMSPDDIR)/src -STMSPDINCDIR = $(STMSPDDIR)/inc -CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 -OPDIR = ../OpenPilot +OPSYSTEM = ./System +OPSYSTEMINC = $(OPSYSTEM)/inc +OPUAVTALK = ../UAVTalk +OPUAVTALKINC = $(OPUAVTALK)/inc OPUAVOBJ = ../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -OPSYSINC = $(OPDIR)/System/inc -BOOT = ../Bootloaders/AHRS -BOOTINC = $(BOOT)/inc +PIOS = ../PiOS.posix +PIOSINC = $(PIOS)/inc +OPMODULEDIR = ../Modules +FLIGHTLIB = ../Libraries +FLIGHTLIBINC = ../Libraries/inc +PIOSPOSIX = $(PIOS)/posix +PIOSCOMMON = $(PIOS)/posix +PIOSBOARDS = $(PIOS)/Boards +PIOSCOMMONLIB = $(PIOSCOMMON)/Libraries +#APPLIBDIR = $(PIOSSTM32F4XX)/Libraries +OPUAVOBJ = ../UAVObjects +OPUAVOBJINC = $(OPUAVOBJ)/inc +BOOT = +BOOTINC = +PYMITE = $(FLIGHTLIB)/PyMite +PYMITELIB = $(PYMITE)/lib +PYMITEPLAT = $(PYMITE)/platform/openpilot +PYMITETOOLS = $(PYMITE)/tools +PYMITEVM = $(PYMITE)/vm +PYMITEINC = $(PYMITEVM) +PYMITEINC += $(PYMITEPLAT) +PYMITEINC += $(OUTDIR) +FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib +FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans HWDEFSINC = ../board_hw_defs/$(BOARD_NAME) +UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight + +SRC = +# optional component libraries +include $(PIOSCOMMONLIB)/FreeRTOS/library.mk +#include $(PIOSCOMMONLIB)/dosfs/library.mk +#include $(PIOSCOMMONLIB)/msheap/library.mk -OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files -## AHRS: -SRC = ahrs.c -SRC += pios_board.c -SRC += ahrs_timer.c -SRC += $(FLIGHTLIB)/ahrs_spi_comm.c -SRC += $(FLIGHTLIB)/ahrs_comm_objects.c -SRC += $(BOOT)/ahrs_spi_program_slave.c -SRC += $(BOOT)/ahrs_slave_test.c -SRC += $(BOOT)/ahrs_spi_program.c -SRC += insgps13state.c +## PyMite files and modules +SRC += $(OUTDIR)/pmlib_img.c +SRC += $(OUTDIR)/pmlib_nat.c +SRC += $(OUTDIR)/pmlibusr_img.c +SRC += $(OUTDIR)/pmlibusr_nat.c +PYSRC += $(wildcard ${PYMITEVM}/*.c) +PYSRC += $(wildcard ${PYMITEPLAT}/*.c) +PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += $(PYSRC) + +## MODULES +SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += ${OUTDIR}/InitMods.c +## OPENPILOT CORE: +SRC += ${OPMODULEDIR}/System/systemmod.c +SRC += $(OPSYSTEM)/simposix.c +SRC += $(OPSYSTEM)/pios_board.c +SRC += $(OPSYSTEM)/alarms.c +SRC += $(OPUAVTALK)/uavtalk.c +SRC += $(OPUAVOBJ)/uavobjectmanager.c +SRC += $(OPUAVOBJ)/eventdispatcher.c +SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c + SRC += $(FLIGHTLIB)/CoordinateConversions.c SRC += $(FLIGHTLIB)/fifo_buffer.c +SRC += $(FLIGHTLIB)/WorldMagModel.c +SRC += $(FLIGHTLIB)/insgps13state.c +SRC += $(FLIGHTLIB)/taskmonitor.c -## PIOS Hardware (STM32F10x) -SRC += $(PIOSSTM32F10X)/pios_adc.c -SRC += $(PIOSSTM32F10X)/pios_sys.c -SRC += $(PIOSSTM32F10X)/pios_led.c -SRC += $(PIOSSTM32F10X)/pios_delay.c -SRC += $(PIOSSTM32F10X)/pios_usart.c -SRC += $(PIOSSTM32F10X)/pios_irq.c -SRC += $(PIOSSTM32F10X)/pios_i2c.c -SRC += $(PIOSSTM32F10X)/pios_gpio.c -SRC += $(PIOSSTM32F10X)/pios_spi.c -SRC += $(PIOSSTM32F10X)/pios_exti.c +## PIOS Hardware (STM32F4xx) +include $(PIOS)/posix/library.mk ## PIOS Hardware (Common) -SRC += $(PIOSCOMMON)/pios_com.c -SRC += $(PIOSCOMMON)/pios_hmc5843.c -SRC += $(PIOSCOMMON)/printf-stdarg.c -SRC += $(PIOSCOMMON)/pios_iap.c -SRC += $(PIOSCOMMON)/pios_bl_helper.c +#SRC += $(PIOSCOMMON)/pios_mpu6000.c +#SRC += $(PIOSCOMMON)/pios_bma180.c +#SRC += $(PIOSCOMMON)/pios_l3gd20.c +#SRC += $(PIOSCOMMON)/pios_hmc5883.c +#SRC += $(PIOSCOMMON)/pios_ms5611.c +#SRC += $(PIOSCOMMON)/pios_crc.c +#SRC += $(PIOSCOMMON)/pios_com.c +#SRC += $(PIOSCOMMON)/pios_rcvr.c +#SRC += $(PIOSCOMMON)/pios_flash_jedec.c +#SRC += $(PIOSCOMMON)/pios_flashfs_objlist.c +#SRC += $(PIOSCOMMON)/printf-stdarg.c +#SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c +#SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c -## CMSIS for STM32 -SRC += $(CMSISDIR)/core_cm3.c -SRC += $(CMSISDIR)/system_stm32f10x.c - -## Used parts of the STM-Library -SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c -SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c -SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c -SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c -SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c -SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c -SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c -SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c -SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c -SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c -SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c -SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c -SRC += $(STMSPDSRCDIR)/misc.c +include ./UAVObjects.inc +SRC += $(UAVOBJSRC) # List C source files here which must be compiled in ARM-Mode (no -mthumb). # use file-extension c for "c-only"-files @@ -153,7 +174,7 @@ CPPSRCARM = # Even though the DOS/Win* filesystem matches both .s and .S the same, # it will preserve the spelling of the filenames, and gcc itself does # care about how the name is spelled on its command-line. -ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S + # List Assembler source files here which must be assembled in ARM-Mode.. ASRCARM = @@ -162,17 +183,38 @@ ASRCARM = # Each directory must be seperated by a space. EXTRAINCDIRS += $(PIOS) EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(OPSYSTEMINC) +EXTRAINCDIRS += $(OPUAVTALK) +EXTRAINCDIRS += $(OPUAVTALKINC) +EXTRAINCDIRS += $(OPUAVOBJ) +EXTRAINCDIRS += $(OPUAVOBJINC) +EXTRAINCDIRS += $(UAVOBJSYNTHDIR) EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(PIOSSTM32F10X) +#EXTRAINCDIRS += $(PIOSSTM32F4XX) EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) -EXTRAINCDIRS += $(STMSPDINCDIR) +#EXTRAINCDIRS += $(STMSPDINCDIR) EXTRAINCDIRS += $(CMSISDIR) -EXTRAINCDIRS += $(AHRSINC) EXTRAINCDIRS += $(OPUAVSYNTHDIR) EXTRAINCDIRS += $(BOOTINC) +EXTRAINCDIRS += $(PYMITEINC) EXTRAINCDIRS += $(HWDEFSINC) +# Generate intermediate code +gencode: ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h + +$(PYSRC): gencode + +PYTHON = python + +# Generate code for PyMite +${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) + @echo $(MSG_PYMITEINIT) $(call toprel, $@) + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) + @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py +EXTRAINCDIRS += ${foreach MOD, ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc + # List any extra directories to look for library files here. # Also add directories where the linker should search for # includes from linker-script to the list @@ -188,7 +230,7 @@ EXTRA_LIBDIRS = EXTRA_LIBS = # Path to Linker-Scripts -LINKERSCRIPTPATH = $(PIOSSTM32F10X) +#LINKERSCRIPTPATH = $(PIOSSTM32F4XX) # Optimization level, can be [0, 1, 2, 3, s]. # 0 = turn off optimization. s = optimize for size. @@ -197,10 +239,25 @@ LINKERSCRIPTPATH = $(PIOSSTM32F10X) ifeq ($(DEBUG),YES) CFLAGS += -O0 CFLAGS += -DGENERAL_COV +CFLAGS += -finstrument-functions -ffixed-r10 else CFLAGS += -Os endif + + +# common architecture-specific flags from the device-specific library makefile +CFLAGS += $(ARCHFLAGS) + +CFLAGS += $(UAVOBJDEFINE) +CFLAGS += -DDIAGNOSTICS +CFLAGS += -DDIAG_TASKS + +# This is not the best place for these. Really should abstract out +# to the board file or something +#CFLAGS += -DSTM32F4XX +CFLAGS += -DMEM_SIZE=1024000000 + # Output format. (can be ihex or binary or both) # binary to create a load-image in raw-binary format i.e. for SAM-BA, # ihex to create a load-image in Intel hex format @@ -213,10 +270,10 @@ DEBUGF = dwarf-2 # Place project-specific -D (define) and/or # -U options for C here. -CDEFS = -DSTM32F10X_$(MODEL) +CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ) +CDEFS += -DSYSCLK_FREQ=$(SYSCLK_FREQ) CDEFS += -DUSE_STDPERIPH_DRIVER CDEFS += -DUSE_$(BOARD) -CDEFS += -DIN_AHRS # Place project-specific -D and/or -U options for # Assembler with preprocessor here. @@ -247,18 +304,18 @@ CFLAGS += -g$(DEBUGF) CFLAGS += -ffast-math -CFLAGS += -mcpu=$(MCU) +#CFLAGS += -mcpu=$(MCU) CFLAGS += $(CDEFS) CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. -CFLAGS += -mapcs-frame +#CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer ifeq ($(CODE_SOURCERY), YES) CFLAGS += -fpromote-loop-indices endif CFLAGS += -Wall -CFLAGS += -Werror +#CFLAGS += -Werror CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) # Compiler flags to generate dependency files: CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d @@ -270,7 +327,7 @@ CONLYFLAGS += $(CSTANDARD) # Assembler flags. # -Wa,...: tell GCC to pass this to the assembler. # -ahlns: create listing -ASFLAGS = -mcpu=$(MCU) -I. -x assembler-with-cpp +ASFLAGS = $(ARCHFLAGS) -I. -x assembler-with-cpp ASFLAGS += $(ADEFS) ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) @@ -281,19 +338,21 @@ MATH_LIB = -lm # -Wl,...: tell GCC to pass this to linker. # -Map: create map file # --cref: add cross reference to map file -LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections +#LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections +LDFLAGS = -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) LDFLAGS += -lc LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) LDFLAGS += $(MATH_LIB) -LDFLAGS += -lc -lgcc +LDFLAGS += -lc -lgcc -lpthread -lrt + +#Linker scripts +LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) -# Set linker-script name depending on selected submodel name -LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_memory.ld -LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_sections.ld # Define programs and commands. REMOVE = $(REMOVE_CMD) -f +PYHON = python # List of all source files. ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) @@ -325,6 +384,7 @@ endif endif endif + # Link: create ELF output file from object files. $(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ))) @@ -357,7 +417,7 @@ $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin $(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino opfw elf: $(OUTDIR)/$(TARGET).elf @@ -420,5 +480,32 @@ else -include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) endif +#create compile-time module auto-initialisation +MODNAMES = ${notdir $(subst /revolution,,$(MODULES))} + +# Test if quotes are needed for the echo-command +result = ${shell echo "test"} +ifeq (${result}, test) + quote = ' +else + quote = +endif + +# Generate intermediate code +gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h + +# Generate code for module initialization +${OUTDIR}/InitMods.c: Makefile + @echo ${MSG_MODINIT} + @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Start(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + # Listing of phony targets. .PHONY : all build clean clean_list install diff --git a/flight/SimPosix/System/alarms.c b/flight/SimPosix/System/alarms.c new file mode 100644 index 000000000..6ccd5fb62 --- /dev/null +++ b/flight/SimPosix/System/alarms.c @@ -0,0 +1,210 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @brief OpenPilot System libraries are available to all OP modules. + * @{ + * @file alarms.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Library for setting and clearing system alarms + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "alarms.h" + +// Private constants + +// Private types + +// Private variables +static xSemaphoreHandle lock; + +// Private functions +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); + +/** + * Initialize the alarms library + */ +int32_t AlarmsInitialize(void) +{ + SystemAlarmsInitialize(); + lock = xSemaphoreCreateRecursiveMutex(); + return 0; +} + +/** + * Set an alarm + * @param alarm The system alarm to be modified + * @param severity The alarm severity + * @return 0 if success, -1 if an error + */ +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return -1; + } + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarm and update its severity only if it was changed + SystemAlarmsGet(&alarms); + if ( alarms.Alarm[alarm] != severity ) + { + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); + } + + // Release lock + xSemaphoreGiveRecursive(lock); + return 0; + +} + +/** + * Get an alarm + * @param alarm The system alarm to be read + * @return Alarm severity + */ +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return 0; + } + + // Read alarm + SystemAlarmsGet(&alarms); + return alarms.Alarm[alarm]; +} + +/** + * Set an alarm to it's default value + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); +} + +/** + * Default all alarms + */ +void AlarmsDefaultAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsDefault(n); + } +} + +/** + * Clear an alarm + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); +} + +/** + * Clear all alarms + */ +void AlarmsClearAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsClear(n); + } +} + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasWarnings() +{ + return hasSeverity(SYSTEMALARMS_ALARM_WARNING); +} + +/** + * Check if there are any alarms with error or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasErrors() +{ + return hasSeverity(SYSTEMALARMS_ALARM_ERROR); +}; + +/** + * Check if there are any alarms with critical or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasCritical() +{ + return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); +}; + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + uint32_t n; + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarms + SystemAlarmsGet(&alarms); + + // Go through alarms and check if any are of the given severity or higher + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + if ( alarms.Alarm[n] >= severity) + { + xSemaphoreGiveRecursive(lock); + return 1; + } + } + + // If this point is reached then no alarms found + xSemaphoreGiveRecursive(lock); + return 0; +} +/** + * @} + * @} + */ + diff --git a/flight/SimPosix/System/inc/FreeRTOSConfig.h b/flight/SimPosix/System/inc/FreeRTOSConfig.h new file mode 100644 index 000000000..72d6e288a --- /dev/null +++ b/flight/SimPosix/System/inc/FreeRTOSConfig.h @@ -0,0 +1,103 @@ + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html. + *----------------------------------------------------------*/ + +/** + * @addtogroup PIOS PIOS + * @{ + * @addtogroup FreeRTOS FreeRTOS + * @{ + */ + +/* Notes: We use 5 task priorities */ + +#define configCPU_CLOCK_HZ (SYSCLK_FREQ) // really the NVIC clock ... +#define configTICK_RATE_HZ ((portTickType )1000) +#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5) +#define configMINIMAL_STACK_SIZE ((unsigned short)512) +#define configTOTAL_HEAP_SIZE ((size_t)(180 * 1024)) // this is minimum, not total +#define configMAX_TASK_NAME_LEN (16) + +#define configUSE_PREEMPTION 1 +#define configUSE_IDLE_HOOK 1 +#define configUSE_TICK_HOOK 0 +#define configUSE_TRACE_FACILITY 0 +#define configUSE_16_BIT_TICKS 0 +#define configIDLE_SHOULD_YIELD 0 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 0 +#define configUSE_ALTERNATIVE_API 0 +#define configCHECK_FOR_STACK_OVERFLOW 2 +#define configQUEUE_REGISTRY_SIZE 10 + +#define configUSE_TIMERS 1 +#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES - 1) /* run timers at max priority */ +#define configTIMER_QUEUE_LENGTH 10 +#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +//#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ + +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 1 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 1 +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 1 + +/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 +(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ +#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ + +/* This is the value being used as per the ST library which permits 16 +priority values, 0 to 15. This must correspond to the +configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest +NVIC value of 255. */ +#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 + +/* Enable run time stats collection */ +#define configGENERATE_RUN_TIME_STATS 1 +#define INCLUDE_uxTaskGetRunTime 1 + +/* + * Once we move to CMSIS2 we can at least use: + * + * CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; + * + * (still nothing for the DWT registers, surprisingly) + */ +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \ + do { \ + (*(unsigned long *)0xe000edfc) |= (1<<24); /* DEMCR |= DEMCR_TRCENA */ \ + (*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */ \ + } while(0) +#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004) /* DWT_CYCCNT */ + + +/** + * @} + */ + +#endif /* FREERTOS_CONFIG_H */ diff --git a/flight/Bootloaders/AHRS/inc/ahrs_bl.h b/flight/SimPosix/System/inc/alarms.h similarity index 57% rename from flight/Bootloaders/AHRS/inc/ahrs_bl.h rename to flight/SimPosix/System/inc/alarms.h index 2d96385ab..0f0faeb8f 100644 --- a/flight/Bootloaders/AHRS/inc/ahrs_bl.h +++ b/flight/SimPosix/System/inc/alarms.h @@ -1,52 +1,50 @@ -/** - ****************************************************************************** - * - * @file ahrs_bl.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main AHRS_BL header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef AHRS_BL_H -#define AHRS_BL_H - -/* PIOS Includes */ -#include - -/** Start programming - returns: true if FLASH erased and ready to program - */ -bool -StartProgramming(void); - -/** Write a block to FLASH - buffer contains the data to be written - returns: true if FLASH programmed correctly - */ -bool -WriteData(uint32_t offset, uint8_t *buffer, uint32_t size); - -/** Read a block from FLASH - returns: true if FLASH read correctly. - Buffer is set to the read data - */ -bool -ReadData(uint32_t offset, uint8_t *buffer, uint32_t size); - -#endif /* AHRS_BL_H */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file alarms.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the alarm library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ALARMS_H +#define ALARMS_H + +#include "systemalarms.h" +#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED + +int32_t AlarmsInitialize(void); +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); +void AlarmsDefaultAll(); +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); +void AlarmsClearAll(); +int32_t AlarmsHasWarnings(); +int32_t AlarmsHasErrors(); +int32_t AlarmsHasCritical(); + +#endif // ALARMS_H + +/** + * @} + * @} + */ diff --git a/flight/SimPosix/System/inc/dcc_stdio.h b/flight/SimPosix/System/inc/dcc_stdio.h new file mode 100644 index 000000000..dbfd39342 --- /dev/null +++ b/flight/SimPosix/System/inc/dcc_stdio.h @@ -0,0 +1,36 @@ +/*************************************************************************** + * Copyright (C) 2008 by Dominic Rath * + * Dominic.Rath@gmx.de * + * Copyright (C) 2008 by Spencer Oliver * + * spen@spen-soft.co.uk * + * * + * This program is free software; you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation; either version 2 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * You should have received a copy of the GNU General Public License * + * along with this program; if not, write to the * + * Free Software Foundation, Inc., * + * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. * + ***************************************************************************/ + +#ifndef DCC_STDIO_H +#define DCC_STDIO_H + +void dbg_trace_point(unsigned long number); + +void dbg_write_u32(const unsigned long *val, long len); +void dbg_write_u16(const unsigned short *val, long len); +void dbg_write_u8(const unsigned char *val, long len); + +void dbg_write_str(const char *msg); +void dbg_write_char(char msg); +void dbg_write_hex32(const unsigned long val); + +#endif /* DCC_STDIO_H */ diff --git a/flight/SimPosix/System/inc/op_config.h b/flight/SimPosix/System/inc/op_config.h new file mode 100644 index 000000000..0fe9e2bdc --- /dev/null +++ b/flight/SimPosix/System/inc/op_config.h @@ -0,0 +1,39 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file op_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief OpenPilot configuration header. + * Compile time config for OpenPilot Application + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OP_CONFIG_H +#define OP_CONFIG_H + +#endif /* OP_CONFIG_H */ +/** + * @} + * @} + */ diff --git a/flight/SimPosix/System/inc/openpilot.h b/flight/SimPosix/System/inc/openpilot.h new file mode 100644 index 000000000..0bbdf971b --- /dev/null +++ b/flight/SimPosix/System/inc/openpilot.h @@ -0,0 +1,53 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file openpilot.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main OpenPilot header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OPENPILOT_H +#define OPENPILOT_H + + +/* PIOS Includes */ +#include + +/* OpenPilot Libraries */ +#include "op_config.h" +#include "utlist.h" +#include "uavobjectmanager.h" +#include "eventdispatcher.h" +#include "alarms.h" +#include "taskmonitor.h" +#include "uavtalk.h" + +/* Global Functions */ +void OpenPilotInit(void); + +#endif /* OPENPILOT_H */ +/** + * @} + * @} + */ diff --git a/flight/SimPosix/System/inc/pios_config.h b/flight/SimPosix/System/inc/pios_config.h new file mode 100644 index 000000000..d4add3666 --- /dev/null +++ b/flight/SimPosix/System/inc/pios_config.h @@ -0,0 +1,120 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * In particular, pios_config.h is where you define which PiOS libraries + * and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* Major features */ +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_BL_HELPER + +/* Enable/Disable PiOS Modules */ +//#define PIOS_INCLUDE_ADC +#define PIOS_INCLUDE_DELAY +//#define PIOS_INCLUDE_I2C +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_SDCARD +//#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_SERVO +#define PIOS_INCLUDE_SPI +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_USART +//#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +//#define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_RTC +#define PIOS_INCLUDE_WDG +#define PIOS_INCLUDE_UDP + +/* Select the sensors to include */ +//#define PIOS_INCLUDE_BMA180 +//#define PIOS_INCLUDE_HMC5883 +//#define PIOS_INCLUDE_MPU6000 +//#define PIOS_MPU6000_ACCEL +//#define PIOS_INCLUDE_L3GD20 +//#define PIOS_INCLUDE_MS5611 +//#define PIOS_INCLUDE_HCSR04 +#define PIOS_FLASH_ON_ACCEL /* true for second revo */ +#define FLASH_FREERTOS +/* Com systems to include */ +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_COM_TELEM +#define PIOS_INCLUDE_COM_AUX +#define PIOS_INCLUDE_COM_AUXSBUS +#define PIOS_INCLUDE_COM_FLEXI + +#define PIOS_INCLUDE_GPS +#define PIOS_OVERO_SPI +/* Supported receiver interfaces */ +#define PIOS_INCLUDE_RCVR +#define PIOS_INCLUDE_DSM +//#define PIOS_INCLUDE_SBUS +#define PIOS_INCLUDE_PPM +#define PIOS_INCLUDE_PWM +//#define PIOS_INCLUDE_GCSRCVR + +#define PIOS_INCLUDE_SETTINGS +#define PIOS_INCLUDE_FLASH +/* A really shitty setting saving implementation */ +//#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS + +/* Other Interfaces */ +//#define PIOS_INCLUDE_I2C_ESC + +/* Flags that alter behaviors - mostly to lower resources for CC */ +#define PIOS_INCLUDE_INITCALL /* Include init call structures */ +#define PIOS_TELEM_PRIORITY_QUEUE /* Enable a priority queue in telemetry */ +#define PIOS_QUATERNION_STABILIZATION /* Stabilization options */ +//#define PIOS_GPS_SETS_HOMELOCATION /* GPS options */ + +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 4000 +#define HEAP_LIMIT_CRITICAL 1000 +#define IRQSTACK_LIMIT_WARNING 150 +#define IRQSTACK_LIMIT_CRITICAL 80 +#define CPULOAD_LIMIT_WARNING 80 +#define CPULOAD_LIMIT_CRITICAL 95 + +// This actually needs calibrating +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (8379692) + +#define REVOLUTION +#define SIMPOSIX + +#endif /* PIOS_CONFIG_H */ +/** + * @} + * @} + */ diff --git a/flight/SimPosix/System/pios_board.c b/flight/SimPosix/System/pios_board.c new file mode 100644 index 000000000..45b078120 --- /dev/null +++ b/flight/SimPosix/System/pios_board.c @@ -0,0 +1,187 @@ +/** + ****************************************************************************** + * @addtogroup Revolution Revolution configuration files + * @{ + * @brief Configures the revolution board + * @{ + * + * @file pios_board.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Defines board specific static initializers for hardware for the Revolution board. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include + +#include +#include +#include "hwsettings.h" +#include "manualcontrolsettings.h" + +#include "board_hw_defs.c" + +/** + * Sensor configurations + */ + +/* One slot per selectable receiver group. + * eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS + * NOTE: No slot in this map for NONE. + */ +uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; + +#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 +#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 + +#define PIOS_COM_GPS_RX_BUF_LEN 32 + +#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 +#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 + +#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 +#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 + +#define PIOS_COM_AUX_RX_BUF_LEN 512 +#define PIOS_COM_AUX_TX_BUF_LEN 512 + +uint32_t pios_com_aux_id = 0; +uint32_t pios_com_gps_id = 0; +uint32_t pios_com_telem_usb_id = 0; +uint32_t pios_com_telem_rf_id = 0; +uint32_t pios_com_bridge_id = 0; + +/* + * Setup a com port based on the passed cfg, driver and buffer sizes. tx size of -1 make the port rx only + */ +static void PIOS_Board_configure_com(const struct pios_udp_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len, + const struct pios_com_driver *com_driver, uint32_t *pios_com_id) +{ + uint32_t pios_usart_id; + if (PIOS_UDP_Init(&pios_usart_id, usart_port_cfg)) { + PIOS_Assert(0); + } + + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(rx_buf_len); + PIOS_Assert(rx_buffer); + if(tx_buf_len!= -1){ // this is the case for rx/tx ports + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(tx_buf_len); + PIOS_Assert(tx_buffer); + + if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, + rx_buffer, rx_buf_len, + tx_buffer, tx_buf_len)) { + PIOS_Assert(0); + } + } + else{ //rx only port + if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, + rx_buffer, rx_buf_len, + NULL, 0)) { + PIOS_Assert(0); + } + } +} + +/** + * PIOS_Board_Init() + * initializes all the core subsystems on this specific hardware + * called from System/openpilot.c + */ +void PIOS_Board_Init(void) { + + /* Delay system */ + PIOS_DELAY_Init(); + + /* Initialize UAVObject libraries */ + EventDispatcherInitialize(); + UAVObjInitialize(); + + HwSettingsInitialize(); + + UAVObjectsInitializeAll(); + + /* Initialize the alarms library */ + AlarmsInitialize(); + + /* Initialize the task monitor library */ + TaskMonitorInitialize(); + + /* Configure IO ports */ + + /* Configure Telemetry port */ + uint8_t hwsettings_rv_telemetryport; + HwSettingsRV_TelemetryPortGet(&hwsettings_rv_telemetryport); + + switch (hwsettings_rv_telemetryport){ + case HWSETTINGS_RV_TELEMETRYPORT_DISABLED: + break; + case HWSETTINGS_RV_TELEMETRYPORT_TELEMETRY: + PIOS_Board_configure_com(&pios_udp_telem_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_udp_com_driver, &pios_com_telem_rf_id); + break; + case HWSETTINGS_RV_TELEMETRYPORT_COMAUX: + PIOS_Board_configure_com(&pios_udp_telem_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_udp_com_driver, &pios_com_aux_id); + break; + + } /* hwsettings_rv_telemetryport */ + + /* Configure GPS port */ + uint8_t hwsettings_rv_gpsport; + HwSettingsRV_GPSPortGet(&hwsettings_rv_gpsport); + switch (hwsettings_rv_gpsport){ + case HWSETTINGS_RV_GPSPORT_DISABLED: + break; + + case HWSETTINGS_RV_GPSPORT_TELEMETRY: + PIOS_Board_configure_com(&pios_udp_gps_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_udp_com_driver, &pios_com_telem_rf_id); + break; + + case HWSETTINGS_RV_GPSPORT_GPS: + PIOS_Board_configure_com(&pios_udp_gps_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_udp_com_driver, &pios_com_gps_id); + break; + + case HWSETTINGS_RV_GPSPORT_COMAUX: + PIOS_Board_configure_com(&pios_udp_gps_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_udp_com_driver, &pios_com_aux_id); + break; + + }/* hwsettings_rv_gpsport */ + + /* Configure AUXPort */ + uint8_t hwsettings_rv_auxport; + HwSettingsRV_AuxPortGet(&hwsettings_rv_auxport); + + switch (hwsettings_rv_auxport) { + case HWSETTINGS_RV_AUXPORT_DISABLED: + break; + + case HWSETTINGS_RV_AUXPORT_TELEMETRY: + PIOS_Board_configure_com(&pios_udp_aux_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_udp_com_driver, &pios_com_telem_rf_id); + break; + + case HWSETTINGS_RV_AUXPORT_COMAUX: + PIOS_Board_configure_com(&pios_udp_aux_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_udp_com_driver, &pios_com_aux_id); + break; + break; + } /* hwsettings_rv_auxport */ +} + +/** + * @} + * @} + */ + diff --git a/flight/SimPosix/System/simposix.c b/flight/SimPosix/System/simposix.c new file mode 100644 index 000000000..1863b81c7 --- /dev/null +++ b/flight/SimPosix/System/simposix.c @@ -0,0 +1,142 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @brief These files are the core system files of OpenPilot. + * They are the ground layer just above PiOS. In practice, OpenPilot actually starts + * in the main() function of openpilot.c + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @brief This is where the OP firmware starts. Those files also define the compile-time + * options of the firmware. + * @{ + * @file openpilot.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Sets up and runs main OpenPilot tasks. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* OpenPilot Includes */ +#include "openpilot.h" +#include "uavobjectsinit.h" +#include "systemmod.h" + +/* Task Priorities */ +#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) + +/* Global Variables */ + +/* Local Variables */ +#define INCLUDE_TEST_TASKS 0 +#if INCLUDE_TEST_TASKS +static uint8_t sdcard_available; +#endif +FILEINFO File; +char Buffer[1024]; +uint32_t Cache; + +/* Function Prototypes */ +#if INCLUDE_TEST_TASKS +static void TaskTick(void *pvParameters); +static void TaskTesting(void *pvParameters); +static void TaskHIDTest(void *pvParameters); +static void TaskServos(void *pvParameters); +static void TaskSDCard(void *pvParameters); +#endif +int32_t CONSOLE_Parse(uint8_t port, char c); +void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value); + +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void Stack_Change(void); +static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change"))); + +/* Local Variables */ +#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority +#define INIT_TASK_STACK (1024 / 4) // XXX this seems excessive +static xTaskHandle initTaskHandle; + +/* Function Prototypes */ +static void initTask(void *parameters); + +/* Prototype of generated InitModules() function */ +extern void InitModules(void); + +/** +* OpenPilot Main function: +* +* Initialize PiOS
+* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
+* Start FreeRTOS Scheduler (vTaskStartScheduler)
+* If something goes wrong, blink LED1 and LED2 every 100ms +* +*/ +int main() +{ + int result; + + /* NOTE: Do NOT modify the following start-up sequence */ + /* Any new initialization functions should be added in OpenPilotInit() */ + + /* Brings up System using CMSIS functions, enables the LEDs. */ + PIOS_SYS_Init(); + + /* For Revolution we use a FreeRTOS task to bring up the system so we can */ + /* always rely on FreeRTOS primitive */ + result = xTaskCreate(initTask, (const signed char *)"init", + INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY, + &initTaskHandle); + PIOS_Assert(result == pdPASS); + + /* Start the FreeRTOS scheduler */ + vTaskStartScheduler(); + + /* If all is well we will never reach here as the scheduler will now be running. */ + /* Do some PIOS_LED_HEARTBEAT to user that something bad just happened */ + PIOS_LED_Off(PIOS_LED_HEARTBEAT); \ + for(;;) { \ + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ + PIOS_DELAY_WaitmS(100); \ + }; + + return 0; +} +/** + * Initialisation task. + * + * Runs board and module initialisation, then terminates. + */ +void +initTask(void *parameters) +{ + /* board driver init */ + PIOS_Board_Init(); + + /* Initialize modules */ + MODULE_INITIALISE_ALL; + + /* terminate this task */ + vTaskDelete(NULL); +} + +/** + * @} + * @} + */ + diff --git a/flight/SimPosix/UAVObjects.inc b/flight/SimPosix/UAVObjects.inc new file mode 100644 index 000000000..d91eb9c17 --- /dev/null +++ b/flight/SimPosix/UAVObjects.inc @@ -0,0 +1,83 @@ +##### +# Project: OpenPilot +# +# Makefile for OpenPilot UAVObject code +# +# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011. +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, but +# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +# for more details. +# +# You should have received a copy of the GNU General Public License along +# with this program; if not, write to the Free Software Foundation, Inc., +# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +##### + +# These are the UAVObjects supposed to be build as part of the OpenPilot target +# (all architectures) + +UAVOBJSRCFILENAMES = +UAVOBJSRCFILENAMES += accessorydesired +UAVOBJSRCFILENAMES += actuatorcommand +UAVOBJSRCFILENAMES += actuatordesired +UAVOBJSRCFILENAMES += actuatorsettings +UAVOBJSRCFILENAMES += altholdsmoothed +UAVOBJSRCFILENAMES += attitudesettings +UAVOBJSRCFILENAMES += attitudeactual +UAVOBJSRCFILENAMES += gyros +UAVOBJSRCFILENAMES += gyrosbias +UAVOBJSRCFILENAMES += accels +UAVOBJSRCFILENAMES += magnetometer +UAVOBJSRCFILENAMES += baroaltitude +UAVOBJSRCFILENAMES += flightbatterysettings +UAVOBJSRCFILENAMES += firmwareiapobj +UAVOBJSRCFILENAMES += flightbatterystate +UAVOBJSRCFILENAMES += flightplancontrol +UAVOBJSRCFILENAMES += flightplansettings +UAVOBJSRCFILENAMES += flightplanstatus +UAVOBJSRCFILENAMES += flighttelemetrystats +UAVOBJSRCFILENAMES += gcstelemetrystats +UAVOBJSRCFILENAMES += gpsposition +UAVOBJSRCFILENAMES += gpssatellites +UAVOBJSRCFILENAMES += gpstime +UAVOBJSRCFILENAMES += guidancesettings +UAVOBJSRCFILENAMES += homelocation +UAVOBJSRCFILENAMES += i2cstats +UAVOBJSRCFILENAMES += manualcontrolcommand +UAVOBJSRCFILENAMES += manualcontrolsettings +UAVOBJSRCFILENAMES += mixersettings +UAVOBJSRCFILENAMES += mixerstatus +UAVOBJSRCFILENAMES += nedaccel +UAVOBJSRCFILENAMES += objectpersistence +UAVOBJSRCFILENAMES += overosyncstats +UAVOBJSRCFILENAMES += positionactual +UAVOBJSRCFILENAMES += positiondesired +UAVOBJSRCFILENAMES += ratedesired +UAVOBJSRCFILENAMES += revocalibration +UAVOBJSRCFILENAMES += sonaraltitude +UAVOBJSRCFILENAMES += stabilizationdesired +UAVOBJSRCFILENAMES += stabilizationsettings +UAVOBJSRCFILENAMES += systemalarms +UAVOBJSRCFILENAMES += systemsettings +UAVOBJSRCFILENAMES += systemstats +UAVOBJSRCFILENAMES += taskinfo +UAVOBJSRCFILENAMES += velocityactual +UAVOBJSRCFILENAMES += velocitydesired +UAVOBJSRCFILENAMES += watchdogstatus +UAVOBJSRCFILENAMES += flightstatus +UAVOBJSRCFILENAMES += hwsettings +UAVOBJSRCFILENAMES += receiveractivity +UAVOBJSRCFILENAMES += cameradesired +UAVOBJSRCFILENAMES += camerastabsettings +UAVOBJSRCFILENAMES += altitudeholdsettings +UAVOBJSRCFILENAMES += altitudeholddesired + +UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) +UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/UAVObjects/eventdispatcher.c b/flight/UAVObjects/eventdispatcher.c index 53a6e039d..a5a728b62 100644 --- a/flight/UAVObjects/eventdispatcher.c +++ b/flight/UAVObjects/eventdispatcher.c @@ -59,7 +59,7 @@ typedef struct { */ struct PeriodicObjectListStruct { EventCallbackInfo evInfo; /** Event callback information */ - int32_t updatePeriodMs; /** Update period in ms or 0 if no periodic updates are needed */ + uint16_t updatePeriodMs; /** Update period in ms or 0 if no periodic updates are needed */ int32_t timeToNextUpdateMs; /** Time delay to the next update */ struct PeriodicObjectListStruct* next; /** Needed by linked list library (utlist.h) */ }; @@ -75,9 +75,9 @@ static EventStats stats; // Private functions static int32_t processPeriodicUpdates(); static void eventTask(); -static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQueueHandle queue, int32_t periodMs); -static int32_t eventPeriodicUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, xQueueHandle queue, int32_t periodMs); -static uint32_t randomizePeriod(uint32_t periodMs); +static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQueueHandle queue, uint16_t periodMs); +static int32_t eventPeriodicUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, xQueueHandle queue, uint16_t periodMs); +static uint16_t randomizePeriod(uint16_t periodMs); /** @@ -151,7 +151,7 @@ int32_t EventCallbackDispatch(UAVObjEvent* ev, UAVObjEventCallback cb) * \param[in] periodMs The period the event is generated * \return Success (0), failure (-1) */ -int32_t EventPeriodicCallbackCreate(UAVObjEvent* ev, UAVObjEventCallback cb, int32_t periodMs) +int32_t EventPeriodicCallbackCreate(UAVObjEvent* ev, UAVObjEventCallback cb, uint16_t periodMs) { return eventPeriodicCreate(ev, cb, 0, periodMs); } @@ -163,7 +163,7 @@ int32_t EventPeriodicCallbackCreate(UAVObjEvent* ev, UAVObjEventCallback cb, int * \param[in] periodMs The period the event is generated * \return Success (0), failure (-1) */ -int32_t EventPeriodicCallbackUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, int32_t periodMs) +int32_t EventPeriodicCallbackUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, uint16_t periodMs) { return eventPeriodicUpdate(ev, cb, 0, periodMs); } @@ -175,7 +175,7 @@ int32_t EventPeriodicCallbackUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, int * \param[in] periodMs The period the event is generated * \return Success (0), failure (-1) */ -int32_t EventPeriodicQueueCreate(UAVObjEvent* ev, xQueueHandle queue, int32_t periodMs) +int32_t EventPeriodicQueueCreate(UAVObjEvent* ev, xQueueHandle queue, uint16_t periodMs) { return eventPeriodicCreate(ev, 0, queue, periodMs); } @@ -187,7 +187,7 @@ int32_t EventPeriodicQueueCreate(UAVObjEvent* ev, xQueueHandle queue, int32_t pe * \param[in] periodMs The period the event is generated * \return Success (0), failure (-1) */ -int32_t EventPeriodicQueueUpdate(UAVObjEvent* ev, xQueueHandle queue, int32_t periodMs) +int32_t EventPeriodicQueueUpdate(UAVObjEvent* ev, xQueueHandle queue, uint16_t periodMs) { return eventPeriodicUpdate(ev, 0, queue, periodMs); } @@ -200,7 +200,7 @@ int32_t EventPeriodicQueueUpdate(UAVObjEvent* ev, xQueueHandle queue, int32_t pe * \param[in] periodMs The period the event is generated * \return Success (0), failure (-1) */ -static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQueueHandle queue, int32_t periodMs) +static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQueueHandle queue, uint16_t periodMs) { PeriodicObjectList* objEntry; // Get lock @@ -244,7 +244,7 @@ static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQue * \param[in] periodMs The period the event is generated * \return Success (0), failure (-1) */ -static int32_t eventPeriodicUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, xQueueHandle queue, int32_t periodMs) +static int32_t eventPeriodicUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, xQueueHandle queue, uint16_t periodMs) { PeriodicObjectList* objEntry; // Get lock @@ -350,6 +350,8 @@ static int32_t processPeriodicUpdates() { if ( xQueueSend(objEntry->evInfo.queue, &objEntry->evInfo.ev, 0) != pdTRUE ) // do not block if queue is full { + if (objEntry->evInfo.ev.obj != NULL) + stats.lastErrorID = UAVObjGetID(objEntry->evInfo.ev.obj); ++stats.eventErrors; } } @@ -372,7 +374,7 @@ static int32_t processPeriodicUpdates() * Based on the Park-Miller-Carta Pseudo-Random Number Generator * http://www.firstpr.com.au/dsp/rand31/ */ -static uint32_t randomizePeriod(uint32_t periodMs) +static uint16_t randomizePeriod(uint16_t periodMs) { static uint32_t seed = 1; uint32_t hi, lo; @@ -382,6 +384,6 @@ static uint32_t randomizePeriod(uint32_t periodMs) lo += hi >> 15; if (lo > 0x7FFFFFFF) lo -= 0x7FFFFFFF; seed = lo; - return (uint32_t)( ((float)periodMs * (float)lo) / (float)0x7FFFFFFF ); + return (uint16_t)( ((float)periodMs * (float)lo) / (float)0x7FFFFFFF ); } diff --git a/flight/UAVObjects/inc/eventdispatcher.h b/flight/UAVObjects/inc/eventdispatcher.h index 9e378b65a..5c2f7e148 100644 --- a/flight/UAVObjects/inc/eventdispatcher.h +++ b/flight/UAVObjects/inc/eventdispatcher.h @@ -31,6 +31,7 @@ * Event dispatcher statistics */ typedef struct { + uint32_t lastErrorID; uint32_t eventErrors; } EventStats; @@ -39,9 +40,9 @@ int32_t EventDispatcherInitialize(); void EventGetStats(EventStats* statsOut); void EventClearStats(); int32_t EventCallbackDispatch(UAVObjEvent* ev, UAVObjEventCallback cb); -int32_t EventPeriodicCallbackCreate(UAVObjEvent* ev, UAVObjEventCallback cb, int32_t periodMs); -int32_t EventPeriodicCallbackUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, int32_t periodMs); -int32_t EventPeriodicQueueCreate(UAVObjEvent* ev, xQueueHandle queue, int32_t periodMs); -int32_t EventPeriodicQueueUpdate(UAVObjEvent* ev, xQueueHandle queue, int32_t periodMs); +int32_t EventPeriodicCallbackCreate(UAVObjEvent* ev, UAVObjEventCallback cb, uint16_t periodMs); +int32_t EventPeriodicCallbackUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, uint16_t periodMs); +int32_t EventPeriodicQueueCreate(UAVObjEvent* ev, xQueueHandle queue, uint16_t periodMs); +int32_t EventPeriodicQueueUpdate(UAVObjEvent* ev, xQueueHandle queue, uint16_t periodMs); #endif // EVENTDISPATCHER_H diff --git a/flight/UAVObjects/inc/uavobjectmanager.h b/flight/UAVObjects/inc/uavobjectmanager.h index ac5d34b5c..bd1dc7f5f 100644 --- a/flight/UAVObjects/inc/uavobjectmanager.h +++ b/flight/UAVObjects/inc/uavobjectmanager.h @@ -35,6 +35,17 @@ #define UAVOBJ_ALL_INSTANCES 0xFFFF #define UAVOBJ_MAX_INSTANCES 1000 +/* + * Shifts and masks used to read/write metadata flags. + */ +#define UAVOBJ_ACCESS_SHIFT 0 +#define UAVOBJ_GCS_ACCESS_SHIFT 1 +#define UAVOBJ_TELEMETRY_ACKED_SHIFT 2 +#define UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT 3 +#define UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT 4 +#define UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT 6 +#define UAVOBJ_UPDATE_MODE_MASK 0x3 + // FIXME: All this typedef for SDCARD needs to be abstracted away #if !defined(PIOS_INCLUDE_SDCARD) @@ -50,42 +61,50 @@ typedef void* UAVObjHandle; typedef enum { UPDATEMODE_PERIODIC = 0, /** Automatically update object at periodic intervals */ UPDATEMODE_ONCHANGE = 1, /** Only update object when its data changes */ - UPDATEMODE_MANUAL = 2, /** Manually update object, by calling the updated() function */ - UPDATEMODE_NEVER = 3 /** Object is never updated */ + UPDATEMODE_THROTTLED = 2, /** Object is updated on change, but not more often than the interval time */ + UPDATEMODE_MANUAL = 3 /** Manually update object, by calling the updated() function */ } UAVObjUpdateMode; /** * Object metadata, each object has a meta object that holds its metadata. The metadata define * properties for each object and can be used by multiple modules (e.g. telemetry and logger) + * + * The object metadata flags are packed into a single 16 bit integer. + * The bits in the flag field are defined as: + * + * Bit(s) Name Meaning + * ------ ---- ------- + * 0 access Defines the access level for the local transactions (readonly=1 and readwrite=0) + * 1 gcsAccess Defines the access level for the local GCS transactions (readonly=1 and readwrite=0), not used in the flight s/w + * 2 telemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 3 gcsTelemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 4-5 telemetryUpdateMode Update mode used by the telemetry module (UAVObjUpdateMode) + * 6-7 gcsTelemetryUpdateMode Update mode used by the GCS (UAVObjUpdateMode) */ typedef struct { - uint8_t access; /** Defines the access level for the local transactions (readonly and readwrite) */ - uint8_t gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite), not used in the flight s/w */ - uint8_t telemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - uint8_t telemetryUpdateMode; /** Update mode used by the telemetry module (UAVObjUpdateMode) */ - uint32_t telemetryUpdatePeriod; /** Update period used by the telemetry module (only if telemetry mode is PERIODIC) */ - uint8_t gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - uint8_t gcsTelemetryUpdateMode; /** Update mode used by the GCS (UAVObjUpdateMode) */ - uint32_t gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - uint8_t loggingUpdateMode; /** Update mode used by the logging module (UAVObjUpdateMode) */ - uint32_t loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ + uint8_t flags; /** Defines flags for update and logging modes and whether an update should be ACK'd (bits defined above) */ + uint16_t telemetryUpdatePeriod; /** Update period used by the telemetry module (only if telemetry mode is PERIODIC) */ + uint16_t gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + uint16_t loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ } __attribute__((packed)) UAVObjMetadata; /** * Event types generated by the objects. */ typedef enum { + EV_NONE = 0x00, /** No event */ EV_UNPACKED = 0x01, /** Object data updated by unpacking */ - EV_UPDATED = 0x02, /** Object data updated by changing the data structure */ - EV_UPDATED_MANUAL = 0x04, /** Object update event manually generated */ - EV_UPDATE_REQ = 0x08 /** Request to update object data */ + EV_UPDATED = 0x02, /** Object data updated by changing the data structure */ + EV_UPDATED_MANUAL = 0x04, /** Object update event manually generated */ + EV_UPDATED_PERIODIC = 0x08, /** Object update from periodic event */ + EV_UPDATE_REQ = 0x10 /** Request to update object data */ } UAVObjEventType; /** * Helper macros for event masks */ #define EV_MASK_ALL 0 -#define EV_MASK_ALL_UPDATES (EV_UNPACKED | EV_UPDATED | EV_UPDATED_MANUAL) +#define EV_MASK_ALL_UPDATES (EV_UNPACKED | EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATED_PERIODIC) /** * Access types @@ -120,7 +139,10 @@ typedef void (*UAVObjInitializeCallback)(UAVObjHandle obj, uint16_t instId); * Event manager statistics */ typedef struct { - uint32_t eventErrors; + uint32_t eventQueueErrors; + uint32_t eventCallbackErrors; + uint32_t lastCallbackErrorID; + uint32_t lastQueueErrorID; } UAVObjStats; int32_t UAVObjInitialize(); @@ -162,10 +184,24 @@ int32_t UAVObjGetInstanceData(UAVObjHandle obj, uint16_t instId, void* dataOut); int32_t UAVObjGetInstanceDataField(UAVObjHandle obj, uint16_t instId, void* dataOut, uint32_t offset, uint32_t size); int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata* dataIn); int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata* dataOut); +uint8_t UAVObjGetMetadataAccess(const UAVObjMetadata* dataOut); +void UAVObjMetadataInitialize(UAVObjMetadata* dataOut); +UAVObjAccessType UAVObjGetAccess(const UAVObjMetadata* dataOut); +void UAVObjSetAccess(UAVObjMetadata* dataOut, UAVObjAccessType mode); +UAVObjAccessType UAVObjGetGcsAccess(const UAVObjMetadata* dataOut); +void UAVObjSetGcsAccess(UAVObjMetadata* dataOut, UAVObjAccessType mode); +uint8_t UAVObjGetTelemetryAcked(const UAVObjMetadata* dataOut); +void UAVObjSetTelemetryAcked( UAVObjMetadata* dataOut, uint8_t val); +uint8_t UAVObjGetGcsTelemetryAcked(const UAVObjMetadata* dataOut); +void UAVObjSetGcsTelemetryAcked(UAVObjMetadata* dataOut, uint8_t val); +UAVObjUpdateMode UAVObjGetTelemetryUpdateMode(const UAVObjMetadata* dataOut); +void UAVObjSetTelemetryUpdateMode(UAVObjMetadata* dataOut, UAVObjUpdateMode val); +UAVObjUpdateMode UAVObjGetGcsTelemetryUpdateMode(const UAVObjMetadata* dataOut); +void UAVObjSetTelemetryGcsUpdateMode(UAVObjMetadata* dataOut, UAVObjUpdateMode val); int8_t UAVObjReadOnly(UAVObjHandle obj); -int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue, int32_t eventMask); +int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue, uint8_t eventMask); int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue); -int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb, int32_t eventMask); +int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb, uint8_t eventMask); int32_t UAVObjDisconnectCallback(UAVObjHandle obj, UAVObjEventCallback cb); void UAVObjRequestUpdate(UAVObjHandle obj); void UAVObjRequestInstanceUpdate(UAVObjHandle obj, uint16_t instId); diff --git a/flight/UAVObjects/uavobjectmanager.c b/flight/UAVObjects/uavobjectmanager.c index 7d30bee7b..8dc077967 100644 --- a/flight/UAVObjects/uavobjectmanager.c +++ b/flight/UAVObjects/uavobjectmanager.c @@ -37,13 +37,22 @@ // Private types +// Macros +#define SET_BITS(var, shift, value, mask) var = (var & ~(mask << shift)) | (value << shift); +#define OLGetIsMetaobject(olp) ((olp)->flags & OL_IS_METAOBJECT) +#define OLSetIsMetaobject(olp, val) ((olp)->flags = (((val) == 0) ? ((olp)->flags & ~OL_IS_METAOBJECT) : ((olp)->flags | OL_IS_METAOBJECT))) +#define OLGetIsSingleInstance(olp) ((olp)->flags & OL_IS_SINGLE_INSTANCE) +#define OLSetIsSingleInstance(olp, val) ((olp)->flags = (((val) == 0) ? ((olp)->flags & ~OL_IS_SINGLE_INSTANCE) : ((olp)->flags | OL_IS_SINGLE_INSTANCE))) +#define OLGetIsSettings(olp) ((olp)->flags & OL_IS_SETTINGS) +#define OLSetIsSettings(olp, val) ((olp)->flags = (((val) == 0) ? ((olp)->flags & ~OL_IS_SETTINGS) : ((olp)->flags | OL_IS_SETTINGS))) + /** * List of event queues and the eventmask associated with the queue. */ struct ObjectEventListStruct { xQueueHandle queue; UAVObjEventCallback cb; - int32_t eventMask; + uint8_t eventMask; struct ObjectEventListStruct *next; }; typedef struct ObjectEventListStruct ObjectEventList; @@ -58,6 +67,12 @@ struct ObjectInstListStruct { }; typedef struct ObjectInstListStruct ObjectInstList; +typedef enum { + OL_IS_METAOBJECT = 0x01, /** Set if this is a metaobject */ + OL_IS_SINGLE_INSTANCE = 0x02, /** Set if this object has a single instance */ + OL_IS_SETTINGS = 0x04 /** Set if this object is a settings object */ +} ObjectListFlags; + /** * List of objects registered in the object manager */ @@ -66,12 +81,8 @@ struct ObjectListStruct { /** The object ID */ const char *name; /** The object name */ - int8_t isMetaobject; - /** Set to 1 if this is a metaobject */ - int8_t isSingleInstance; - /** Set to 1 if this object has a single instance */ - int8_t isSettings; - /** Set to 1 if this object is a settings object */ + ObjectListFlags flags; + /** The object list mode flags */ uint16_t numBytes; /** Number of data bytes contained in the object (for a single instance) */ uint16_t numInstances; @@ -93,7 +104,7 @@ static int32_t sendEvent(ObjectList * obj, uint16_t instId, static ObjectInstList *createInstance(ObjectList * obj, uint16_t instId); static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId); static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue, - UAVObjEventCallback cb, int32_t eventMask); + UAVObjEventCallback cb, uint8_t eventMask); static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb); @@ -125,16 +136,7 @@ int32_t UAVObjInitialize() return -1; // Initialize default metadata structure (metadata of metaobjects) - defMetadata.access = ACCESS_READWRITE; - defMetadata.gcsAccess = ACCESS_READWRITE; - defMetadata.telemetryAcked = 1; - defMetadata.telemetryUpdateMode = UPDATEMODE_ONCHANGE; - defMetadata.telemetryUpdatePeriod = 0; - defMetadata.gcsTelemetryAcked = 1; - defMetadata.gcsTelemetryUpdateMode = UPDATEMODE_ONCHANGE; - defMetadata.gcsTelemetryUpdatePeriod = 0; - defMetadata.loggingUpdateMode = UPDATEMODE_ONCHANGE; - defMetadata.loggingUpdatePeriod = 0; + UAVObjMetadataInitialize(&defMetadata); // Done return 0; @@ -204,9 +206,9 @@ UAVObjHandle UAVObjRegister(uint32_t id, const char *name, } objEntry->id = id; objEntry->name = name; - objEntry->isMetaobject = (int8_t) isMetaobject; - objEntry->isSingleInstance = (int8_t) isSingleInstance; - objEntry->isSettings = (int8_t) isSettings; + OLSetIsMetaobject(objEntry, isMetaobject); + OLSetIsSingleInstance(objEntry, isSingleInstance); + OLSetIsSettings(objEntry, isSettings); objEntry->numBytes = numBytes; objEntry->events = NULL; objEntry->numInstances = 0; @@ -243,11 +245,11 @@ UAVObjHandle UAVObjRegister(uint32_t id, const char *name, initCb((UAVObjHandle) objEntry, 0); } // Attempt to load object's metadata from the SD card (not done directly on the metaobject, but through the object) - if (!objEntry->isMetaobject) { + if (!OLGetIsMetaobject(objEntry)) { UAVObjLoad((UAVObjHandle) objEntry->linkedObj, 0); } // If this is a settings object, attempt to load from SD card - if (objEntry->isSettings) { + if (OLGetIsSettings(objEntry)) { UAVObjLoad((UAVObjHandle) objEntry, 0); } // Release lock @@ -403,7 +405,7 @@ uint16_t UAVObjCreateInstance(UAVObjHandle obj, */ int32_t UAVObjIsSingleInstance(UAVObjHandle obj) { - return ((ObjectList *) obj)->isSingleInstance; + return OLGetIsSingleInstance((ObjectList *) obj); } /** @@ -413,7 +415,7 @@ int32_t UAVObjIsSingleInstance(UAVObjHandle obj) */ int32_t UAVObjIsMetaobject(UAVObjHandle obj) { - return ((ObjectList *) obj)->isMetaobject; + return OLGetIsMetaobject((ObjectList *) obj); } /** @@ -423,7 +425,7 @@ int32_t UAVObjIsMetaobject(UAVObjHandle obj) */ int32_t UAVObjIsSettings(UAVObjHandle obj) { - return ((ObjectList *) obj)->isSettings; + return OLGetIsSettings((ObjectList *) obj); } /** @@ -539,7 +541,7 @@ int32_t UAVObjSaveToFile(UAVObjHandle obj, uint16_t instId, &bytesWritten); // Write the instance ID - if (!objEntry->isSingleInstance) { + if (!OLGetIsSingleInstance(objEntry)) { PIOS_FWRITE(file, &instEntry->instId, sizeof(instEntry->instId), &bytesWritten); } @@ -658,7 +660,7 @@ UAVObjHandle UAVObjLoadFromFile(FILEINFO * file) // Get the instance ID instId = 0; - if (!objEntry->isSingleInstance) { + if (!OLGetIsSingleInstance(objEntry)) { if (PIOS_FREAD (file, &instId, sizeof(instId), &bytesRead)) { xSemaphoreGiveRecursive(mutex); @@ -719,10 +721,11 @@ int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId) return -1; // Fire event on success - if (PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data) == 0) + int32_t retval; + if ((retval = PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data)) == 0) sendEvent(objEntry, instId, EV_UNPACKED); else - return -1; + return retval; #endif #if defined(PIOS_INCLUDE_SDCARD) @@ -822,7 +825,7 @@ int32_t UAVObjSaveSettings() // Save all settings objects LL_FOREACH(objList, objEntry) { // Check if this is a settings object - if (objEntry->isSettings) { + if (OLGetIsSettings(objEntry)) { // Save object if (UAVObjSave((UAVObjHandle) objEntry, 0) == -1) { @@ -851,7 +854,7 @@ int32_t UAVObjLoadSettings() // Load all settings objects LL_FOREACH(objList, objEntry) { // Check if this is a settings object - if (objEntry->isSettings) { + if (OLGetIsSettings(objEntry)) { // Load object if (UAVObjLoad((UAVObjHandle) objEntry, 0) == -1) { @@ -880,7 +883,7 @@ int32_t UAVObjDeleteSettings() // Save all settings objects LL_FOREACH(objList, objEntry) { // Check if this is a settings object - if (objEntry->isSettings) { + if (OLGetIsSettings(objEntry)) { // Save object if (UAVObjDelete((UAVObjHandle) objEntry, 0) == -1) { @@ -909,7 +912,7 @@ int32_t UAVObjSaveMetaobjects() // Save all settings objects LL_FOREACH(objList, objEntry) { // Check if this is a settings object - if (objEntry->isMetaobject) { + if (OLGetIsMetaobject(objEntry)) { // Save object if (UAVObjSave((UAVObjHandle) objEntry, 0) == -1) { @@ -938,7 +941,7 @@ int32_t UAVObjLoadMetaobjects() // Load all settings objects LL_FOREACH(objList, objEntry) { // Check if this is a settings object - if (objEntry->isMetaobject) { + if (OLGetIsMetaobject(objEntry)) { // Load object if (UAVObjLoad((UAVObjHandle) objEntry, 0) == -1) { @@ -967,7 +970,7 @@ int32_t UAVObjDeleteMetaobjects() // Load all settings objects LL_FOREACH(objList, objEntry) { // Check if this is a settings object - if (objEntry->isMetaobject) { + if (OLGetIsMetaobject(objEntry)) { // Load object if (UAVObjDelete((UAVObjHandle) objEntry, 0) == -1) { @@ -1047,11 +1050,11 @@ int32_t UAVObjSetInstanceData(UAVObjHandle obj, uint16_t instId, objEntry = (ObjectList *) obj; // Check access level - if (!objEntry->isMetaobject) { + if (!OLGetIsMetaobject(objEntry)) { mdata = (UAVObjMetadata *) (objEntry->linkedObj->instances. data); - if (mdata->access == ACCESS_READONLY) { + if (UAVObjGetAccess(mdata) == ACCESS_READONLY) { xSemaphoreGiveRecursive(mutex); return -1; } @@ -1094,10 +1097,10 @@ int32_t UAVObjSetInstanceDataField(UAVObjHandle obj, uint16_t instId, const void objEntry = (ObjectList*)obj; // Check access level - if ( !objEntry->isMetaobject ) + if ( !OLGetIsMetaobject(objEntry) ) { mdata = (UAVObjMetadata*)(objEntry->linkedObj->instances.data); - if ( mdata->access == ACCESS_READONLY ) + if ( UAVObjGetAccess(mdata) == ACCESS_READONLY ) { xSemaphoreGiveRecursive(mutex); return -1; @@ -1223,7 +1226,7 @@ int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata * dataIn) // Set metadata (metadata of metaobjects can not be modified) objEntry = (ObjectList *) obj; - if (!objEntry->isMetaobject) { + if (!OLGetIsMetaobject(objEntry)) { UAVObjSetData((UAVObjHandle) objEntry->linkedObj, dataIn); } else { @@ -1250,7 +1253,7 @@ int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata * dataOut) // Get metadata objEntry = (ObjectList *) obj; - if (objEntry->isMetaobject) { + if (OLGetIsMetaobject(objEntry)) { memcpy(dataOut, &defMetadata, sizeof(UAVObjMetadata)); } else { UAVObjGetData((UAVObjHandle) objEntry->linkedObj, @@ -1262,6 +1265,136 @@ int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata * dataOut) return 0; } +/** + * Initialize a UAVObjMetadata object. + * \param[in] metadata The metadata object + */ +void UAVObjMetadataInitialize(UAVObjMetadata* metadata) +{ + metadata->flags = + ACCESS_READWRITE << UAVOBJ_ACCESS_SHIFT | + ACCESS_READWRITE << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UPDATEMODE_ONCHANGE << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UPDATEMODE_ONCHANGE << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata->telemetryUpdatePeriod = 0; + metadata->gcsTelemetryUpdatePeriod = 0; + metadata->loggingUpdatePeriod = 0; +} + +/** + * Get the UAVObject metadata access member + * \param[in] metadata The metadata object + * \return the access type + */ +UAVObjAccessType UAVObjGetAccess(const UAVObjMetadata* metadata) +{ + return (metadata->flags >> UAVOBJ_ACCESS_SHIFT) & 1; +} + +/** + * Set the UAVObject metadata access member + * \param[in] metadata The metadata object + * \param[in] mode The access mode + */ +void UAVObjSetAccess(UAVObjMetadata* metadata, UAVObjAccessType mode) +{ + SET_BITS(metadata->flags, UAVOBJ_ACCESS_SHIFT, mode, 1); +} + +/** + * Get the UAVObject metadata GCS access member + * \param[in] metadata The metadata object + * \return the GCS access type + */ +UAVObjAccessType UAVObjGetGcsAccess(const UAVObjMetadata* metadata) +{ + return (metadata->flags >> UAVOBJ_GCS_ACCESS_SHIFT) & 1; +} + +/** + * Set the UAVObject metadata GCS access member + * \param[in] metadata The metadata object + * \param[in] mode The access mode + */ +void UAVObjSetGcsAccess(UAVObjMetadata* metadata, UAVObjAccessType mode) { + SET_BITS(metadata->flags, UAVOBJ_GCS_ACCESS_SHIFT, mode, 1); +} + +/** + * Get the UAVObject metadata telemetry acked member + * \param[in] metadata The metadata object + * \return the telemetry acked boolean + */ +uint8_t UAVObjGetTelemetryAcked(const UAVObjMetadata* metadata) { + return (metadata->flags >> UAVOBJ_TELEMETRY_ACKED_SHIFT) & 1; +} + +/** + * Set the UAVObject metadata telemetry acked member + * \param[in] metadata The metadata object + * \param[in] val The telemetry acked boolean + */ +void UAVObjSetTelemetryAcked(UAVObjMetadata* metadata, uint8_t val) { + SET_BITS(metadata->flags, UAVOBJ_TELEMETRY_ACKED_SHIFT, val, 1); +} + +/** + * Get the UAVObject metadata GCS telemetry acked member + * \param[in] metadata The metadata object + * \return the telemetry acked boolean + */ +uint8_t UAVObjGetGcsTelemetryAcked(const UAVObjMetadata* metadata) { + return (metadata->flags >> UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT) & 1; +} + +/** + * Set the UAVObject metadata GCS telemetry acked member + * \param[in] metadata The metadata object + * \param[in] val The GCS telemetry acked boolean + */ +void UAVObjSetGcsTelemetryAcked(UAVObjMetadata* metadata, uint8_t val) { + SET_BITS(metadata->flags, UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT, val, 1); +} + +/** + * Get the UAVObject metadata telemetry update mode + * \param[in] metadata The metadata object + * \return the telemetry update mode + */ +UAVObjUpdateMode UAVObjGetTelemetryUpdateMode(const UAVObjMetadata* metadata) { + return (metadata->flags >> UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK; +} + +/** + * Set the UAVObject metadata telemetry update mode member + * \param[in] metadata The metadata object + * \param[in] val The telemetry update mode + */ +void UAVObjSetTelemetryUpdateMode(UAVObjMetadata* metadata, UAVObjUpdateMode val) { + SET_BITS(metadata->flags, UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT, val, UAVOBJ_UPDATE_MODE_MASK); +} + +/** + * Get the UAVObject metadata GCS telemetry update mode + * \param[in] metadata The metadata object + * \return the GCS telemetry update mode + */ +UAVObjUpdateMode UAVObjGetGcsTelemetryUpdateMode(const UAVObjMetadata* metadata) { + return (metadata->flags >> UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK; +} + +/** + * Set the UAVObject metadata GCS telemetry update mode member + * \param[in] metadata The metadata object + * \param[in] val The GCS telemetry update mode + */ +void UAVObjSetGcsTelemetryUpdateMode(UAVObjMetadata* metadata, UAVObjUpdateMode val) { + SET_BITS(metadata->flags, UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT, val, UAVOBJ_UPDATE_MODE_MASK); +} + + /** * Check if an object is read only * \param[in] obj The object handle @@ -1279,11 +1412,11 @@ int8_t UAVObjReadOnly(UAVObjHandle obj) objEntry = (ObjectList *) obj; // Check access level - if (!objEntry->isMetaobject) { + if (!OLGetIsMetaobject(objEntry)) { mdata = (UAVObjMetadata *) (objEntry->linkedObj->instances. data); - return mdata->access == ACCESS_READONLY; + return UAVObjGetAccess(mdata) == ACCESS_READONLY; } return -1; } @@ -1297,7 +1430,7 @@ int8_t UAVObjReadOnly(UAVObjHandle obj) * \return 0 if success or -1 if failure */ int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue, - int32_t eventMask) + uint8_t eventMask) { int32_t res; xSemaphoreTakeRecursive(mutex, portMAX_DELAY); @@ -1330,7 +1463,7 @@ int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue) * \return 0 if success or -1 if failure */ int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb, - int32_t eventMask) + uint8_t eventMask) { int32_t res; xSemaphoreTakeRecursive(mutex, portMAX_DELAY); @@ -1441,14 +1574,16 @@ static int32_t sendEvent(ObjectList * obj, uint16_t instId, if (eventEntry->queue != 0) { if (xQueueSend(eventEntry->queue, &msg, 0) != pdTRUE) // will not block { - ++stats.eventErrors; + stats.lastQueueErrorID = UAVObjGetID(obj); + ++stats.eventQueueErrors; } } // Invoke callback (from event task) if a valid one is registered if (eventEntry->cb != 0) { if (EventCallbackDispatch(&msg, eventEntry->cb) != pdTRUE) // invoke callback from the event task, will not block { - ++stats.eventErrors; + ++stats.eventCallbackErrors; + stats.lastCallbackErrorID = UAVObjGetID(obj); } } } @@ -1467,7 +1602,7 @@ static ObjectInstList *createInstance(ObjectList * obj, uint16_t instId) int32_t n; // For single instance objects, only instance zero is allowed - if (obj->isSingleInstance && instId != 0) { + if (OLGetIsSingleInstance(obj) && instId != 0) { return NULL; } // Make sure that the instance ID is within limits @@ -1541,7 +1676,7 @@ static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId) * \return 0 if success or -1 if failure */ static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue, - UAVObjEventCallback cb, int32_t eventMask) + UAVObjEventCallback cb, uint8_t eventMask) { ObjectEventList *eventEntry; ObjectList *objEntry; diff --git a/flight/UAVObjects/uavobjectsinittemplate.c b/flight/UAVObjects/uavobjectsinittemplate.c index 97a1525a4..75a104d18 100644 --- a/flight/UAVObjects/uavobjectsinittemplate.c +++ b/flight/UAVObjects/uavobjectsinittemplate.c @@ -36,7 +36,5 @@ $(OBJINC) */ void UAVObjectsInitializeAll() { -return; -// This function is no longer used anyway $(OBJINIT) } diff --git a/flight/UAVObjects/uavobjecttemplate.c b/flight/UAVObjects/uavobjecttemplate.c index 6d572dbcb..ad37eef83 100644 --- a/flight/UAVObjects/uavobjecttemplate.c +++ b/flight/UAVObjects/uavobjecttemplate.c @@ -85,15 +85,15 @@ $(INITFIELDS) UAVObjSetInstanceData(obj, instId, &data); // Initialize object metadata to their default values - metadata.access = $(FLIGHTACCESS); - metadata.gcsAccess = $(GCSACCESS); - metadata.telemetryAcked = $(FLIGHTTELEM_ACKED); - metadata.telemetryUpdateMode = $(FLIGHTTELEM_UPDATEMODE); + metadata.flags = + $(FLIGHTACCESS) << UAVOBJ_ACCESS_SHIFT | + $(GCSACCESS) << UAVOBJ_GCS_ACCESS_SHIFT | + $(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT | + $(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + $(FLIGHTTELEM_UPDATEMODE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + $(GCSTELEM_UPDATEMODE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; metadata.telemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - metadata.gcsTelemetryAcked = $(GCSTELEM_ACKED); - metadata.gcsTelemetryUpdateMode = $(GCSTELEM_UPDATEMODE); metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - metadata.loggingUpdateMode = $(LOGGING_UPDATEMODE); metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); UAVObjSetMetadata(obj, &metadata); } diff --git a/flight/UAVTalk/inc/uavtalk.h b/flight/UAVTalk/inc/uavtalk.h index 3b7f2a2f9..a45fdb0db 100644 --- a/flight/UAVTalk/inc/uavtalk.h +++ b/flight/UAVTalk/inc/uavtalk.h @@ -45,13 +45,18 @@ typedef struct { typedef void* UAVTalkConnection; +typedef enum {UAVTALK_STATE_ERROR=0, UAVTALK_STATE_SYNC, UAVTALK_STATE_TYPE, UAVTALK_STATE_SIZE, UAVTALK_STATE_OBJID, UAVTALK_STATE_INSTID, UAVTALK_STATE_DATA, UAVTALK_STATE_CS, UAVTALK_STATE_COMPLETE} UAVTalkRxState; + // Public functions UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream); int32_t UAVTalkSetOutputStream(UAVTalkConnection connection, UAVTalkOutputStream outputStream); UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connection); int32_t UAVTalkSendObject(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs); int32_t UAVTalkSendObjectRequest(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, int32_t timeoutMs); -int32_t UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte); +int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId); +int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId); +UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte); +UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connection, uint8_t rxbyte); void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats); void UAVTalkResetStats(UAVTalkConnection connection); diff --git a/flight/UAVTalk/inc/uavtalk_priv.h b/flight/UAVTalk/inc/uavtalk_priv.h index 77863a6a8..992bf91af 100644 --- a/flight/UAVTalk/inc/uavtalk_priv.h +++ b/flight/UAVTalk/inc/uavtalk_priv.h @@ -55,8 +55,6 @@ typedef uint8_t uavtalk_checksum; #define UAVTALK_MIN_PACKET_LENGTH UAVTALK_MAX_HEADER_LENGTH + UAVTALK_CHECKSUM_LENGTH #define UAVTALK_MAX_PACKET_LENGTH UAVTALK_MIN_PACKET_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH -typedef enum {UAVTALK_STATE_SYNC, UAVTALK_STATE_TYPE, UAVTALK_STATE_SIZE, UAVTALK_STATE_OBJID, UAVTALK_STATE_INSTID, UAVTALK_STATE_DATA, UAVTALK_STATE_CS} UAVTalkRxState; - typedef struct { UAVObjHandle obj; uint8_t type; diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c index 844ed5e38..bf0d7e100 100644 --- a/flight/UAVTalk/uavtalk.c +++ b/flight/UAVTalk/uavtalk.c @@ -252,16 +252,18 @@ static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle * Process an byte from the telemetry stream. * \param[in] connection UAVTalkConnection to be used * \param[in] rxbyte Received byte - * \return 0 Success - * \return -1 Failure + * \return UAVTalkRxState */ -int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte) +UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connectionHandle, uint8_t rxbyte) { UAVTalkConnectionData *connection; CHECKCONHANDLE(connectionHandle,connection,return -1); UAVTalkInputProcessor *iproc = &connection->iproc; ++connection->stats.rxBytes; + + if (iproc->state == UAVTALK_STATE_ERROR || iproc->state == UAVTALK_STATE_COMPLETE) + iproc->state = UAVTALK_STATE_SYNC; if (iproc->rxPacketLength < 0xffff) iproc->rxPacketLength++; // update packet byte count @@ -288,7 +290,7 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx if ((rxbyte & UAVTALK_TYPE_MASK) != UAVTALK_TYPE_VER) { - iproc->state = UAVTALK_STATE_SYNC; + iproc->state = UAVTALK_STATE_ERROR; break; } @@ -316,7 +318,7 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx if (iproc->packet_size < UAVTALK_MIN_HEADER_LENGTH || iproc->packet_size > UAVTALK_MAX_HEADER_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH) { // incorrect packet size - iproc->state = UAVTALK_STATE_SYNC; + iproc->state = UAVTALK_STATE_ERROR; break; } @@ -335,17 +337,8 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx if (iproc->rxCount < 4) break; - // Search for object, if not found reset state machine - // except if we got a OBJ_REQ for an object which does not - // exist, in which case we'll send a NACK - + // Search for object. iproc->obj = UAVObjGetByID(iproc->objId); - if (iproc->obj == 0 && iproc->type != UAVTALK_TYPE_OBJ_REQ) - { - connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_SYNC; - break; - } // Determine data length if (iproc->type == UAVTALK_TYPE_OBJ_REQ || iproc->type == UAVTALK_TYPE_ACK || iproc->type == UAVTALK_TYPE_NACK) @@ -355,15 +348,24 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx } else { - iproc->length = UAVObjGetNumBytes(iproc->obj); - iproc->instanceLength = (UAVObjIsSingleInstance(iproc->obj) ? 0 : 2); + if (iproc->obj) + { + iproc->length = UAVObjGetNumBytes(iproc->obj); + iproc->instanceLength = (UAVObjIsSingleInstance(iproc->obj) ? 0 : 2); + } + else + { + // We don't know if it's a multi-instance object, so just assume it's 0. + iproc->instanceLength = 0; + iproc->length = iproc->packet_size - iproc->rxPacketLength; + } } // Check length and determine next state if (iproc->length >= UAVTALK_MAX_PAYLOAD_LENGTH) { connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_SYNC; + iproc->state = UAVTALK_STATE_ERROR; break; } @@ -371,34 +373,30 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx if ((iproc->rxPacketLength + iproc->instanceLength + iproc->length) != iproc->packet_size) { // packet error - mismatched packet size connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_SYNC; + iproc->state = UAVTALK_STATE_ERROR; break; } iproc->instId = 0; - if (iproc->obj == 0) + if (iproc->type == UAVTALK_TYPE_NACK) { // If this is a NACK, we skip to Checksum iproc->state = UAVTALK_STATE_CS; - iproc->rxCount = 0; - } // Check if this is a single instance object (i.e. if the instance ID field is coming next) - else if (UAVObjIsSingleInstance(iproc->obj)) + else if ((iproc->obj != 0) && !UAVObjIsSingleInstance(iproc->obj)) + { + iproc->state = UAVTALK_STATE_INSTID; + } + else { // If there is a payload get it, otherwise receive checksum if (iproc->length > 0) iproc->state = UAVTALK_STATE_DATA; else iproc->state = UAVTALK_STATE_CS; - - iproc->rxCount = 0; - } - else - { - iproc->state = UAVTALK_STATE_INSTID; - iproc->rxCount = 0; } + iproc->rxCount = 0; break; @@ -441,33 +439,84 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx if (rxbyte != iproc->cs) { // packet error - faulty CRC connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_SYNC; + iproc->state = UAVTALK_STATE_ERROR; break; } if (iproc->rxPacketLength != (iproc->packet_size + 1)) { // packet error - mismatched packet size connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_SYNC; + iproc->state = UAVTALK_STATE_ERROR; break; } - - xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); - receiveObject(connection, iproc->type, iproc->objId, iproc->instId, connection->rxBuffer, iproc->length); + connection->stats.rxObjectBytes += iproc->length; connection->stats.rxObjects++; - xSemaphoreGiveRecursive(connection->lock); - - iproc->state = UAVTALK_STATE_SYNC; + + iproc->state = UAVTALK_STATE_COMPLETE; break; default: connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_SYNC; + iproc->state = UAVTALK_STATE_ERROR; } // Done - return 0; + return iproc->state; +} + +/** + * Process an byte from the telemetry stream. + * \param[in] connection UAVTalkConnection to be used + * \param[in] rxbyte Received byte + * \return UAVTalkRxState + */ +UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte) +{ + UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(connectionHandle, rxbyte); + + if (state == UAVTALK_STATE_COMPLETE) + { + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + UAVTalkInputProcessor *iproc = &connection->iproc; + + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + receiveObject(connection, iproc->type, iproc->objId, iproc->instId, connection->rxBuffer, iproc->length); + xSemaphoreGiveRecursive(connection->lock); + } + + return state; +} + +/** + * Send a ACK through the telemetry link. + * \param[in] connectionHandle UAVTalkConnection to be used + * \param[in] objId Object ID to send a NACK for + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + + return sendObject(connection, obj, instId, UAVTALK_TYPE_ACK); +} + +/** + * Send a NACK through the telemetry link. + * \param[in] connectionHandle UAVTalkConnection to be used + * \param[in] objId Object ID to send a NACK for + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + + return sendNack(connection, objId); } /** @@ -494,7 +543,7 @@ static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, ui switch (type) { case UAVTALK_TYPE_OBJ: // All instances, not allowed for OBJ messages - if (instId != UAVOBJ_ALL_INSTANCES) + if (obj && (instId != UAVOBJ_ALL_INSTANCES)) { // Unpack object, if the instance does not exist it will be created! UAVObjUnpack(obj, instId, data); @@ -508,7 +557,7 @@ static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, ui break; case UAVTALK_TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages - if (instId != UAVOBJ_ALL_INSTANCES) + if (obj && (instId != UAVOBJ_ALL_INSTANCES)) { // Unpack object, if the instance does not exist it will be created! if ( UAVObjUnpack(obj, instId, data) == 0 ) @@ -538,7 +587,7 @@ static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, ui break; case UAVTALK_TYPE_ACK: // All instances, not allowed for ACK messages - if (instId != UAVOBJ_ALL_INSTANCES) + if (obj && (instId != UAVOBJ_ALL_INSTANCES)) { // Check if an ack is pending updateAck(connection, obj, instId); diff --git a/flight/board_hw_defs/ahrs/board_hw_defs.c b/flight/board_hw_defs/ahrs/board_hw_defs.c deleted file mode 100644 index d774ce799..000000000 --- a/flight/board_hw_defs/ahrs/board_hw_defs.c +++ /dev/null @@ -1,351 +0,0 @@ -#include - -#if defined(PIOS_INCLUDE_LED) - -#include -static const struct pios_led pios_leds[] = { - [PIOS_LED_HEARTBEAT] = { - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Mode = GPIO_Mode_Out_PP, - .GPIO_Speed = GPIO_Speed_50MHz, - }, - }, - }, -}; - -static const struct pios_led_cfg pios_led_cfg = { - .leds = pios_leds, - .num_leds = NELEMENTS(pios_leds), -}; - -#endif /* PIOS_INCLUDE_LED */ - -#if defined(PIOS_INCLUDE_SPI) - -#include - -/* OP Interface - * - * NOTE: Leave this declared as const data so that it ends up in the - * .rodata section (ie. Flash) rather than in the .bss section (RAM). - */ -void PIOS_SPI_op_irq_handler(void); -void DMA1_Channel5_IRQHandler() __attribute__ ((alias("PIOS_SPI_op_irq_handler"))); -void DMA1_Channel4_IRQHandler() __attribute__ ((alias("PIOS_SPI_op_irq_handler"))); -static const struct pios_spi_cfg pios_spi_op_cfg = { - .regs = SPI2, - .init = { - .SPI_Mode = SPI_Mode_Slave, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Hard, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_2Edge, - }, - .use_crc = TRUE, - .dma = { - .ahb_clk = RCC_AHBPeriph_DMA1, - - .irq = { - .flags = - (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | - DMA1_FLAG_GL4), - .init = { - .NVIC_IRQChannel = DMA1_Channel4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA1_Channel4, - .init = { - .DMA_PeripheralBaseAddr = - (uint32_t) & (SPI2->DR), - .DMA_DIR = DMA_DIR_PeripheralSRC, - .DMA_PeripheralInc = - DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = - DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = - DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - .tx = { - .channel = DMA1_Channel5, - .init = { - .DMA_PeripheralBaseAddr = - (uint32_t) & (SPI2->DR), - .DMA_DIR = DMA_DIR_PeripheralDST, - .DMA_PeripheralInc = - DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = - DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = - DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - }, - .ssel = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, - .sclk = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_13, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, - .miso = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_14, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, - .mosi = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, -}; - -uint32_t pios_spi_op_id; -void PIOS_SPI_op_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_op_id); -} - -#endif /* PIOS_INCLUDE_SPI */ - -#if defined(PIOS_INCLUDE_ADC) - -/* - * ADC system - */ -#include "pios_adc_priv.h" -extern void PIOS_ADC_handler(void); -void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler"))); -// Remap the ADC DMA handler to this one -static const struct pios_adc_cfg pios_adc_cfg = { - .dma = { - .ahb_clk = RCC_AHBPeriph_DMA1, - .irq = { - .flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1), - .init = { - .NVIC_IRQChannel = DMA1_Channel1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .channel = DMA1_Channel1, - .init = { - .DMA_PeripheralBaseAddr = (uint32_t) & ADC1->DR, - .DMA_DIR = DMA_DIR_PeripheralSRC, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Word, - .DMA_Mode = DMA_Mode_Circular, - .DMA_Priority = DMA_Priority_High, - .DMA_M2M = DMA_M2M_Disable, - }, - } - }, - .half_flag = DMA1_IT_HT1, - .full_flag = DMA1_IT_TC1, -}; - -struct pios_adc_dev pios_adc_devs[] = { - { - .cfg = &pios_adc_cfg, - .callback_function = NULL, - }, -}; - -uint8_t pios_adc_num_devices = NELEMENTS(pios_adc_devs); - -void PIOS_ADC_handler() { - PIOS_ADC_DMA_Handler(); -} - -#endif /* PIOS_INCLUDE_ADC */ - -#if defined(PIOS_INCLUDE_USART) - -#include - -/* - * AUX USART - */ -static const struct pios_usart_cfg pios_usart_aux_cfg = { - .regs = USART3, - .init = { - .USART_BaudRate = 230400, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART3_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, -}; - -#endif /* PIOS_INCLUDE_USART */ - -#if defined(PIOS_INCLUDE_COM) - -#include - -#endif /* PIOS_INCLUDE_COM */ - -#if defined(PIOS_INCLUDE_I2C) - -#include - -/* - * I2C Adapters - */ - -void PIOS_I2C_main_adapter_ev_irq_handler(void); -void PIOS_I2C_main_adapter_er_irq_handler(void); -void I2C1_EV_IRQHandler() - __attribute__ ((alias("PIOS_I2C_main_adapter_ev_irq_handler"))); -void I2C1_ER_IRQHandler() - __attribute__ ((alias("PIOS_I2C_main_adapter_er_irq_handler"))); - -static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = { - .regs = I2C1, - .init = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_OwnAddress1 = 0, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 200000, /* bits/s */ - }, - .transfer_timeout_ms = 50, - .scl = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_OD, - }, - }, - .sda = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_OD, - }, - }, - .event = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C1_EV_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .error = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C1_ER_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -uint32_t pios_i2c_main_adapter_id; -void PIOS_I2C_main_adapter_ev_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_main_adapter_id); -} - -void PIOS_I2C_main_adapter_er_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_main_adapter_id); -} - -#endif /* PIOS_INCLUDE_I2C */ - -#if defined(PIOS_ENABLE_DEBUG_PINS) - -static const struct stm32_gpio pios_debug_pins[] = { - { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, - { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, -}; - -#endif /* PIOS_ENABLE_DEBUG_PINS */ diff --git a/flight/board_hw_defs/coptercontrol/board_hw_defs.c b/flight/board_hw_defs/coptercontrol/board_hw_defs.c index b5f81027f..328fd44ce 100644 --- a/flight/board_hw_defs/coptercontrol/board_hw_defs.c +++ b/flight/board_hw_defs/coptercontrol/board_hw_defs.c @@ -1,9 +1,41 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file board_hw_defs.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Defines board specific static initializers for hardware for the OpenPilot board. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include +#include + +#define BOARD_REVISION_CC 1 +#define BOARD_REVISION_CC3D 2 #if defined(PIOS_INCLUDE_LED) #include -static const struct pios_led pios_leds[] = { +static const struct pios_led pios_leds_cc[] = { [PIOS_LED_HEARTBEAT] = { .pin = { .gpio = GPIOA, @@ -16,17 +48,148 @@ static const struct pios_led pios_leds[] = { }, }; -static const struct pios_led_cfg pios_led_cfg = { - .leds = pios_leds, - .num_leds = NELEMENTS(pios_leds), +static const struct pios_led_cfg pios_led_cfg_cc = { + .leds = pios_leds_cc, + .num_leds = NELEMENTS(pios_leds_cc), }; +static const struct pios_led pios_leds_cc3d[] = { + [PIOS_LED_HEARTBEAT] = { + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Mode = GPIO_Mode_Out_PP, + .GPIO_Speed = GPIO_Speed_50MHz, + }, + }, + .remap = GPIO_Remap_SWJ_JTAGDisable, + }, +}; + +static const struct pios_led_cfg pios_led_cfg_cc3d = { + .leds = pios_leds_cc3d, + .num_leds = NELEMENTS(pios_leds_cc3d), +}; + +const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revision) +{ + switch (board_revision) { + case BOARD_REVISION_CC: return &pios_led_cfg_cc; + case BOARD_REVISION_CC3D: return &pios_led_cfg_cc3d; + default: return NULL; + } +} + #endif /* PIOS_INCLUDE_LED */ #if defined(PIOS_INCLUDE_SPI) #include +/* Gyro interface */ +void PIOS_SPI_gyro_irq_handler(void); +void DMA1_Channel2_IRQHandler() __attribute__ ((alias ("PIOS_SPI_gyro_irq_handler"))); +void DMA1_Channel3_IRQHandler() __attribute__ ((alias ("PIOS_SPI_gyro_irq_handler"))); +static const struct pios_spi_cfg pios_spi_gyro_cfg = { + .regs = SPI1, + .init = { + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16, /* 10 Mhz */ + }, + .use_crc = false, + .dma = { + .ahb_clk = RCC_AHBPeriph_DMA1, + + .irq = { + .flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2), + .init = { + .NVIC_IRQChannel = DMA1_Channel2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA1_Channel2, + .init = { + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), + .DMA_DIR = DMA_DIR_PeripheralSRC, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + .DMA_M2M = DMA_M2M_Disable, + }, + }, + .tx = { + .channel = DMA1_Channel3, + .init = { + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), + .DMA_DIR = DMA_DIR_PeripheralDST, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + .DMA_M2M = DMA_M2M_Disable, + }, + }, + }, + .sclk = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, + .miso = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .mosi = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, + .slave_count = 1, + .ssel = {{ + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_Out_PP, + }, + }}, +}; + +static uint32_t pios_spi_gyro_id; +void PIOS_SPI_gyro_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_gyro_id); +} + + /* Flash/Accel Interface * * NOTE: Leave this declared as const data so that it ends up in the @@ -35,109 +198,213 @@ static const struct pios_led_cfg pios_led_cfg = { void PIOS_SPI_flash_accel_irq_handler(void); void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_flash_accel_irq_handler"))); void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_flash_accel_irq_handler"))); -static const struct pios_spi_cfg pios_spi_flash_accel_cfg = { - .regs = SPI2, - .init = { - .SPI_Mode = SPI_Mode_Master, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Soft, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, - }, - .use_crc = FALSE, - .dma = { - .ahb_clk = RCC_AHBPeriph_DMA1, - - .irq = { - .flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4), - .init = { - .NVIC_IRQChannel = DMA1_Channel4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, +static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc3d = { + .regs = SPI2, + .init = { + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8, + }, + .use_crc = false, + .dma = { + .ahb_clk = RCC_AHBPeriph_DMA1, + + .irq = { + .flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4), + .init = { + .NVIC_IRQChannel = DMA1_Channel4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA1_Channel4, + .init = { + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR), + .DMA_DIR = DMA_DIR_PeripheralSRC, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_High, + .DMA_M2M = DMA_M2M_Disable, + }, + }, + .tx = { + .channel = DMA1_Channel5, + .init = { + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR), + .DMA_DIR = DMA_DIR_PeripheralDST, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_High, + .DMA_M2M = DMA_M2M_Disable, + }, + }, + }, + .sclk = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, + .miso = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .mosi = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, + .slave_count = 2, + .ssel = {{ + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_Out_PP, + }},{ + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_Out_PP, + }, + }}, +}; - .rx = { - .channel = DMA1_Channel4, - .init = { - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR), - .DMA_DIR = DMA_DIR_PeripheralSRC, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_High, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - .tx = { - .channel = DMA1_Channel5, - .init = { - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR), - .DMA_DIR = DMA_DIR_PeripheralDST, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_High, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - }, - .ssel = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - .sclk = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_13, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, - .miso = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_14, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, - .mosi = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, +static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc = { + .regs = SPI2, + .init = { + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8, + }, + .use_crc = false, + .dma = { + .ahb_clk = RCC_AHBPeriph_DMA1, + + .irq = { + .flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4), + .init = { + .NVIC_IRQChannel = DMA1_Channel4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA1_Channel4, + .init = { + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR), + .DMA_DIR = DMA_DIR_PeripheralSRC, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_High, + .DMA_M2M = DMA_M2M_Disable, + }, + }, + .tx = { + .channel = DMA1_Channel5, + .init = { + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR), + .DMA_DIR = DMA_DIR_PeripheralDST, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_High, + .DMA_M2M = DMA_M2M_Disable, + }, + }, + }, + .sclk = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, + .miso = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .mosi = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, + .slave_count = 2, + .ssel = {{ + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_Out_PP, + }},{ + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_Out_PP, + }, + }}, }; static uint32_t pios_spi_flash_accel_id; void PIOS_SPI_flash_accel_irq_handler(void) { - /* Call into the generic code to handle the IRQ for this specific device */ + /* Call into the generic code to handle the IRQ for this specific device */ PIOS_SPI_IRQ_Handler(pios_spi_flash_accel_id); } #endif /* PIOS_INCLUDE_SPI */ -#if defined(PIOS_INCLUDE_ADC) /* * ADC system */ +#if defined(PIOS_INCLUDE_ADC) #include "pios_adc_priv.h" extern void PIOS_ADC_handler(void); void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler"))); @@ -173,22 +440,10 @@ static const struct pios_adc_cfg pios_adc_cfg = { .full_flag = DMA1_IT_TC1, }; -struct pios_adc_dev pios_adc_devs[] = { - { - .cfg = &pios_adc_cfg, - .callback_function = NULL, - }, -}; - -uint8_t pios_adc_num_devices = NELEMENTS(pios_adc_devs); - void PIOS_ADC_handler() { PIOS_ADC_DMA_Handler(); } - -#endif /* PIOS_INCLUDE_ADC */ - -#if defined(PIOS_INCLUDE_TIM) +#endif #include "pios_tim_priv.h" @@ -479,7 +734,7 @@ static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = { }, }, }, - + // Receiver port pins // S3-S6 inputs are used as outputs in this case { @@ -531,83 +786,80 @@ static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = { }, }, }; - -#endif /* PIOS_INCLUDE_TIM */ - #if defined(PIOS_INCLUDE_USART) #include "pios_usart_priv.h" static const struct pios_usart_cfg pios_usart_generic_main_cfg = { - .regs = USART1, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, + .regs = USART1, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART1_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, }; static const struct pios_usart_cfg pios_usart_generic_flexi_cfg = { - .regs = USART3, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART3_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, + .regs = USART3, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, }; #if defined(PIOS_INCLUDE_DSM) @@ -632,7 +884,7 @@ static const struct pios_usart_cfg pios_usart_dsm_main_cfg = { .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, - }, + }, }, .rx = { .gpio = GPIOA, @@ -679,7 +931,7 @@ static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = { .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, - }, + }, }, .rx = { .gpio = GPIOB, @@ -712,6 +964,7 @@ static const struct pios_dsm_cfg pios_dsm_flexi_cfg = { #endif /* PIOS_INCLUDE_DSM */ + #if defined(PIOS_INCLUDE_SBUS) /* * S.Bus USART @@ -970,15 +1223,42 @@ void PIOS_I2C_flexi_adapter_er_irq_handler(void) #if defined(PIOS_INCLUDE_USB) #include "pios_usb_priv.h" -static const struct pios_usb_cfg pios_usb_main_cfg = { - .irq = { - .init = { - .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, +static const struct pios_usb_cfg pios_usb_main_cfg_cc = { + .irq = { + .init = { + .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .vsense = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_OD, + }, + } +}; + +static const struct pios_usb_cfg pios_usb_main_cfg_cc3d = { + .irq = { + .init = { + .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .vsense = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_OD, + }, + } }; #include "pios_usb_board_data_priv.h" @@ -997,20 +1277,21 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { #include const struct pios_usb_hid_cfg pios_usb_hid_cfg = { - .data_if = 0, + .data_if = 2, .data_rx_ep = 1, .data_tx_ep = 1, }; + #endif /* PIOS_INCLUDE_USB_HID */ #if defined(PIOS_INCLUDE_USB_CDC) #include const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = { - .ctrl_if = 1, + .ctrl_if = 0, .ctrl_tx_ep = 2, - .data_if = 2, + .data_if = 1, .data_rx_ep = 3, .data_tx_ep = 3, }; diff --git a/flight/board_hw_defs/ins/board_hw_defs.c b/flight/board_hw_defs/ins/board_hw_defs.c deleted file mode 100644 index b1b5a166c..000000000 --- a/flight/board_hw_defs/ins/board_hw_defs.c +++ /dev/null @@ -1,496 +0,0 @@ -#include - -#if defined(PIOS_INCLUDE_LED) - -#include -static const struct pios_led pios_leds[] = { - [PIOS_LED_HEARTBEAT] = { - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Mode = GPIO_Mode_Out_PP, - .GPIO_Speed = GPIO_Speed_50MHz, - }, - }, - }, - [PIOS_LED_ALARM] = { - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_2, - .GPIO_Mode = GPIO_Mode_Out_PP, - .GPIO_Speed = GPIO_Speed_50MHz, - }, - }, - }, -}; - -static const struct pios_led_cfg pios_led_cfg = { - .leds = pios_leds, - .num_leds = NELEMENTS(pios_leds), -}; - -#endif /* PIOS_INCLUDE_LED */ - -#if defined(PIOS_INCLUDE_SPI) - -#include - -/* SPI2 Interface - * - Used for mainboard communications and magnetometer - * - * NOTE: Leave this declared as const data so that it ends up in the - * .rodata section (ie. Flash) rather than in the .bss section (RAM). - */ -void PIOS_SPI_op_mag_irq_handler(void); -void DMA1_Channel5_IRQHandler() __attribute__ ((alias("PIOS_SPI_op_mag_irq_handler"))); -void DMA1_Channel4_IRQHandler() __attribute__ ((alias("PIOS_SPI_op_mag_irq_handler"))); -static const struct pios_spi_cfg pios_spi_op_mag_cfg = { - .regs = SPI2, - .init = { - .SPI_Mode = SPI_Mode_Slave, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Hard, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_2Edge, - }, - .use_crc = TRUE, - .dma = { - .ahb_clk = RCC_AHBPeriph_DMA1, - - .irq = { - .flags = - (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | - DMA1_FLAG_GL4), - .init = { - .NVIC_IRQChannel = DMA1_Channel4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA1_Channel4, - .init = { - .DMA_PeripheralBaseAddr = - (uint32_t) & (SPI2->DR), - .DMA_DIR = DMA_DIR_PeripheralSRC, - .DMA_PeripheralInc = - DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = - DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = - DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - .tx = { - .channel = DMA1_Channel5, - .init = { - .DMA_PeripheralBaseAddr = - (uint32_t) & (SPI2->DR), - .DMA_DIR = DMA_DIR_PeripheralDST, - .DMA_PeripheralInc = - DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = - DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = - DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - }, - .ssel = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, - .sclk = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_13, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, - .miso = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_14, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, - .mosi = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, -}; - -uint32_t pios_spi_op_mag_id; -void PIOS_SPI_op_mag_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_op_mag_id); -} - -/* SPI1 Interface - * - Used for BMA180 accelerometer - */ -void PIOS_SPI_accel_irq_handler(void); -void DMA1_Channel2_IRQHandler() __attribute__ ((alias("PIOS_SPI_accel_irq_handler"))); -void DMA1_Channel3_IRQHandler() __attribute__ ((alias("PIOS_SPI_accel_irq_handler"))); -static const struct pios_spi_cfg pios_spi_accel_cfg = { - .regs = SPI1, - .init = { - .SPI_Mode = SPI_Mode_Master, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Soft, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_1Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, - }, - .use_crc = FALSE, - .dma = { - .ahb_clk = RCC_AHBPeriph_DMA1, - - .irq = { - .flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2), - .init = { - .NVIC_IRQChannel = DMA1_Channel2_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA1_Channel2, - .init = { - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), - .DMA_DIR = DMA_DIR_PeripheralSRC, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - .tx = { - .channel = DMA1_Channel3, - .init = { - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), - .DMA_DIR = DMA_DIR_PeripheralDST, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_High, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - }, - .ssel = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_4, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - .sclk = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, - .miso = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, - .mosi = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, -}; - -static uint32_t pios_spi_accel_id; -void PIOS_SPI_accel_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_accel_id); -} - -#endif /* PIOS_INCLUDE_SPI */ - -#if defined(PIOS_INCLUDE_GPS) -#include - -/* - * GPS USART - */ -static const struct pios_usart_cfg pios_usart_gps_cfg = { - .regs = USART1, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, -}; - -#endif /* PIOS_INCLUDE_GPS */ - -#ifdef PIOS_COM_AUX -/* - * AUX USART - */ -static const struct pios_usart_cfg pios_usart_aux_cfg = { - .regs = USART4, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, -}; - -#endif /* PIOS_COM_AUX */ - - -#if defined(PIOS_INCLUDE_COM) - -#include - -#endif /* PIOS_INCLUDE_COM */ - -#if defined(PIOS_INCLUDE_I2C) - -#include - -/* - * I2C Adapters - */ - -void PIOS_I2C_pres_mag_adapter_ev_irq_handler(void); -void PIOS_I2C_pres_mag_adapter_er_irq_handler(void); -void I2C1_EV_IRQHandler() - __attribute__ ((alias("PIOS_I2C_pres_mag_adapter_ev_irq_handler"))); -void I2C1_ER_IRQHandler() - __attribute__ ((alias("PIOS_I2C_pres_mag_adapter_er_irq_handler"))); - -static const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = { - .regs = I2C1, - .init = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_OwnAddress1 = 0, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 200000, /* bits/s */ - }, - .transfer_timeout_ms = 50, - .scl = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_OD, - }, - }, - .sda = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_OD, - }, - }, - .event = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C1_EV_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .error = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C1_ER_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -uint32_t pios_i2c_pres_mag_adapter_id; -void PIOS_I2C_pres_mag_adapter_ev_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_pres_mag_adapter_id); -} - -void PIOS_I2C_pres_mag_adapter_er_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_pres_mag_adapter_id); -} - - -void PIOS_I2C_gyro_adapter_ev_irq_handler(void); -void PIOS_I2C_gyro_adapter_er_irq_handler(void); -void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_gyro_adapter_ev_irq_handler"))); -void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_gyro_adapter_er_irq_handler"))); - -static const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = { - .regs = I2C2, - .init = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_OwnAddress1 = 0, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 400000, /* bits/s */ - }, - .transfer_timeout_ms = 50, - .scl = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_OD, - }, - }, - .sda = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_OD, - }, - }, - .event = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C2_EV_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .error = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C2_ER_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -uint32_t pios_i2c_gyro_adapter_id; -void PIOS_I2C_gyro_adapter_ev_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_gyro_adapter_id); -} - -void PIOS_I2C_gyro_adapter_er_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_gyro_adapter_id); -} - -#endif /* PIOS_INCLUDE_I2C */ diff --git a/flight/board_hw_defs/openpilot/board_hw_defs.c b/flight/board_hw_defs/openpilot/board_hw_defs.c deleted file mode 100644 index 681089d09..000000000 --- a/flight/board_hw_defs/openpilot/board_hw_defs.c +++ /dev/null @@ -1,1085 +0,0 @@ -#include - -#if defined(PIOS_INCLUDE_LED) - -#include -static const struct pios_led pios_leds[] = { - [PIOS_LED_HEARTBEAT] = { - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Mode = GPIO_Mode_Out_PP, - .GPIO_Speed = GPIO_Speed_50MHz, - }, - }, - }, - [PIOS_LED_ALARM] = { - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_13, - .GPIO_Mode = GPIO_Mode_Out_PP, - .GPIO_Speed = GPIO_Speed_50MHz, - }, - }, - }, -}; - -static const struct pios_led_cfg pios_led_cfg = { - .leds = pios_leds, - .num_leds = NELEMENTS(pios_leds), -}; - -#endif /* PIOS_INCLUDE_LED */ - -#if defined(PIOS_INCLUDE_SPI) - -#include - -/* MicroSD Interface - * - * NOTE: Leave this declared as const data so that it ends up in the - * .rodata section (ie. Flash) rather than in the .bss section (RAM). - */ -void PIOS_SPI_sdcard_irq_handler(void); -void DMA1_Channel2_IRQHandler() __attribute__ ((alias ("PIOS_SPI_sdcard_irq_handler"))); -void DMA1_Channel3_IRQHandler() __attribute__ ((alias ("PIOS_SPI_sdcard_irq_handler"))); -static const struct pios_spi_cfg pios_spi_sdcard_cfg = { - .regs = SPI1, - .init = { - .SPI_Mode = SPI_Mode_Master, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Soft, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256, /* Maximum divider (ie. slowest clock rate) */ - }, - .dma = { - .ahb_clk = RCC_AHBPeriph_DMA1, - - .irq = { - .flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2), - .init = { - .NVIC_IRQChannel = DMA1_Channel2_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA1_Channel2, - .init = { - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), - .DMA_DIR = DMA_DIR_PeripheralSRC, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - .tx = { - .channel = DMA1_Channel3, - .init = { - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), - .DMA_DIR = DMA_DIR_PeripheralDST, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - }, - .ssel = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_4, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - .sclk = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, - .miso = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .mosi = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, -}; - -/* AHRS Interface - * - * NOTE: Leave this declared as const data so that it ends up in the - * .rodata section (ie. Flash) rather than in the .bss section (RAM). - */ -void PIOS_SPI_ahrs_irq_handler(void); -void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_ahrs_irq_handler"))); -void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_ahrs_irq_handler"))); -static const struct pios_spi_cfg pios_spi_ahrs_cfg = { - .regs = SPI2, - .init = { - .SPI_Mode = SPI_Mode_Master, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Soft, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16, - }, - .use_crc = TRUE, - .dma = { - .ahb_clk = RCC_AHBPeriph_DMA1, - - .irq = { - .flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4), - .init = { - .NVIC_IRQChannel = DMA1_Channel4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA1_Channel4, - .init = { - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR), - .DMA_DIR = DMA_DIR_PeripheralSRC, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_High, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - .tx = { - .channel = DMA1_Channel5, - .init = { - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR), - .DMA_DIR = DMA_DIR_PeripheralDST, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_High, - .DMA_M2M = DMA_M2M_Disable, - }, - }, - }, - .ssel = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - .sclk = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_13, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, - .miso = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_14, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, - .mosi = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, -}; - -static uint32_t pios_spi_sdcard_id; -void PIOS_SPI_sdcard_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_sdcard_id); -} - -uint32_t pios_spi_ahrs_id; -void PIOS_SPI_ahrs_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_ahrs_id); -} - -#endif /* PIOS_INCLUDE_SPI */ - -#if defined(PIOS_INCLUDE_ADC) - -/* - * ADC system - */ -#include "pios_adc_priv.h" -extern void PIOS_ADC_handler(void); -void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler"))); -// Remap the ADC DMA handler to this one -static const struct pios_adc_cfg pios_adc_cfg = { - .dma = { - .ahb_clk = RCC_AHBPeriph_DMA1, - .irq = { - .flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1), - .init = { - .NVIC_IRQChannel = DMA1_Channel1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .channel = DMA1_Channel1, - .init = { - .DMA_PeripheralBaseAddr = (uint32_t) & ADC1->DR, - .DMA_DIR = DMA_DIR_PeripheralSRC, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Word, - .DMA_Mode = DMA_Mode_Circular, - .DMA_Priority = DMA_Priority_Low, - .DMA_M2M = DMA_M2M_Disable, - }, - } - }, - .half_flag = DMA1_IT_HT1, - .full_flag = DMA1_IT_TC1, -}; - -struct pios_adc_dev pios_adc_devs[] = { - { - .cfg = &pios_adc_cfg, - .callback_function = NULL, - }, -}; - -uint8_t pios_adc_num_devices = NELEMENTS(pios_adc_devs); - -void PIOS_ADC_handler() { - PIOS_ADC_DMA_Handler(); -} - -#endif /* PIOS_INCLUDE_ADC */ - -#if defined(PIOS_INCLUDE_TIM) - -#include "pios_tim_priv.h" - -static const TIM_TimeBaseInitTypeDef tim_4_8_time_base = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), - .TIM_RepetitionCounter = 0x0000, -}; - -static const struct pios_tim_clock_cfg tim_4_cfg = { - .timer = TIM4, - .time_base_init = &tim_4_8_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -static const struct pios_tim_clock_cfg tim_8_cfg = { - .timer = TIM8, - .time_base_init = &tim_4_8_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM8_CC_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -static const TIM_TimeBaseInitTypeDef tim_1_3_5_time_base = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, -}; - -static const struct pios_tim_clock_cfg tim_1_cfg = { - .timer = TIM1, - .time_base_init = &tim_1_3_5_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM1_CC_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -static const struct pios_tim_clock_cfg tim_3_cfg = { - .timer = TIM3, - .time_base_init = &tim_1_3_5_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM3_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -static const struct pios_tim_clock_cfg tim_5_cfg = { - .timer = TIM5, - .time_base_init = &tim_1_3_5_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM5_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -#endif /* PIOS_INCLUDE_TIM */ - -#if defined(PIOS_INCLUDE_USART) - -#include "pios_usart_priv.h" - -/* - * Telemetry USART - */ -static const struct pios_usart_cfg pios_usart_telem_cfg = { - .regs = USART2, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART2_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_2, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, -}; - -/* - * GPS USART - */ -static const struct pios_usart_cfg pios_usart_gps_cfg = { - .regs = USART3, - .remap = GPIO_PartialRemap_USART3, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART3_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, -}; - -#ifdef PIOS_COM_AUX -/* - * AUX USART - */ -static const struct pios_usart_cfg pios_usart_aux_cfg = { - .regs = USART1, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .remap = GPIO_Remap_USART1, - .rx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, -}; -#endif - -#if defined(PIOS_INCLUDE_RTC) -/* - * Realtime Clock (RTC) - */ -#include - -void PIOS_RTC_IRQ_Handler (void); -void RTC_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler"))); -static const struct pios_rtc_cfg pios_rtc_main_cfg = { - .clksrc = RCC_RTCCLKSource_HSE_Div128, - .prescaler = 100, - .irq = { - .init = { - .NVIC_IRQChannel = RTC_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -void PIOS_RTC_IRQ_Handler (void) -{ - PIOS_RTC_irq_handler (); -} - -#endif - -#if defined(PIOS_INCLUDE_DSM) -/* - * Spektrum/JR DSM USART - */ -#include - -static const struct pios_usart_cfg pios_usart_dsm_cfg = { - .regs = USART1, - .init = { - .USART_BaudRate = 115200, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, -}; - -static const struct pios_dsm_cfg pios_dsm_cfg = { - .bind = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, -}; - -#endif /* PIOS_COM_DSM */ - -#if defined(PIOS_INCLUDE_SBUS) -#error PIOS_INCLUDE_SBUS not implemented -#endif /* PIOS_INCLUDE_SBUS */ - -#endif /* PIOS_INCLUDE_USART */ - -#if defined(PIOS_INCLUDE_COM) - -#include "pios_com_priv.h" - -#endif /* PIOS_INCLUDE_COM */ - -#if defined(PIOS_INCLUDE_SERVO) && defined(PIOS_INCLUDE_TIM) - -/** - * Pios servo configuration structures - */ -#include -static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { - { - .timer = TIM4, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM4, - .timer_chan = TIM_Channel_2, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM4, - .timer_chan = TIM_Channel_3, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM4, - .timer_chan = TIM_Channel_4, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM8, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM8, - .timer_chan = TIM_Channel_2, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM8, - .timer_chan = TIM_Channel_3, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM8, - .timer_chan = TIM_Channel_4, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, -}; - -const struct pios_servo_cfg pios_servo_cfg = { - .tim_oc_init = { - .TIM_OCMode = TIM_OCMode_PWM1, - .TIM_OutputState = TIM_OutputState_Enable, - .TIM_OutputNState = TIM_OutputNState_Disable, - .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, - .TIM_OCPolarity = TIM_OCPolarity_High, - .TIM_OCNPolarity = TIM_OCPolarity_High, - .TIM_OCIdleState = TIM_OCIdleState_Reset, - .TIM_OCNIdleState = TIM_OCNIdleState_Reset, - }, - .channels = pios_tim_servoport_all_pins, - .num_channels = NELEMENTS(pios_tim_servoport_all_pins), -}; - -#endif /* PIOS_INCLUDE_SERVO && PIOS_INCLUDE_TIM */ - -/* - * PWM Inputs - */ -#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) -#include -static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { - { - .timer = TIM1, - .timer_chan = TIM_Channel_2, - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM1, - .timer_chan = TIM_Channel_3, - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM5, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_0, - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM1, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM3, - .timer_chan = TIM_Channel_4, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_1, - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM3, - .timer_chan = TIM_Channel_3, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_0, - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - }, - { - .timer = TIM3, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_4, - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - .remap = GPIO_PartialRemap_TIM3, - }, - { - .timer = TIM3, - .timer_chan = TIM_Channel_2, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - .remap = GPIO_PartialRemap_TIM3, - }, -}; - -const struct pios_pwm_cfg pios_pwm_cfg = { - .tim_ic_init = { - .TIM_ICPolarity = TIM_ICPolarity_Rising, - .TIM_ICSelection = TIM_ICSelection_DirectTI, - .TIM_ICPrescaler = TIM_ICPSC_DIV1, - .TIM_ICFilter = 0x0, - }, - .channels = pios_tim_rcvrport_all_channels, - .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels), -}; -#endif - -/* - * PPM Input - */ -#if defined(PIOS_INCLUDE_PPM) -#include -static const struct pios_ppm_cfg pios_ppm_cfg = { - .tim_ic_init = { - .TIM_ICPolarity = TIM_ICPolarity_Rising, - .TIM_ICSelection = TIM_ICSelection_DirectTI, - .TIM_ICPrescaler = TIM_ICPSC_DIV1, - .TIM_ICFilter = 0x0, - .TIM_Channel = TIM_Channel_2, - }, - /* Use only the first channel for ppm */ - .channels = &pios_tim_rcvrport_all_channels[0], - .num_channels = 1, -}; - -#endif //PPM - -#if defined(PIOS_INCLUDE_I2C) - -#include - -/* - * I2C Adapters - */ - -void PIOS_I2C_main_adapter_ev_irq_handler(void); -void PIOS_I2C_main_adapter_er_irq_handler(void); -void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_main_adapter_ev_irq_handler"))); -void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_main_adapter_er_irq_handler"))); - -static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = { - .regs = I2C2, - .init = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_OwnAddress1 = 0, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 400000, /* bits/s */ - }, - .transfer_timeout_ms = 50, - .scl = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_OD, - }, - }, - .sda = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_10MHz, - .GPIO_Mode = GPIO_Mode_AF_OD, - }, - }, - .event = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C2_EV_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .error = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C2_ER_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -uint32_t pios_i2c_main_adapter_id; -void PIOS_I2C_main_adapter_ev_irq_handler(void) -{ -#ifdef I2C_DEBUG_PIN - PIOS_DEBUG_PinHigh(I2C_DEBUG_PIN); -#endif - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_main_adapter_id); -#ifdef I2C_DEBUG_PIN - PIOS_DEBUG_PinLow(I2C_DEBUG_PIN); -#endif -} - -void PIOS_I2C_main_adapter_er_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_main_adapter_id); -} - -#endif /* PIOS_INCLUDE_I2C */ - -#if defined(PIOS_ENABLE_DEBUG_PINS) - -static const struct stm32_gpio pios_debug_pins[] = { - #define PIOS_DEBUG_PIN_SERVO_1 0 - { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - #define PIOS_DEBUG_PIN_SERVO_2 1 - { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - #define PIOS_DEBUG_PIN_SERVO_3 2 - { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - #define PIOS_DEBUG_PIN_SERVO_4 3 - { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - #define PIOS_DEBUG_PIN_SERVO_5 4 - { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - #define PIOS_DEBUG_PIN_SERVO_6 5 - { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - #define PIOS_DEBUG_PIN_SERVO_7 6 - { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, - #define PIOS_DEBUG_PIN_SERVO_8 7 - { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_Out_PP, - }, - }, -}; - -#endif /* PIOS_ENABLE_DEBUG_PINS */ - -#if defined(PIOS_INCLUDE_RCVR) -#include "pios_rcvr_priv.h" - -#endif /* PIOS_INCLUDE_RCVR */ - -#if defined(PIOS_INCLUDE_USB) -#include "pios_usb_priv.h" - -static const struct pios_usb_cfg pios_usb_main_cfg = { - .irq = { - .init = { - .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -#include "pios_usb_board_data_priv.h" -#include "pios_usb_desc_hid_cdc_priv.h" -#include "pios_usb_desc_hid_only_priv.h" -#endif /* PIOS_INCLUDE_USB */ - -#if defined(PIOS_INCLUDE_COM_MSG) - -#include - -#endif /* PIOS_INCLUDE_COM_MSG */ - -#if defined(PIOS_INCLUDE_USB_HID) -#include - -const struct pios_usb_hid_cfg pios_usb_hid_cfg = { - .data_if = 0, - .data_rx_ep = 1, - .data_tx_ep = 1, -}; - -#endif /* PIOS_INCLUDE_USB_HID */ - -#if defined(PIOS_INCLUDE_USB_CDC) -#include - -const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = { - .ctrl_if = 1, - .ctrl_tx_ep = 2, - - .data_if = 2, - .data_rx_ep = 3, - .data_tx_ep = 3, -}; -#endif /* PIOS_INCLUDE_USB_CDC */ diff --git a/flight/board_hw_defs/pipxtreme/board_hw_defs.c b/flight/board_hw_defs/pipxtreme/board_hw_defs.c index 8dc17d5ba..7df2c8132 100644 --- a/flight/board_hw_defs/pipxtreme/board_hw_defs.c +++ b/flight/board_hw_defs/pipxtreme/board_hw_defs.c @@ -1,4 +1,63 @@ #include +#include + +#if defined(PIOS_INCLUDE_LED) + +#include +static const struct pios_led pios_leds[] = { + [PIOS_LED_USB] = { + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Mode = GPIO_Mode_Out_PP, + .GPIO_Speed = GPIO_Speed_50MHz, + }, + }, + }, + [PIOS_LED_LINK] = { + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Mode = GPIO_Mode_Out_PP, + .GPIO_Speed = GPIO_Speed_50MHz, + }, + }, + }, + [PIOS_LED_RX] = { + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_Out_PP, + .GPIO_Speed = GPIO_Speed_50MHz, + }, + }, + }, + [PIOS_LED_TX] = { + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_Out_PP, + .GPIO_Speed = GPIO_Speed_50MHz, + }, + }, + }, +}; + +static const struct pios_led_cfg pios_led_cfg = { + .leds = pios_leds, + .num_leds = NELEMENTS(pios_leds), +}; + +const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revision) +{ + return &pios_led_cfg; +} + +#endif /* PIOS_INCLUDE_LED */ #if defined(PIOS_INCLUDE_SPI) @@ -74,9 +133,9 @@ static const struct pios_spi_cfg pios_spi_port_cfg = }, }, }, - + .slave_count = 1, .ssel = - { + {{ .gpio = GPIOA, .init = { @@ -84,7 +143,7 @@ static const struct pios_spi_cfg pios_spi_port_cfg = .GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Mode = GPIO_Mode_Out_PP, }, - }, + }}, .sclk = { .gpio = GPIOA, @@ -181,6 +240,86 @@ void PIOS_ADC_handler() { #endif /* PIOS_INCLUDE_ADC */ +#if defined(PIOS_INCLUDE_TIM) + +#include "pios_tim_priv.h" + +static const TIM_TimeBaseInitTypeDef tim_1_2_3_4_time_base = { + .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_1_cfg = { + .timer = TIM1, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_2_cfg = { + .timer = TIM2, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_3_cfg = { + .timer = TIM3, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_4_cfg = { + .timer = TIM4, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_channel pios_tim_ppm_flexi_port = { + .timer = TIM2, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap2_TIM2, +}; + +#endif /* PIOS_INCLUDE_TIM */ + #if defined(PIOS_INCLUDE_USART) #include @@ -232,6 +371,42 @@ static const struct pios_usart_cfg pios_usart_serial_cfg = }, }; +static const struct pios_usart_cfg pios_usart_telem_flexi_cfg = { + .regs = USART3, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, +}; + #endif /* PIOS_INCLUDE_USART */ #if defined(PIOS_INCLUDE_COM) @@ -240,34 +415,136 @@ static const struct pios_usart_cfg pios_usart_serial_cfg = #endif /* PIOS_INCLUDE_COM */ -// *********************************************************************************** +#if defined(PIOS_INCLUDE_RTC) +/* + * Realtime Clock (RTC) + */ +#include + +void PIOS_RTC_IRQ_Handler (void); +void RTC_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler"))); +static const struct pios_rtc_cfg pios_rtc_main_cfg = { + .clksrc = RCC_RTCCLKSource_HSE_Div128, + .prescaler = 100, + .irq = { + .init = { + .NVIC_IRQChannel = RTC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +void PIOS_RTC_IRQ_Handler (void) +{ + PIOS_RTC_irq_handler (); +} + +#endif + +/* + * PPM Inputs + */ +#if defined(PIOS_INCLUDE_PPM) +#include + +const struct pios_ppm_cfg pios_ppm_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + }, + .channels = &pios_tim_ppm_flexi_port, + .num_channels = 1, +}; + +#endif /* PIOS_INCLUDE_PPM */ + +#if defined(PIOS_INCLUDE_RCVR) +#include "pios_rcvr_priv.h" + +#endif /* PIOS_INCLUDE_RCVR */ #if defined(PIOS_INCLUDE_USB) #include "pios_usb_priv.h" static const struct pios_usb_cfg pios_usb_main_cfg = { - .irq = { - .init = { - .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, + .irq = { + .init = { + .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .vsense = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_OD, + }, + } }; #include "pios_usb_board_data_priv.h" +#include "pios_usb_desc_hid_cdc_priv.h" #include "pios_usb_desc_hid_only_priv.h" #endif /* PIOS_INCLUDE_USB */ +#if defined(PIOS_INCLUDE_COM_MSG) + +#include + +#endif /* PIOS_INCLUDE_COM_MSG */ + #if defined(PIOS_INCLUDE_USB_HID) #include const struct pios_usb_hid_cfg pios_usb_hid_cfg = { - .data_if = 0, + .data_if = 2, .data_rx_ep = 1, .data_tx_ep = 1, }; +#endif /* PIOS_INCLUDE_USB_HID */ -#endif /* PIOS_INCLUDE_USB_HID */ +#if defined(PIOS_INCLUDE_USB_CDC) +#include + +const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = { + .ctrl_if = 0, + .ctrl_tx_ep = 2, + + .data_if = 1, + .data_rx_ep = 3, + .data_tx_ep = 3, +}; +#endif /* PIOS_INCLUDE_USB_CDC */ + +#if defined(PIOS_INCLUDE_FLASH_EEPROM) +#include + +const struct pios_eeprom_cfg pios_eeprom_cfg = { + .base_address = PIOS_FLASH_EEPROM_ADDR, + .max_size = PIOS_FLASH_EEPROM_LEN, +}; +#endif /* PIOS_INCLUDE_FLASH_EEPROM */ + +#if defined(PIOS_INCLUDE_RFM22B) +#include + +#endif /* PIOS_INCLUDE_RFM22B */ + +#if defined(PIOS_INCLUDE_PACKET_HANDLER) +#include + +// Initialize the packet handler +PacketHandlerConfig pios_ph_cfg = { + .winSize = PIOS_PH_WIN_SIZE, + .maxConnections = PIOS_PH_MAX_CONNECTIONS, +}; + +#endif /* PIOS_INCLUDE_PACKET_HANDLER */ diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c new file mode 100644 index 000000000..70a9e0c45 --- /dev/null +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -0,0 +1,1813 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file board_hw_defs.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Defines board specific static initializers for hardware for the OpenPilot board. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include + +#if defined(PIOS_INCLUDE_LED) + +#include +static const struct pios_led pios_leds[] = { + [PIOS_LED_HEARTBEAT] = { + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + }, + [PIOS_LED_ALARM] = { + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + }, +}; + +static const struct pios_led_cfg pios_led_cfg = { + .leds = pios_leds, + .num_leds = NELEMENTS(pios_leds), +}; + +#endif /* PIOS_INCLUDE_LED */ + +#if defined(PIOS_INCLUDE_SPI) +#include +/* SPI1 Interface + * - Used for BMA180 accelerometer + */ +void PIOS_SPI_accel_irq_handler(void); +void DMA2_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_accel_irq_handler"))); +void DMA2_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_accel_irq_handler"))); +static const struct pios_spi_cfg pios_spi_accel_cfg = { + .regs = SPI1, + .remap = GPIO_AF_SPI1, + .init = { + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16, + }, + .use_crc = false, + .dma = { + .irq = { + .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), + .init = { + .NVIC_IRQChannel = DMA2_Stream0_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA2_Stream0, + .init = { + .DMA_Channel = DMA_Channel_3, + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), + .DMA_DIR = DMA_DIR_PeripheralToMemory, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + /* .DMA_FIFOThreshold */ + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + .tx = { + .channel = DMA2_Stream3, + .init = { + .DMA_Channel = DMA_Channel_3, + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), + .DMA_DIR = DMA_DIR_MemoryToPeripheral, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_High, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + /* .DMA_FIFOThreshold */ + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + }, + .sclk = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .miso = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .mosi = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .slave_count = 2, + .ssel = { { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + } }, + { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + } }, + } +}; + +static uint32_t pios_spi_accel_id; +void PIOS_SPI_accel_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_accel_id); +} + + +/* SPI2 Interface + * - Used for gyro communications + */ +void PIOS_SPI_GYRO_irq_handler(void); +void DMA1_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); +void DMA1_Stream4_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); +static const struct pios_spi_cfg pios_spi_gyro_cfg = { + .regs = SPI2, + .remap = GPIO_AF_SPI2, + .init = { + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8, + }, + .use_crc = false, + .dma = { + .irq = { + // Note this is the stream ID that triggers interrupts (in this case RX) + .flags = (DMA_IT_TCIF3 | DMA_IT_TEIF3 | DMA_IT_HTIF3), + .init = { + .NVIC_IRQChannel = DMA1_Stream3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA1_Stream3, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI2->DR), + .DMA_DIR = DMA_DIR_PeripheralToMemory, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + //TODO: Enable FIFO + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + .tx = { + .channel = DMA1_Stream4, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI2->DR), + .DMA_DIR = DMA_DIR_MemoryToPeripheral, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + }, + .sclk = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .miso = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .mosi = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .slave_count = 1, + .ssel = { { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + } }, +}; + +uint32_t pios_spi_gyro_id; +void PIOS_SPI_gyro_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_gyro_id); +} + + +#if !defined(PIOS_FLASH_ON_ACCEL) +/* SPI3 Interface + * - Used for flash communications + */ +void PIOS_SPI_flash_irq_handler(void); +void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_flash_irq_handler"))); +void DMA1_Stream5_IRQHandler(void) __attribute__((alias("PIOS_SPI_flash_irq_handler"))); +static const struct pios_spi_cfg pios_spi_flash_cfg = { + .regs = SPI3, + .remap = GPIO_AF_SPI3, + .init = { + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, + }, + .use_crc = false, + .dma = { + .irq = { + // Note this is the stream ID that triggers interrupts (in this case RX) + .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), + .init = { + .NVIC_IRQChannel = DMA1_Stream0_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA1_Stream0, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), + .DMA_DIR = DMA_DIR_PeripheralToMemory, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + //TODO: Enable FIFO + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + .tx = { + .channel = DMA1_Stream5, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), + .DMA_DIR = DMA_DIR_MemoryToPeripheral, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + }, + .sclk = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .miso = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .mosi = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .slave_count = 1, + .ssel = { { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + } }, +}; + +uint32_t pios_spi_flash_id; +void PIOS_SPI_flash_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_flash_id); +} +#endif /* PIOS_FLASH_ON_ACCEL */ + +#if defined(PIOS_OVERO_SPI) +/* SPI3 Interface + * - Used for flash communications + */ +void PIOS_SPI_overo_irq_handler(void); +void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_overo_irq_handler"))); +void DMA1_Stream7_IRQHandler(void) __attribute__((alias("PIOS_SPI_overo_irq_handler"))); +static const struct pios_spi_cfg pios_spi_overo_cfg = { + .regs = SPI3, + .remap = GPIO_AF_SPI3, + .init = { + .SPI_Mode = SPI_Mode_Slave, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Hard, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, + }, + .use_crc = false, + .dma = { + .irq = { + // Note this is the stream ID that triggers interrupts (in this case RX) + .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), + .init = { + .NVIC_IRQChannel = DMA1_Stream0_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA1_Stream0, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), + .DMA_DIR = DMA_DIR_PeripheralToMemory, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + //TODO: Enable FIFO + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + .tx = { + .channel = DMA1_Stream7, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), + .DMA_DIR = DMA_DIR_MemoryToPeripheral, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + }, + .sclk = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .miso = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .mosi = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .slave_count = 1, + .ssel = { { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + } }, +}; + +uint32_t pios_spi_overo_id; +void PIOS_SPI_overo_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_overo_id); +} +#else +uint32_t pios_spi_overo_id = 0; +#endif /* PIOS_OVERO_SPI */ + +#endif /* PIOS_INCLUDE_SPI */ + + + +#include + +#ifdef PIOS_INCLUDE_COM_TELEM +/* + * Telemetry on main USART + */ +static const struct pios_usart_cfg pios_usart_telem_cfg = { + .regs = USART2, + .remap = GPIO_AF_USART2, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = + USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_COM_TELEM */ + +#ifdef PIOS_INCLUDE_GPS +/* + * GPS USART + */ +static const struct pios_usart_cfg pios_usart_gps_cfg = { + .regs = USART1, + .remap = GPIO_AF_USART1, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = + USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART1_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_INCLUDE_GPS */ + +#ifdef PIOS_INCLUDE_COM_AUX +/* + * AUX USART (UART label on rev2) + */ +static const struct pios_usart_cfg pios_usart_aux_cfg = { + .regs = USART6, + .remap = GPIO_AF_USART6, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = + USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART6_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_COM_AUX */ + +#ifdef PIOS_INCLUDE_COM_AUXSBUS +/* + * AUX USART SBUS ( UART/ S Bus label on rev2) + */ +static const struct pios_usart_cfg pios_usart_auxsbus_cfg = { + .regs = UART4, + .remap = GPIO_AF_UART4, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = + USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = UART4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_INCLUDE_COM_AUXSBUS */ + +#ifdef PIOS_INCLUDE_COM_FLEXI +/* + * FLEXI PORT + */ +static const struct pios_usart_cfg pios_usart_flexi_cfg = { + .regs = USART3, + .remap = GPIO_AF_USART3, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = + USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_INCLUDE_COM_FLEXI */ + +#if defined(PIOS_INCLUDE_DSM) +/* + * Spektrum/JR DSM USART + */ +#include + +static const struct pios_usart_cfg pios_usart_dsm_aux_cfg = { + .regs = USART6, + .remap = GPIO_AF_USART6, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART6_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +static const struct pios_dsm_cfg pios_dsm_aux_cfg = { + .bind = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, +}; + +static const struct pios_usart_cfg pios_usart_dsm_auxsbus_cfg = { + .regs = UART4, + .remap = GPIO_AF_UART4, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = UART4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +static const struct pios_dsm_cfg pios_dsm_auxsbus_cfg = { + .bind = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, +}; + +static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = { + .regs = USART3, + .remap = GPIO_AF_USART3, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +static const struct pios_dsm_cfg pios_dsm_flexi_cfg = { + .bind = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, +}; + +#endif /* PIOS_INCLUDE_DSM */ + +#if defined(PIOS_INCLUDE_SBUS) +/* + * S.Bus USART + */ +#include + +static const struct pios_usart_cfg pios_usart_sbus_auxsbus_cfg = { + .regs = UART4, + .init = { + .USART_BaudRate = 100000, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_Even, + .USART_StopBits = USART_StopBits_2, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = UART4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, +}; + +static const struct pios_sbus_cfg pios_sbus_cfg = { + /* Inverter configuration */ + .inv = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .gpio_clk_func = RCC_AHB1PeriphClockCmd, + .gpio_clk_periph = RCC_AHB1Periph_GPIOB, + .gpio_inv_enable = Bit_SET, +}; + +#endif /* PIOS_INCLUDE_SBUS */ + +#if defined(PIOS_INCLUDE_COM) + +#include + +#endif /* PIOS_INCLUDE_COM */ + +#if defined(PIOS_INCLUDE_I2C) + +#include + +/* + * I2C Adapters + */ +void PIOS_I2C_mag_adapter_ev_irq_handler(void); +void PIOS_I2C_mag_adapter_er_irq_handler(void); +void I2C1_EV_IRQHandler() +__attribute__ ((alias("PIOS_I2C_mag_adapter_ev_irq_handler"))); +void I2C1_ER_IRQHandler() +__attribute__ ((alias("PIOS_I2C_mag_adapter_er_irq_handler"))); + +static const struct pios_i2c_adapter_cfg pios_i2c_mag_adapter_cfg = { + .regs = I2C1, + .remap = GPIO_AF_I2C1, + .init = { + .I2C_Mode = I2C_Mode_I2C, + .I2C_OwnAddress1 = 0, + .I2C_Ack = I2C_Ack_Enable, + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, + .I2C_DutyCycle = I2C_DutyCycle_2, + .I2C_ClockSpeed = 400000, /* bits/s */ + }, + .transfer_timeout_ms = 50, + .scl = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .sda = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .event = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C1_EV_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .error = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C1_ER_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +uint32_t pios_i2c_mag_adapter_id; +void PIOS_I2C_mag_adapter_ev_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_EV_IRQ_Handler(pios_i2c_mag_adapter_id); +} + +void PIOS_I2C_mag_adapter_er_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_ER_IRQ_Handler(pios_i2c_mag_adapter_id); +} + + +void PIOS_I2C_flexiport_adapter_ev_irq_handler(void); +void PIOS_I2C_flexiport_adapter_er_irq_handler(void); +void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_flexiport_adapter_ev_irq_handler"))); +void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_flexiport_adapter_er_irq_handler"))); + +static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = { + .regs = I2C2, + .remap = GPIO_AF_I2C2, + .init = { + .I2C_Mode = I2C_Mode_I2C, + .I2C_OwnAddress1 = 0, + .I2C_Ack = I2C_Ack_Enable, + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, + .I2C_DutyCycle = I2C_DutyCycle_2, + .I2C_ClockSpeed = 400000, /* bits/s */ + }, + .transfer_timeout_ms = 50, + .scl = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .sda = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .event = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C2_EV_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .error = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C2_ER_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +uint32_t pios_i2c_flexiport_adapter_id; +void PIOS_I2C_flexiport_adapter_ev_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_EV_IRQ_Handler(pios_i2c_flexiport_adapter_id); +} + +void PIOS_I2C_flexiport_adapter_er_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_ER_IRQ_Handler(pios_i2c_flexiport_adapter_id); +} + + +void PIOS_I2C_pressure_adapter_ev_irq_handler(void); +void PIOS_I2C_pressure_adapter_er_irq_handler(void); +void I2C3_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_pressure_adapter_ev_irq_handler"))); +void I2C3_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_pressure_adapter_er_irq_handler"))); + +static const struct pios_i2c_adapter_cfg pios_i2c_pressure_adapter_cfg = { + .regs = I2C3, + .remap = GPIO_AF_I2C3, + .init = { + .I2C_Mode = I2C_Mode_I2C, + .I2C_OwnAddress1 = 0, + .I2C_Ack = I2C_Ack_Enable, + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, + .I2C_DutyCycle = I2C_DutyCycle_2, + .I2C_ClockSpeed = 40000, /* bits/s */ + }, + .transfer_timeout_ms = 50, + .scl = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .sda = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .event = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C3_EV_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .error = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C3_ER_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +uint32_t pios_i2c_pressure_adapter_id; +void PIOS_I2C_pressure_adapter_ev_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_EV_IRQ_Handler(pios_i2c_pressure_adapter_id); +} + +void PIOS_I2C_pressure_adapter_er_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_ER_IRQ_Handler(pios_i2c_pressure_adapter_id); +} +#endif /* PIOS_INCLUDE_I2C */ + +#if defined(PIOS_INCLUDE_RTC) +/* + * Realtime Clock (RTC) + */ +#include + +void PIOS_RTC_IRQ_Handler (void); +void RTC_WKUP_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler"))); +static const struct pios_rtc_cfg pios_rtc_main_cfg = { + .clksrc = RCC_RTCCLKSource_HSE_Div16, // Divide 8 Mhz crystal down to 1 + // For some reason it's acting like crystal is 16 Mhz. This clock is then divided + // by another 16 to give a nominal 62.5 khz clock + .prescaler = 100, // Every 100 cycles gives 625 Hz + .irq = { + .init = { + .NVIC_IRQChannel = RTC_WKUP_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +void PIOS_RTC_IRQ_Handler (void) +{ + PIOS_RTC_irq_handler (); +} + +#endif + +#include "pios_tim_priv.h" + +static const TIM_TimeBaseInitTypeDef tim_3_5_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_RepetitionCounter = 0x0000, +}; +static const TIM_TimeBaseInitTypeDef tim_9_10_11_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_3_cfg = { + .timer = TIM3, + .time_base_init = &tim_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_5_cfg = { + .timer = TIM5, + .time_base_init = &tim_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_9_cfg = { + .timer = TIM9, + .time_base_init = &tim_9_10_11_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_BRK_TIM9_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_10_cfg = { + .timer = TIM10, + .time_base_init = &tim_9_10_11_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_UP_TIM10_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_11_cfg = { + .timer = TIM11, + .time_base_init = &tim_9_10_11_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_TRG_COM_TIM11_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +// Set up timers that only have inputs on APB2 +static const TIM_TimeBaseInitTypeDef tim_1_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = 0xFFFF, + .TIM_RepetitionCounter = 0x0000, +}; +// Set up timers that only have inputs on APB2 +static const TIM_TimeBaseInitTypeDef tim_4_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = 0xFFFF, + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_1_cfg = { + .timer = TIM1, + .time_base_init = &tim_1_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_4_cfg = { + .timer = TIM4, + .time_base_init = &tim_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +/** + * Pios servo configuration structures + */ +#include +static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { + { + .timer = TIM9, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource5, + }, + .remap = GPIO_AF_TIM9, + }, + { + .timer = TIM9, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource6, + }, + .remap = GPIO_AF_TIM9, + }, + { + .timer = TIM11, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource9, + }, + .remap = GPIO_AF_TIM11, + }, + { + .timer = TIM10, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource8, + }, + .remap = GPIO_AF_TIM10, + }, + { + .timer = TIM5, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource2, + }, + .remap = GPIO_AF_TIM5, + }, + { + .timer = TIM5, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource3, + }, + .remap = GPIO_AF_TIM5, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource0, + }, + .remap = GPIO_AF_TIM3, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource1, + }, + .remap = GPIO_AF_TIM3, + }, +}; + +const struct pios_servo_cfg pios_servo_cfg = { + .tim_oc_init = { + .TIM_OCMode = TIM_OCMode_PWM1, + .TIM_OutputState = TIM_OutputState_Enable, + .TIM_OutputNState = TIM_OutputNState_Disable, + .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, + .TIM_OCPolarity = TIM_OCPolarity_High, + .TIM_OCNPolarity = TIM_OCPolarity_High, + .TIM_OCIdleState = TIM_OCIdleState_Reset, + .TIM_OCNIdleState = TIM_OCNIdleState_Reset, + }, + .channels = pios_tim_servoport_all_pins, + .num_channels = NELEMENTS(pios_tim_servoport_all_pins), +}; + + +/* + * PWM Inputs + */ +#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) +#include +static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { + { + .timer = TIM4, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource15, + }, + .remap = GPIO_AF_TIM4, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource14, + }, + .remap = GPIO_AF_TIM4, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource13, + }, + .remap = GPIO_AF_TIM4, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource12, + }, + .remap = GPIO_AF_TIM4, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource14, + }, + .remap = GPIO_AF_TIM1, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource13, + }, + .remap = GPIO_AF_TIM1, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource11, + }, + .remap = GPIO_AF_TIM1, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource9, + }, + .remap = GPIO_AF_TIM1, + }, +}; + +const struct pios_pwm_cfg pios_pwm_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + }, + .channels = pios_tim_rcvrport_all_channels, + .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels), +}; +#endif + +/* + * PPM Input + */ +#if defined(PIOS_INCLUDE_PPM) +#include +static const struct pios_ppm_cfg pios_ppm_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + .TIM_Channel = TIM_Channel_2, + }, + /* Use only the first channel for ppm */ + .channels = &pios_tim_rcvrport_all_channels[0], + .num_channels = 1, +}; + +#endif //PPM + +#if defined(PIOS_INCLUDE_RCVR) +#include "pios_rcvr_priv.h" + +#endif + +#if defined(PIOS_INCLUDE_USB) +#include "pios_usb_priv.h" + +static const struct pios_usb_cfg pios_usb_main_cfg = { + .irq = { + .init = { + .NVIC_IRQChannel = OTG_FS_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 3, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .vsense = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_25MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + }, + } +}; + +#include "pios_usb_board_data_priv.h" +#include "pios_usb_desc_hid_cdc_priv.h" +#include "pios_usb_desc_hid_only_priv.h" +#include "pios_usbhook.h" + +#endif /* PIOS_INCLUDE_USB */ + +#if defined(PIOS_INCLUDE_COM_MSG) + +#include + +#endif /* PIOS_INCLUDE_COM_MSG */ + +#if defined(PIOS_INCLUDE_USB_HID) +#include + +const struct pios_usb_hid_cfg pios_usb_hid_cfg = { + .data_if = 0, + .data_rx_ep = 1, + .data_tx_ep = 1, +}; +#endif /* PIOS_INCLUDE_USB_HID */ + +#if defined(PIOS_INCLUDE_USB_CDC) +#include + +const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = { + .ctrl_if = 1, + .ctrl_tx_ep = 2, + + .data_if = 2, + .data_rx_ep = 3, + .data_tx_ep = 3, +}; +#endif /* PIOS_INCLUDE_USB_CDC */ diff --git a/flight/board_hw_defs/simposix/board_hw_defs.c b/flight/board_hw_defs/simposix/board_hw_defs.c new file mode 100644 index 000000000..28740cdb9 --- /dev/null +++ b/flight/board_hw_defs/simposix/board_hw_defs.c @@ -0,0 +1,73 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file board_hw_defs.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Defines board specific static initializers for hardware for the OpenPilot board. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include + +#ifdef PIOS_INCLUDE_UDP + +#include + +#ifdef PIOS_INCLUDE_COM_TELEM +/* + * Telemetry on main USART + */ +const struct pios_udp_cfg pios_udp_telem_cfg = { + .ip = "0.0.0.0", + .port = 9000, +}; +#endif /* PIOS_COM_TELEM */ + +#ifdef PIOS_INCLUDE_GPS +/* + * GPS USART + */ +const struct pios_udp_cfg pios_udp_gps_cfg = { + .ip = "0.0.0.0", + .port = 9001, +}; + +#endif /* PIOS_INCLUDE_GPS */ + +#ifdef PIOS_INCLUDE_COM_AUX +/* + * AUX USART (UART label on rev2) + */ +const struct pios_udp_cfg pios_udp_aux_cfg = { + .ip = "0.0.0.0", + .port = 9002, +}; +#endif /* PIOS_COM_AUX */ + +#endif /* PIOS_UDP */ + +#if defined(PIOS_INCLUDE_COM) + +#include + +#endif /* PIOS_INCLUDE_COM */ + diff --git a/ground/openpilotgcs/share/openpilotgcs/dials/default/flightmode-status.svg b/ground/openpilotgcs/share/openpilotgcs/dials/default/flightmode-status.svg index 56f2ae83b..3a9f27ba4 100755 --- a/ground/openpilotgcs/share/openpilotgcs/dials/default/flightmode-status.svg +++ b/ground/openpilotgcs/share/openpilotgcs/dials/default/flightmode-status.svg @@ -1272,9 +1272,9 @@ style="opacity:0.98000004;fill:#ffffff;fill-opacity:1;stroke:#e31717;stroke-width:3.18836617;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" id="value" width="132.66878" - height="13.323594" - x="15.425945" - y="33.75214" + height="23" + x="15" + y="41" ry="3.4474616" inkscape:label="#rect2989" /> diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 1224614b5..47006a789 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -6,8 +6,8 @@ 0 0 - 730 - 602 + 796 + 618 @@ -73,25 +73,8 @@ - - #groupBox,#groupBox_2,#groupBox_3,#groupBox_6,#elevonMixBox{ -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); -border: 1px outset #999; -border-radius: 3; -font:bold; -} - -QGroupBox::title { - subcontrol-origin: margin; - subcontrol-position: top center; /* position at the top center */ - padding: 0 3px; - background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, - stop: 0 #FFOECE, stop: 1 #FFFFFF); - top: 5px; - } - - 2 + 0 @@ -747,7 +730,7 @@ margin:1px; - + 0 @@ -1376,7 +1359,7 @@ margin:1px; 0 - + @@ -1389,13 +1372,13 @@ margin:1px; false - + - + - + - + 0 @@ -1417,7 +1400,7 @@ margin:1px; - + Qt::Horizontal @@ -1432,7 +1415,7 @@ margin:1px; - + @@ -1462,9 +1445,9 @@ margin:1px; - + - + 0 @@ -1480,7 +1463,7 @@ margin:1px; Output channel asignmets - + @@ -1644,11 +1627,11 @@ margin:1px; Differential Steering Mix - + - + - + @@ -1685,7 +1668,7 @@ margin:1px; - + @@ -1727,7 +1710,7 @@ margin:1px; - + Qt::Horizontal @@ -1750,7 +1733,7 @@ margin:1px; Front throttle curve - + @@ -1807,7 +1790,7 @@ margin:1px; Rear throttle curve - + @@ -1850,7 +1833,7 @@ margin:1px; - + Qt::Vertical @@ -1863,9 +1846,9 @@ margin:1px; - + - + Qt::Horizontal @@ -2571,6 +2554,9 @@ margin:1px; true + + Qt::StrongFocus + Overall level of feed forward (in percentage). @@ -2600,6 +2586,9 @@ margin:1px; true + + Qt::StrongFocus + In miliseconds. When tuning: Slowly raise accel time from zero to just @@ -2629,6 +2618,9 @@ its target speed. true + + Qt::StrongFocus + When tuning: Slowly raise decel time from zero to just under the level where the motor starts to undershoot @@ -2667,6 +2659,9 @@ Do it after accel time is setup. + + Qt::StrongFocus + Limits how much the engines can accelerate or decelerate. In 'units per second', a sound default is 1000. @@ -2704,6 +2699,9 @@ In 'units per second', a sound default is 1000. + + Qt::StrongFocus + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> @@ -2719,6 +2717,9 @@ p, li { white-space: pre-wrap; } + + Qt::StrongFocus + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> @@ -2734,6 +2735,9 @@ p, li { white-space: pre-wrap; } + + Qt::StrongFocus + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> @@ -2780,14 +2784,14 @@ p, li { white-space: pre-wrap; } <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> +</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;"> <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD IS DANGEROUS</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</span></p> -<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</span></p></td></tr></table></body></html> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD IS DANGEROUS</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p> +<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html> @@ -2889,7 +2893,7 @@ p, li { white-space: pre-wrap; } 1 - ConfigccpmWidget + ConfigCcpmWidget QWidget
cfg_vehicletypes/configccpmwidget.h
1 @@ -2995,22 +2999,6 @@ p, li { white-space: pre-wrap; } - - mrPitchMixLevel - valueChanged(int) - mrPitchMixValue - setNum(int) - - - 83 - 228 - - - 82 - 168 - - - mrRollMixLevel valueChanged(int) @@ -3043,5 +3031,21 @@ p, li { white-space: pre-wrap; } + + mrPitchMixLevel + valueChanged(int) + mrPitchMixValue + setNum(int) + + + 92 + 222 + + + 92 + 151 + + + diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index b734ce54f..e535faa50 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -1,825 +1,835 @@ - - - CameraStabilizationWidget - - - - 0 - 0 - 720 - 567 - - - - Form - - - - - - #groupBox_5,#groupBox{ -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); -border: 1px outset #999; -border-radius: 3; -font:bold; -} - -QGroupBox::title { - subcontrol-origin: margin; - subcontrol-position: top center; /* position at the top center */ - padding: 0 3px; - background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, - stop: 0 #FFOECE, stop: 1 #FFFFFF); - top: 5px; - } - - - QFrame::NoFrame - - - true - - - - - 0 - 0 - 702 - 484 - - - - - - - Enable CameraStabilization module - - - - - - - After enabling the module, you must power cycle before using and configuring. - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 100 - - - - Basic Settings (Stabilization) - - - - - - Camera yaw angle for 100% output value, deg. - -This value should be tuned for particular gimbal and servo. You also -have to define channel output range using Output configuration tab. - - - 180 - - - 20 - - - - - - - Camera pitch angle for 100% output value, deg. - -This value should be tuned for particular gimbal and servo. You also -have to define channel output range using Output configuration tab. - - - 180 - - - 20 - - - - - - - Camera roll angle for 100% output value, deg. - -This value should be tuned for particular gimbal and servo. You also -have to define channel output range using Output configuration tab. - - - 180 - - - 20 - - - - - - - Yaw output channel for camera gimbal - - - - None - - - - - - - - Pitch output channel for camera gimbal - - - - None - - - - - - - - Roll output channel for camera gimbal - - - - None - - - - - - - - Output Channel - - - - - - - Output Range - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Yaw - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Pitch - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Roll - - - Qt::AlignCenter - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 204 - - - - Advanced Settings (Control) - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Yaw - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Pitch - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Roll - - - Qt::AlignCenter - - - - - - - Input channel to control camera yaw - -Don't forget to map this channel using Input configuration tab. - - - - None - - - - - - - - Input channel to control camera pitch - -Don't forget to map this channel using Input configuration tab. - - - - None - - - - - - - - Input channel to control camera roll - -Don't forget to map this channel using Input configuration tab. - - - - None - - - - - - - - Input Channel - - - - - - - Axis stabilization mode - -Attitude: camera tracks level for the axis. Input controls the deflection. -AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. - - - - Attitude - - - - - - - - Maximum camera yaw deflection for 100% input in Attitude mode, deg. - - - 180 - - - 20 - - - - - - - Maximum camera yaw rate for 100% input in AxisLock mode, deg/s. - - - 180 - - - 50 - - - - - - - Input low-pass filter response time for yaw axis, ms. - -This option smoothes the stick input. Zero value disables LPF. - - - 1000 - - - 150 - - - - - - - Axis stabilization mode - -Attitude: camera tracks level for the axis. Input controls the deflection. -AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. - - - - Attitude - - - - - - - - Maximum camera pitch deflection for 100% input in Attitude mode, deg. - - - 180 - - - 20 - - - - - - - Maximum camera pitch rate for 100% input in AxisLock mode, deg/s. - - - 180 - - - 50 - - - - - - - Input low-pass filter response time for pitch axis, ms. - -This option smoothes the stick input. Zero value disables LPF. - - - 1000 - - - 150 - - - - - - - Axis stabilization mode - -Attitude: camera tracks level for the axis. Input controls the deflection. -AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. - - - - Attitude - - - - - - - - Maximum camera roll deflection for 100% input in Attitude mode, deg. - - - 180 - - - 20 - - - - - - - Maximum camera roll rate for 100% input in AxisLock mode, deg/s. - - - 180 - - - 50 - - - - - - - Input low-pass filter response time for roll axis, ms. - -This option smoothes the stick input. Zero value disables LPF. - - - 1000 - - - 150 - - - - - - - MaxAxisLockRate - - - - - - - Response Time - - - - - - - Input Rate - - - - - - - Input Range - - - - - - - Stabilization Mode - - - - - - - (the same value for Roll, Pitch, Yaw) - - - - - - - Stick input deadband for all axes in AxisLock mode, deg/s. - -When stick input is within the MaxAxisLockRate range, camera tracks -current attitude. Otherwise it starts moving according to input with -rate depending on input value. - -If you have drift in your Tx controls, you may want to increase this -value. - - - 1 - - - 0.100000000000000 - - - 1.000000000000000 - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - - - - - - - - - - - QFrame::StyledPanel - - - QFrame::Raised - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 32 - 32 - - - - - true - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - Ctrl+S - - - false - - - true - - - - - - - Load default CameraStabilization settings except output channels - -Loaded settings are not applied automatically. You have to click the -Apply or Save button afterwards. - - - Reset To Defaults - - - - - - - Send settings to the board but do not save to the non-volatile memory - - - Apply - - - - - - - Send settings to the board and save to the non-volatile memory - - - Save - - - false - - - - - - - - - - - enableCameraStabilization - rollChannel - pitchChannel - yawChannel - rollOutputRange - pitchOutputRange - yawOutputRange - rollInputChannel - pitchInputChannel - yawInputChannel - rollStabilizationMode - pitchStabilizationMode - yawStabilizationMode - rollInputRange - pitchInputRange - yawInputRange - rollInputRate - pitchInputRate - yawInputRate - rollResponseTime - pitchResponseTime - yawResponseTime - MaxAxisLockRate - camerastabilizationHelp - camerastabilizationResetToDefaults - camerastabilizationSaveRAM - camerastabilizationSaveSD - scrollArea - - - - - - + + + CameraStabilizationWidget + + + + 0 + 0 + 720 + 739 + + + + Form + + + + + + QFrame::NoFrame + + + true + + + + + 0 + 0 + 696 + 635 + + + + + + + Qt::StrongFocus + + + Enable CameraStabilization module + + + + + + + After enabling the module, you must power cycle before using and configuring. + + + + + + + Qt::Horizontal + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 100 + + + + Basic Settings (Stabilization) + + + + + + Qt::StrongFocus + + + Camera yaw angle for 100% output value, deg. + +This value should be tuned for particular gimbal and servo. You also +have to define channel output range using Output configuration tab. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Camera pitch angle for 100% output value, deg. + +This value should be tuned for particular gimbal and servo. You also +have to define channel output range using Output configuration tab. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Camera roll angle for 100% output value, deg. + +This value should be tuned for particular gimbal and servo. You also +have to define channel output range using Output configuration tab. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Yaw output channel for camera gimbal + + + + None + + + + + + + + Qt::StrongFocus + + + Pitch output channel for camera gimbal + + + + None + + + + + + + + Qt::StrongFocus + + + Roll output channel for camera gimbal + + + + None + + + + + + + + Output Channel + + + + + + + Output Range + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Yaw + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Pitch + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Roll + + + Qt::AlignCenter + + + + + + + + + + + 0 + 0 + + + + + 0 + 204 + + + + Advanced Settings (Control) + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Yaw + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Pitch + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Roll + + + Qt::AlignCenter + + + + + + + Qt::StrongFocus + + + Input channel to control camera yaw + +Don't forget to map this channel using Input configuration tab. + + + + None + + + + + + + + Qt::StrongFocus + + + Input channel to control camera pitch + +Don't forget to map this channel using Input configuration tab. + + + + None + + + + + + + + Qt::StrongFocus + + + Input channel to control camera roll + +Don't forget to map this channel using Input configuration tab. + + + + None + + + + + + + + Input Channel + + + + + + + Qt::StrongFocus + + + Axis stabilization mode + +Attitude: camera tracks level for the axis. Input controls the deflection. +AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. + + + + Attitude + + + + + + + + Qt::StrongFocus + + + Maximum camera yaw deflection for 100% input in Attitude mode, deg. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Maximum camera yaw rate for 100% input in AxisLock mode, deg/s. + + + 180 + + + 50 + + + + + + + Qt::StrongFocus + + + Input low-pass filter response time for yaw axis, ms. + +This option smoothes the stick input. Zero value disables LPF. + + + 1000 + + + 150 + + + + + + + Qt::StrongFocus + + + Axis stabilization mode + +Attitude: camera tracks level for the axis. Input controls the deflection. +AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. + + + + Attitude + + + + + + + + Qt::StrongFocus + + + Maximum camera pitch deflection for 100% input in Attitude mode, deg. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Maximum camera pitch rate for 100% input in AxisLock mode, deg/s. + + + 180 + + + 50 + + + + + + + Qt::StrongFocus + + + Input low-pass filter response time for pitch axis, ms. + +This option smoothes the stick input. Zero value disables LPF. + + + 1000 + + + 150 + + + + + + + Qt::StrongFocus + + + Axis stabilization mode + +Attitude: camera tracks level for the axis. Input controls the deflection. +AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. + + + + Attitude + + + + + + + + Qt::StrongFocus + + + Maximum camera roll deflection for 100% input in Attitude mode, deg. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Maximum camera roll rate for 100% input in AxisLock mode, deg/s. + + + 180 + + + 50 + + + + + + + Qt::StrongFocus + + + Input low-pass filter response time for roll axis, ms. + +This option smoothes the stick input. Zero value disables LPF. + + + 1000 + + + 150 + + + + + + + MaxAxisLockRate + + + + + + + Response Time + + + + + + + Input Rate + + + + + + + Input Range + + + + + + + Stabilization Mode + + + + + + + (the same value for Roll, Pitch, Yaw) + + + + + + + Qt::StrongFocus + + + Stick input deadband for all axes in AxisLock mode, deg/s. + +When stick input is within the MaxAxisLockRate range, camera tracks +current attitude. Otherwise it starts moving according to input with +rate depending on input value. + +If you have drift in your Tx controls, you may want to increase this +value. + + + 1 + + + 0.100000000000000 + + + 1.000000000000000 + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + + + + + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + true + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + Ctrl+S + + + false + + + true + + + + + + + Load default CameraStabilization settings except output channels + +Loaded settings are not applied automatically. You have to click the +Apply or Save button afterwards. + + + Reset To Defaults + + + + + + + Send settings to the board but do not save to the non-volatile memory + + + Apply + + + + + + + Send settings to the board and save to the non-volatile memory + + + Save + + + false + + + + + + + + + + + enableCameraStabilization + rollChannel + pitchChannel + yawChannel + rollOutputRange + pitchOutputRange + yawOutputRange + rollInputChannel + pitchInputChannel + yawInputChannel + rollStabilizationMode + pitchStabilizationMode + yawStabilizationMode + rollInputRange + pitchInputRange + yawInputRange + rollInputRate + pitchInputRate + yawInputRate + rollResponseTime + pitchResponseTime + yawResponseTime + MaxAxisLockRate + camerastabilizationHelp + camerastabilizationResetToDefaults + camerastabilizationSaveRAM + camerastabilizationSaveSD + scrollArea + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/ccpm.ui b/ground/openpilotgcs/src/plugins/config/ccpm.ui index 8bb8a4e27..c31e5fb97 100644 --- a/ground/openpilotgcs/src/plugins/config/ccpm.ui +++ b/ground/openpilotgcs/src/plugins/config/ccpm.ui @@ -3959,7 +3959,7 @@ margin:1px; ccpmCollectiveSlider - sliderMoved(int) + valueChanged(int) ccpmCollectivespinBox setValue(int) @@ -4007,7 +4007,7 @@ margin:1px; ccpmRevoSlider - sliderMoved(int) + valueChanged(int) ccpmREVOspinBox setValue(int) @@ -4023,7 +4023,7 @@ margin:1px; SwashLvlPositionSlider - sliderMoved(int) + valueChanged(int) SwashLvlPositionSpinBox setValue(int) @@ -4071,7 +4071,7 @@ margin:1px; ccpmCollectiveScale - sliderMoved(int) + valueChanged(int) ccpmCollectiveScaleBox setValue(int) @@ -4087,7 +4087,7 @@ margin:1px; ccpmCyclicScale - sliderMoved(int) + valueChanged(int) ccpmCyclicScaleBox setValue(int) @@ -4119,7 +4119,7 @@ margin:1px; ccpmPitchScale - sliderMoved(int) + valueChanged(int) ccpmPitchScaleBox setValue(int) @@ -4167,7 +4167,7 @@ margin:1px; ccpmRollScale - sliderMoved(int) + valueChanged(int) ccpmRollScaleBox setValue(int) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp index 6d7a974c2..4a6ca62a9 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp @@ -25,7 +25,6 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "configccpmwidget.h" -#include "mixersettings.h" #include #include @@ -44,21 +43,17 @@ #define Pi 3.14159265358979323846 -ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) +ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent) { int i; - - m_ccpm = new Ui_ccpmWidget(); - m_ccpm->setupUi(this); SwashLvlConfigurationInProgress=0; SwashLvlState=0; SwashLvlServoInterlock=0; updatingFromHardware=FALSE; updatingToHardware=FALSE; - // Now connect the widget to the ManualControlCommand / Channel UAVObject - //ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - //UAVObjectManager *objManager = pm->getObject(); + m_ccpm = new Ui_ccpmWidget(); + m_ccpm->setupUi(this); // Initialization of the swashplaye widget m_ccpm->SwashplateImage->setScene(new QGraphicsScene(this)); @@ -147,21 +142,18 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) UAVObjectField * curve2source = mixerSettings->getField("Curve2Source"); Q_ASSERT(curve2source); - QStringList channels; - channels << "Channel1" << "Channel2" << "Channel3" << "Channel4" << - "Channel5" << "Channel6" << "Channel7" << "Channel8" << "None"; - m_ccpm->ccpmEngineChannel->addItems(channels); - m_ccpm->ccpmEngineChannel->setCurrentIndex(8); - m_ccpm->ccpmTailChannel->addItems(channels); - m_ccpm->ccpmTailChannel->setCurrentIndex(8); - m_ccpm->ccpmServoWChannel->addItems(channels); - m_ccpm->ccpmServoWChannel->setCurrentIndex(8); - m_ccpm->ccpmServoXChannel->addItems(channels); - m_ccpm->ccpmServoXChannel->setCurrentIndex(8); - m_ccpm->ccpmServoYChannel->addItems(channels); - m_ccpm->ccpmServoYChannel->setCurrentIndex(8); - m_ccpm->ccpmServoZChannel->addItems(channels); - m_ccpm->ccpmServoZChannel->setCurrentIndex(8); + m_ccpm->ccpmEngineChannel->addItems(channelNames); + m_ccpm->ccpmEngineChannel->setCurrentIndex(0); + m_ccpm->ccpmTailChannel->addItems(channelNames); + m_ccpm->ccpmTailChannel->setCurrentIndex(0); + m_ccpm->ccpmServoWChannel->addItems(channelNames); + m_ccpm->ccpmServoWChannel->setCurrentIndex(0); + m_ccpm->ccpmServoXChannel->addItems(channelNames); + m_ccpm->ccpmServoXChannel->setCurrentIndex(0); + m_ccpm->ccpmServoYChannel->addItems(channelNames); + m_ccpm->ccpmServoYChannel->setCurrentIndex(0); + m_ccpm->ccpmServoZChannel->addItems(channelNames); + m_ccpm->ccpmServoZChannel->setCurrentIndex(0); QStringList Types; Types << QString::fromUtf8("CCPM 2 Servo 90º") << QString::fromUtf8("CCPM 3 Servo 90º") << @@ -170,12 +162,14 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) QString::fromUtf8("Custom - User Angles") << QString::fromUtf8("Custom - Advanced Settings"); m_ccpm->ccpmType->addItems(Types); m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - 1); - requestccpmUpdate(); + UpdateCurveSettings(); //disable changing number of points in curves until UAVObjects have more than 5 m_ccpm->NumCurvePoints->setEnabled(0); + refreshWidgetsValues(QString("HeliCP")); + UpdateType(); //connect(m_ccpm->saveccpmToSD, SIGNAL(clicked()), this, SLOT(saveccpmUpdate())); @@ -205,9 +199,6 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) connect(m_ccpm->CurveSettings, SIGNAL(cellChanged (int, int)), this, SLOT(UpdateCurveWidgets())); connect(m_ccpm->TabObject, SIGNAL(currentChanged ( QWidget * )), this, SLOT(UpdateType())); -// connect(m_ccpm->SwashLvlSwashplateImage, SIGNAL(valueChanged(double)), this, SLOT(ccpmSwashplateRedraw())); - - connect(m_ccpm->PitchCurve, SIGNAL(curveUpdated(QList,double)), this, SLOT(updatePitchCurveValue(QList,double))); connect(m_ccpm->ThrottleCurve, SIGNAL(curveUpdated(QList,double)), this, SLOT(updateThrottleCurveValue(QList,double))); @@ -216,6 +207,7 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) connect(m_ccpm->SwashLvlCancelButton, SIGNAL(clicked()), this, SLOT(SwashLvlCancelButtonPressed())); connect(m_ccpm->SwashLvlFinishButton, SIGNAL(clicked()), this, SLOT(SwashLvlFinishButtonPressed())); + connect(m_ccpm->ccpmCollectivePassthrough, SIGNAL(clicked()),this, SLOT(SetUIComponentVisibilities())); connect(m_ccpm->ccpmLinkCyclic, SIGNAL(clicked()), this, SLOT(SetUIComponentVisibilities())); connect(m_ccpm->ccpmLinkRoll, SIGNAL(clicked()), this, SLOT(SetUIComponentVisibilities())); @@ -224,18 +216,96 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) ccpmSwashplateRedraw(); } -ConfigccpmWidget::~ConfigccpmWidget() +ConfigCcpmWidget::~ConfigCcpmWidget() { // Do nothing } -void ConfigccpmWidget::UpdateType() +void ConfigCcpmWidget::setupUI(QString frameType) +{ +} + +void ConfigCcpmWidget::ResetActuators(GUIConfigDataUnion* configData) +{ + configData->heli.Throttle = 0; + configData->heli.Tail = 0; + configData->heli.ServoIndexW = 0; + configData->heli.ServoIndexX = 0; + configData->heli.ServoIndexY = 0; + configData->heli.ServoIndexZ = 0; +} + +QStringList ConfigCcpmWidget::getChannelDescriptions() +{ + int i; + QStringList channelDesc; + + // init a channel_numelem list of channel desc defaults + for (i=0; i < (int)(ConfigCcpmWidget::CHANNEL_NUMELEM); i++) + { + channelDesc.append(QString("-")); + } + + // get the gui config data + GUIConfigDataUnion configData = GetConfigData(); + heliGUISettingsStruct heli = configData.heli; + + if (heli.Throttle > 0) + channelDesc[heli.Throttle - 1] = QString("Throttle"); + if (heli.Tail > 0) + channelDesc[heli.Tail - 1] = QString("Tail"); + + switch(heli.FirstServoIndex) + { + case 0: //front + if (heli.ServoIndexW > 0) + channelDesc[heli.ServoIndexW - 1] = QString("Elevator"); + if (heli.ServoIndexX > 0) + channelDesc[heli.ServoIndexX - 1] = QString("Roll1"); + if (heli.ServoIndexY > 0) + channelDesc[heli.ServoIndexY - 1] = QString("Roll2"); + break; + + case 1: //right + if (heli.ServoIndexW > 0) + channelDesc[heli.ServoIndexW - 1] = QString("ServoW"); + if (heli.ServoIndexX > 0) + channelDesc[heli.ServoIndexX - 1] = QString("ServoX"); + if (heli.ServoIndexY > 0) + channelDesc[heli.ServoIndexY - 1] = QString("ServoY"); + break; + + case 2: //rear + if (heli.ServoIndexW > 0) + channelDesc[heli.ServoIndexW - 1] = QString("Elevator"); + if (heli.ServoIndexX > 0) + channelDesc[heli.ServoIndexX - 1] = QString("Roll1"); + if (heli.ServoIndexY > 0) + channelDesc[heli.ServoIndexY - 1] = QString("Roll2"); + break; + + case 3: //left + if (heli.ServoIndexW > 0) + channelDesc[heli.ServoIndexW - 1] = QString("ServoW"); + if (heli.ServoIndexX > 0) + channelDesc[heli.ServoIndexX - 1] = QString("ServoX"); + if (heli.ServoIndexY > 0) + channelDesc[heli.ServoIndexY - 1] = QString("ServoY"); + break; + + } + if (heli.ServoIndexZ > 0) + channelDesc[heli.ServoIndexZ - 1] = QString("ServoZ"); + + return channelDesc; +} + +void ConfigCcpmWidget::UpdateType() { int TypeInt,SingleServoIndex,NumServosDefined; QString TypeText; double AdjustmentAngle=0; - UpdateCCPMOptionsFromUI(); SetUIComponentVisibilities(); TypeInt = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1; @@ -283,8 +353,8 @@ void ConfigccpmWidget::UpdateType() m_ccpm->ccpmAngleZ->setValue(0); m_ccpm->ccpmAngleY->setEnabled(0); m_ccpm->ccpmAngleZ->setEnabled(0); - m_ccpm->ccpmServoYChannel->setCurrentIndex(8); - m_ccpm->ccpmServoZChannel->setCurrentIndex(8); + m_ccpm->ccpmServoYChannel->setCurrentIndex(0); + m_ccpm->ccpmServoZChannel->setCurrentIndex(0); m_ccpm->ccpmServoYChannel->setEnabled(0); m_ccpm->ccpmServoZChannel->setEnabled(0); //m_ccpm->ccpmCorrectionAngle->setValue(0); @@ -298,7 +368,7 @@ void ConfigccpmWidget::UpdateType() m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 180,360)); m_ccpm->ccpmAngleZ->setValue(0); m_ccpm->ccpmAngleZ->setEnabled(0); - m_ccpm->ccpmServoZChannel->setCurrentIndex(8); + m_ccpm->ccpmServoZChannel->setCurrentIndex(0); m_ccpm->ccpmServoZChannel->setEnabled(0); //m_ccpm->ccpmCorrectionAngle->setValue(0); NumServosDefined=3; @@ -323,7 +393,7 @@ void ConfigccpmWidget::UpdateType() m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 240,360)); m_ccpm->ccpmAngleZ->setValue(0); m_ccpm->ccpmAngleZ->setEnabled(0); - m_ccpm->ccpmServoZChannel->setCurrentIndex(8); + m_ccpm->ccpmServoZChannel->setCurrentIndex(0); m_ccpm->ccpmServoZChannel->setEnabled(0); //m_ccpm->ccpmCorrectionAngle->setValue(0); NumServosDefined=3; @@ -336,7 +406,7 @@ void ConfigccpmWidget::UpdateType() m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 220,360)); m_ccpm->ccpmAngleZ->setValue(0); m_ccpm->ccpmAngleZ->setEnabled(0); - m_ccpm->ccpmServoZChannel->setCurrentIndex(8); + m_ccpm->ccpmServoZChannel->setCurrentIndex(0); m_ccpm->ccpmServoZChannel->setEnabled(0); //m_ccpm->ccpmCorrectionAngle->setValue(0); NumServosDefined=3; @@ -350,8 +420,8 @@ void ConfigccpmWidget::UpdateType() m_ccpm->ccpmAngleZ->setValue(0); m_ccpm->ccpmAngleY->setEnabled(0); m_ccpm->ccpmAngleZ->setEnabled(0); - m_ccpm->ccpmServoYChannel->setCurrentIndex(8); - m_ccpm->ccpmServoZChannel->setCurrentIndex(8); + m_ccpm->ccpmServoYChannel->setCurrentIndex(0); + m_ccpm->ccpmServoZChannel->setCurrentIndex(0); m_ccpm->ccpmServoYChannel->setEnabled(0); m_ccpm->ccpmServoZChannel->setEnabled(0); //m_ccpm->ccpmCorrectionAngle->setValue(0); @@ -407,12 +477,12 @@ void ConfigccpmWidget::UpdateType() /** Resets a mixer curve */ -void ConfigccpmWidget::resetMixer(MixerCurveWidget *mixer, int numElements) +void ConfigCcpmWidget::resetMixer(MixerCurveWidget *mixer, int numElements) { mixer->initLinearCurve(numElements,(double)1); } -void ConfigccpmWidget::UpdateCurveWidgets() +void ConfigCcpmWidget::UpdateCurveWidgets() { int NumCurvePoints,i,Changed; QList curveValues; @@ -446,7 +516,7 @@ void ConfigccpmWidget::UpdateCurveWidgets() if (Changed==1)m_ccpm->PitchCurve->setCurve(curveValues); } -void ConfigccpmWidget::updatePitchCurveValue(QList curveValues0,double Value0) +void ConfigCcpmWidget::updatePitchCurveValue(QList curveValues0,double Value0) { Q_UNUSED(curveValues0); Q_UNUSED(Value0); @@ -470,7 +540,7 @@ void ConfigccpmWidget::updatePitchCurveValue(QList curveValues0,double V } -void ConfigccpmWidget::updateThrottleCurveValue(QList curveValues0,double Value0) +void ConfigCcpmWidget::updateThrottleCurveValue(QList curveValues0,double Value0) { Q_UNUSED(curveValues0); Q_UNUSED(Value0); @@ -495,7 +565,7 @@ void ConfigccpmWidget::updateThrottleCurveValue(QList curveValues0,doubl } -void ConfigccpmWidget::UpdateCurveSettings() +void ConfigCcpmWidget::UpdateCurveSettings() { int NumCurvePoints,i; double scale; @@ -625,7 +695,7 @@ void ConfigccpmWidget::UpdateCurveSettings() UpdateCurveWidgets(); } -void ConfigccpmWidget::GenerateCurve() +void ConfigCcpmWidget::GenerateCurve() { int NumCurvePoints,CurveToGenerate,i; double value1, value2, value3, scale; @@ -695,7 +765,7 @@ void ConfigccpmWidget::GenerateCurve() } -void ConfigccpmWidget::ccpmSwashplateRedraw() +void ConfigCcpmWidget::ccpmSwashplateRedraw() { double angle[CCPM_MAX_SWASH_SERVOS],CorrectionAngle,x,y,w,h,radius,CenterX,CenterY; int used[CCPM_MAX_SWASH_SERVOS],defined[CCPM_MAX_SWASH_SERVOS],i; @@ -735,10 +805,10 @@ void ConfigccpmWidget::ccpmSwashplateRedraw() defined[1]=(m_ccpm->ccpmServoXChannel->isEnabled()); defined[2]=(m_ccpm->ccpmServoYChannel->isEnabled()); defined[3]=(m_ccpm->ccpmServoZChannel->isEnabled()); - used[0]=((m_ccpm->ccpmServoWChannel->currentIndex()<8)&&(m_ccpm->ccpmServoWChannel->isEnabled())); - used[1]=((m_ccpm->ccpmServoXChannel->currentIndex()<8)&&(m_ccpm->ccpmServoXChannel->isEnabled())); - used[2]=((m_ccpm->ccpmServoYChannel->currentIndex()<8)&&(m_ccpm->ccpmServoYChannel->isEnabled())); - used[3]=((m_ccpm->ccpmServoZChannel->currentIndex()<8)&&(m_ccpm->ccpmServoZChannel->isEnabled())); + used[0]=((m_ccpm->ccpmServoWChannel->currentIndex()>0)&&(m_ccpm->ccpmServoWChannel->isEnabled())); + used[1]=((m_ccpm->ccpmServoXChannel->currentIndex()>0)&&(m_ccpm->ccpmServoXChannel->isEnabled())); + used[2]=((m_ccpm->ccpmServoYChannel->currentIndex()>0)&&(m_ccpm->ccpmServoYChannel->isEnabled())); + used[3]=((m_ccpm->ccpmServoZChannel->currentIndex()>0)&&(m_ccpm->ccpmServoZChannel->isEnabled())); angle[0]=(CorrectionAngle+180+m_ccpm->ccpmAngleW->value())*Pi/180.00; angle[1]=(CorrectionAngle+180+m_ccpm->ccpmAngleX->value())*Pi/180.00; angle[2]=(CorrectionAngle+180+m_ccpm->ccpmAngleY->value())*Pi/180.00; @@ -796,69 +866,14 @@ void ConfigccpmWidget::ccpmSwashplateRedraw() //m_ccpm->SwashplateImage->fitInView(SwashplateImg, Qt::KeepAspectRatio); } -void ConfigccpmWidget::ccpmSwashplateUpdate() +void ConfigCcpmWidget::ccpmSwashplateUpdate() { ccpmSwashplateRedraw(); SetUIComponentVisibilities(); UpdateMixer(); } -void ConfigccpmWidget::ccpmChannelCheck() -{ - if((m_ccpm->ccpmServoWChannel->currentIndex()==8)&&(m_ccpm->ccpmServoWChannel->isEnabled())) - { - m_ccpm->ccpmServoWLabel->setText("Servo W"); - } - else - { - m_ccpm->ccpmServoWLabel->setText("Servo W"); - } - if((m_ccpm->ccpmServoXChannel->currentIndex()==8)&&(m_ccpm->ccpmServoXChannel->isEnabled())) - { - m_ccpm->ccpmServoXLabel->setText("Servo X"); - } - else - { - m_ccpm->ccpmServoXLabel->setText("Servo X"); - } - if((m_ccpm->ccpmServoYChannel->currentIndex()==8)&&(m_ccpm->ccpmServoYChannel->isEnabled())) - { - m_ccpm->ccpmServoYLabel->setText("Servo Y"); - } - else - { - m_ccpm->ccpmServoYLabel->setText("Servo Y"); - } - if((m_ccpm->ccpmServoZChannel->currentIndex()==8)&&(m_ccpm->ccpmServoZChannel->isEnabled())) - { - m_ccpm->ccpmServoZLabel->setText("Servo Z"); - } - else - { - m_ccpm->ccpmServoZLabel->setText("Servo Z"); - } - - if((m_ccpm->ccpmEngineChannel->currentIndex()==8)&&(m_ccpm->ccpmEngineChannel->isEnabled())) - { - m_ccpm->ccpmEngineLabel->setText("Engine"); - } - else - { - m_ccpm->ccpmEngineLabel->setText("Engine"); - } - - if((m_ccpm->ccpmTailChannel->currentIndex()==8)&&(m_ccpm->ccpmTailChannel->isEnabled())) - { - m_ccpm->ccpmTailLabel->setText("Tail Rotor"); - } - else - { - m_ccpm->ccpmTailLabel->setText("Tail Rotor"); - } - -} - -void ConfigccpmWidget::UpdateMixer() +void ConfigCcpmWidget::UpdateMixer() { bool useCCPM; bool useCyclic; @@ -866,13 +881,14 @@ void ConfigccpmWidget::UpdateMixer() float CollectiveConstant,PitchConstant,RollConstant,ThisAngle[6]; QString Channel; - ccpmChannelCheck(); - UpdateCCPMOptionsFromUI(); - - useCCPM = !(GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState); - useCyclic = GUIConfigData.heli.ccpmLinkRollState; + throwConfigError(QString("HeliCP")); - CollectiveConstant = (float)GUIConfigData.heli.SliderValue0 / 100.00; + GUIConfigDataUnion config = GetConfigData(); + + useCCPM = !(config.heli.ccpmCollectivePassthroughState || !config.heli.ccpmLinkCyclicState); + useCyclic = config.heli.ccpmLinkRollState; + + CollectiveConstant = (float)config.heli.SliderValue0 / 100.00; if (useCCPM) {//cyclic = 1 - collective @@ -881,18 +897,18 @@ void ConfigccpmWidget::UpdateMixer() } else { - PitchConstant = (float)GUIConfigData.heli.SliderValue1 / 100.00;; + PitchConstant = (float)config.heli.SliderValue1 / 100.00;; if (useCyclic) { RollConstant = PitchConstant; } else { - RollConstant = (float)GUIConfigData.heli.SliderValue2 / 100.00;; + RollConstant = (float)config.heli.SliderValue2 / 100.00;; } } - if (GUIConfigData.heli.SwasplateType>0) + if (config.heli.SwashplateType>0) {//not advanced settings //get the channel data from the ui MixerChannelData[0] = m_ccpm->ccpmEngineChannel->currentIndex(); @@ -914,18 +930,18 @@ void ConfigccpmWidget::UpdateMixer() ThisEnable[4] = m_ccpm->ccpmServoYChannel->isEnabled(); ThisEnable[5] = m_ccpm->ccpmServoZChannel->isEnabled(); - ServosText[0]->setPlainText(QString("%1").arg( MixerChannelData[2]+1 )); - ServosText[1]->setPlainText(QString("%1").arg( MixerChannelData[3]+1 )); - ServosText[2]->setPlainText(QString("%1").arg( MixerChannelData[4]+1 )); - ServosText[3]->setPlainText(QString("%1").arg( MixerChannelData[5]+1 )); + ServosText[0]->setPlainText(QString("%1").arg( MixerChannelData[2] )); + ServosText[1]->setPlainText(QString("%1").arg( MixerChannelData[3] )); + ServosText[2]->setPlainText(QString("%1").arg( MixerChannelData[4] )); + ServosText[3]->setPlainText(QString("%1").arg( MixerChannelData[5] )); //go through the user data and update the mixer matrix for (i=0;i<6;i++) { - if ((MixerChannelData[i]<8)&&((ThisEnable[i])||(i<2))) + if ((MixerChannelData[i]>0)&&((ThisEnable[i])||(i<2))) { - m_ccpm->ccpmAdvancedSettingsTable->item(i,0)->setText(QString("%1").arg( MixerChannelData[i]+1 )); + m_ccpm->ccpmAdvancedSettingsTable->item(i,0)->setText(QString("%1").arg( MixerChannelData[i] )); //config the vector if (i==0) {//motor-engine @@ -947,8 +963,8 @@ void ConfigccpmWidget::UpdateMixer() {//Swashplate m_ccpm->ccpmAdvancedSettingsTable->item(i,1)->setText(QString("%1").arg(0));//ThrottleCurve1 m_ccpm->ccpmAdvancedSettingsTable->item(i,2)->setText(QString("%1").arg((int)(127.0*CollectiveConstant)));//ThrottleCurve2 - m_ccpm->ccpmAdvancedSettingsTable->item(i,3)->setText(QString("%1").arg((int)(127.0*(RollConstant)*sin((180+GUIConfigData.heli.CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Roll - m_ccpm->ccpmAdvancedSettingsTable->item(i,4)->setText(QString("%1").arg((int)(127.0*(PitchConstant)*cos((GUIConfigData.heli.CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Pitch + m_ccpm->ccpmAdvancedSettingsTable->item(i,3)->setText(QString("%1").arg((int)(127.0*(RollConstant)*sin((180+config.heli.CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Roll + m_ccpm->ccpmAdvancedSettingsTable->item(i,4)->setText(QString("%1").arg((int)(127.0*(PitchConstant)*cos((config.heli.CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Pitch m_ccpm->ccpmAdvancedSettingsTable->item(i,5)->setText(QString("%1").arg(0));//Yaw } @@ -970,246 +986,167 @@ void ConfigccpmWidget::UpdateMixer() } } - - } - -/************************** - * ccpm settings - **************************/ -/* - Get the state of the UI check boxes and change the visibility of sliders - typedef struct { - uint SwasplateType:3; - uint FirstServoIndex:2; - uint CorrectionAngle:9; - uint ccpmCollectivePassthroughState:1; - uint ccpmLinkCyclicState:1; - uint ccpmLinkRollState:1; - uint CollectiveChannel:3; - uint padding:12; - } __attribute__((packed)) heliGUISettingsStruct; - - */ -void ConfigccpmWidget::UpdateCCPMOptionsFromUI() +QString ConfigCcpmWidget::updateConfigObjects() { + QString airframeType = "HeliCP"; + bool useCCPM; bool useCyclic; - - if (updatingFromHardware) return; + + if (updatingFromHardware == TRUE) return airframeType; + + updatingFromHardware = TRUE; + //get the user options + GUIConfigDataUnion config = GetConfigData(); + //swashplate config - GUIConfigData.heli.SwasplateType = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1; - GUIConfigData.heli.FirstServoIndex = m_ccpm->ccpmSingleServo->currentIndex(); - + config.heli.SwashplateType = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1; + config.heli.FirstServoIndex = m_ccpm->ccpmSingleServo->currentIndex(); + //ccpm mixing options - GUIConfigData.heli.ccpmCollectivePassthroughState = m_ccpm->ccpmCollectivePassthrough->isChecked(); - GUIConfigData.heli.ccpmLinkCyclicState = m_ccpm->ccpmLinkCyclic->isChecked(); - GUIConfigData.heli.ccpmLinkRollState = m_ccpm->ccpmLinkRoll->isChecked(); - useCCPM = !(GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState); - useCyclic = GUIConfigData.heli.ccpmLinkRollState; - + config.heli.ccpmCollectivePassthroughState = m_ccpm->ccpmCollectivePassthrough->isChecked(); + config.heli.ccpmLinkCyclicState = m_ccpm->ccpmLinkCyclic->isChecked(); + config.heli.ccpmLinkRollState = m_ccpm->ccpmLinkRoll->isChecked(); + useCCPM = !(config.heli.ccpmCollectivePassthroughState || !config.heli.ccpmLinkCyclicState); + useCyclic = config.heli.ccpmLinkRollState; + //correction angle - GUIConfigData.heli.CorrectionAngle = m_ccpm->ccpmCorrectionAngle->value(); - + config.heli.CorrectionAngle = m_ccpm->ccpmCorrectionAngle->value(); + //update sliders - if (useCCPM) + if (useCCPM) { - GUIConfigData.heli.SliderValue0 = m_ccpm->ccpmCollectiveSlider->value(); + config.heli.SliderValue0 = m_ccpm->ccpmCollectiveSlider->value(); } else { - GUIConfigData.heli.SliderValue0 = m_ccpm->ccpmCollectiveScale->value(); + config.heli.SliderValue0 = m_ccpm->ccpmCollectiveScale->value(); } - if (useCyclic) + if (useCyclic) { - GUIConfigData.heli.SliderValue1 = m_ccpm->ccpmCyclicScale->value(); + config.heli.SliderValue1 = m_ccpm->ccpmCyclicScale->value(); } else { - GUIConfigData.heli.SliderValue1 = m_ccpm->ccpmPitchScale->value(); - } - GUIConfigData.heli.SliderValue2 = m_ccpm->ccpmRollScale->value(); - + config.heli.SliderValue1 = m_ccpm->ccpmPitchScale->value(); + } + config.heli.SliderValue2 = m_ccpm->ccpmRollScale->value(); + //servo assignments - GUIConfigData.heli.ServoIndexW = m_ccpm->ccpmServoWChannel->currentIndex(); - GUIConfigData.heli.ServoIndexX = m_ccpm->ccpmServoXChannel->currentIndex(); - GUIConfigData.heli.ServoIndexY = m_ccpm->ccpmServoYChannel->currentIndex(); - GUIConfigData.heli.ServoIndexZ = m_ccpm->ccpmServoZChannel->currentIndex(); - + config.heli.ServoIndexW = m_ccpm->ccpmServoWChannel->currentIndex(); + config.heli.ServoIndexX = m_ccpm->ccpmServoXChannel->currentIndex(); + config.heli.ServoIndexY = m_ccpm->ccpmServoYChannel->currentIndex(); + config.heli.ServoIndexZ = m_ccpm->ccpmServoZChannel->currentIndex(); + + //throttle + config.heli.Throttle = m_ccpm->ccpmEngineChannel->currentIndex(); + //tail + config.heli.Tail = m_ccpm->ccpmTailChannel->currentIndex(); + + SetConfigData(config); + + updatingFromHardware = FALSE; + return airframeType; } -void ConfigccpmWidget::UpdateCCPMUIFromOptions() + +QString ConfigCcpmWidget::updateConfigObjectsFromWidgets() //UpdateCCPMOptionsFromUI() { + QString airframeType = updateConfigObjects(); + + setMixer(); + + return airframeType; +} + +void ConfigCcpmWidget::refreshWidgetsValues(QString frameType) //UpdateCCPMUIFromOptions() +{ + Q_UNUSED(frameType); + + GUIConfigDataUnion config = GetConfigData(); + //swashplate config - m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - (GUIConfigData.heli.SwasplateType +1)); - m_ccpm->ccpmSingleServo->setCurrentIndex(GUIConfigData.heli.FirstServoIndex); + setComboCurrentIndex( m_ccpm->ccpmType, m_ccpm->ccpmType->count() - (config.heli.SwashplateType +1)); + setComboCurrentIndex(m_ccpm->ccpmSingleServo, config.heli.FirstServoIndex); //ccpm mixing options - m_ccpm->ccpmCollectivePassthrough->setChecked(GUIConfigData.heli.ccpmCollectivePassthroughState); - m_ccpm->ccpmLinkCyclic->setChecked(GUIConfigData.heli.ccpmLinkCyclicState); - m_ccpm->ccpmLinkRoll->setChecked(GUIConfigData.heli.ccpmLinkRollState); + m_ccpm->ccpmCollectivePassthrough->setChecked(config.heli.ccpmCollectivePassthroughState); + m_ccpm->ccpmLinkCyclic->setChecked(config.heli.ccpmLinkCyclicState); + m_ccpm->ccpmLinkRoll->setChecked(config.heli.ccpmLinkRollState); //correction angle - m_ccpm->ccpmCorrectionAngle->setValue(GUIConfigData.heli.CorrectionAngle); + m_ccpm->ccpmCorrectionAngle->setValue(config.heli.CorrectionAngle); //update sliders - m_ccpm->ccpmCollectiveScale->setValue(GUIConfigData.heli.SliderValue0); - m_ccpm->ccpmCollectiveScaleBox->setValue(GUIConfigData.heli.SliderValue0); - m_ccpm->ccpmCyclicScale->setValue(GUIConfigData.heli.SliderValue1); - m_ccpm->ccpmCyclicScaleBox->setValue(GUIConfigData.heli.SliderValue1); - m_ccpm->ccpmPitchScale->setValue(GUIConfigData.heli.SliderValue1); - m_ccpm->ccpmPitchScaleBox->setValue(GUIConfigData.heli.SliderValue1); - m_ccpm->ccpmRollScale->setValue(GUIConfigData.heli.SliderValue2); - m_ccpm->ccpmRollScaleBox->setValue(GUIConfigData.heli.SliderValue2); - m_ccpm->ccpmCollectiveSlider->setValue(GUIConfigData.heli.SliderValue0); - m_ccpm->ccpmCollectivespinBox->setValue(GUIConfigData.heli.SliderValue0); + m_ccpm->ccpmCollectiveScale->setValue(config.heli.SliderValue0); + m_ccpm->ccpmCollectiveScaleBox->setValue(config.heli.SliderValue0); + m_ccpm->ccpmCyclicScale->setValue(config.heli.SliderValue1); + m_ccpm->ccpmCyclicScaleBox->setValue(config.heli.SliderValue1); + m_ccpm->ccpmPitchScale->setValue(config.heli.SliderValue1); + m_ccpm->ccpmPitchScaleBox->setValue(config.heli.SliderValue1); + m_ccpm->ccpmRollScale->setValue(config.heli.SliderValue2); + m_ccpm->ccpmRollScaleBox->setValue(config.heli.SliderValue2); + m_ccpm->ccpmCollectiveSlider->setValue(config.heli.SliderValue0); + m_ccpm->ccpmCollectivespinBox->setValue(config.heli.SliderValue0); //servo assignments - m_ccpm->ccpmServoWChannel->setCurrentIndex(GUIConfigData.heli.ServoIndexW); - m_ccpm->ccpmServoXChannel->setCurrentIndex(GUIConfigData.heli.ServoIndexX); - m_ccpm->ccpmServoYChannel->setCurrentIndex(GUIConfigData.heli.ServoIndexY); - m_ccpm->ccpmServoZChannel->setCurrentIndex(GUIConfigData.heli.ServoIndexZ); + setComboCurrentIndex(m_ccpm->ccpmServoWChannel, config.heli.ServoIndexW); + setComboCurrentIndex( m_ccpm->ccpmServoXChannel,config.heli.ServoIndexX); + setComboCurrentIndex( m_ccpm->ccpmServoYChannel,config.heli.ServoIndexY); + setComboCurrentIndex( m_ccpm->ccpmServoZChannel,config.heli.ServoIndexZ); + //throttle + setComboCurrentIndex( m_ccpm->ccpmEngineChannel, config.heli.Throttle); + //tail + setComboCurrentIndex( m_ccpm->ccpmTailChannel, config.heli.Tail); + + getMixer(); } -void ConfigccpmWidget::SetUIComponentVisibilities() +void ConfigCcpmWidget::SetUIComponentVisibilities() { - UpdateCCPMOptionsFromUI(); - //set which sliders are user... m_ccpm->ccpmRevoMixingBox->setVisible(0); - m_ccpm->ccpmPitchMixingBox->setVisible(!GUIConfigData.heli.ccpmCollectivePassthroughState && GUIConfigData.heli.ccpmLinkCyclicState); - m_ccpm->ccpmCollectiveScalingBox->setVisible(GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState); + m_ccpm->ccpmPitchMixingBox->setVisible(!m_ccpm->ccpmCollectivePassthrough->isChecked() && + m_ccpm->ccpmLinkCyclic->isChecked()); - m_ccpm->ccpmLinkCyclic->setVisible(!GUIConfigData.heli.ccpmCollectivePassthroughState); - - m_ccpm->ccpmCyclicScalingBox->setVisible((GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState) && GUIConfigData.heli.ccpmLinkRollState); - if (!GUIConfigData.heli.ccpmCollectivePassthroughState && GUIConfigData.heli.ccpmLinkCyclicState) + m_ccpm->ccpmCollectiveScalingBox->setVisible(m_ccpm->ccpmCollectivePassthrough->isChecked() || !m_ccpm->ccpmLinkCyclic->isChecked()); + + m_ccpm->ccpmLinkCyclic->setVisible(!m_ccpm->ccpmCollectivePassthrough->isChecked()); + + m_ccpm->ccpmCyclicScalingBox->setVisible((m_ccpm->ccpmCollectivePassthrough->isChecked() || !m_ccpm->ccpmLinkCyclic->isChecked()) && + m_ccpm->ccpmLinkRoll->isChecked()); + + if (!m_ccpm->ccpmCollectivePassthrough->checkState() && m_ccpm->ccpmLinkCyclic->isChecked()) { m_ccpm->ccpmPitchScalingBox->setVisible(0); m_ccpm->ccpmRollScalingBox->setVisible(0); m_ccpm->ccpmLinkRoll->setVisible(0); - + } else { - m_ccpm->ccpmPitchScalingBox->setVisible(!GUIConfigData.heli.ccpmLinkRollState); - m_ccpm->ccpmRollScalingBox->setVisible(!GUIConfigData.heli.ccpmLinkRollState); + m_ccpm->ccpmPitchScalingBox->setVisible(!m_ccpm->ccpmLinkRoll->isChecked()); + m_ccpm->ccpmRollScalingBox->setVisible(!m_ccpm->ccpmLinkRoll->isChecked()); m_ccpm->ccpmLinkRoll->setVisible(1); } - } /** Request the current value of the SystemSettings which holds the ccpm type */ -void ConfigccpmWidget::requestccpmUpdate() +void ConfigCcpmWidget::getMixer() { -#define MaxAngleError 2 - int MixerDataFromHeli[8][5]; - quint8 MixerOutputType[8]; - int EngineChannel,TailRotorChannel,ServoChannels[4],ServoAngles[4],SortAngles[4],ServoCurve2[4]; - int NumServos=0; - if (SwashLvlConfigurationInProgress)return; if (updatingToHardware)return; updatingFromHardware=TRUE; - unsigned int i,j; - - SystemSettings * systemSettings = SystemSettings::GetInstance(getObjectManager()); - Q_ASSERT(systemSettings); - SystemSettings::DataFields systemSettingsData = systemSettings->getData(); - - Q_ASSERT(SystemSettings::GUICONFIGDATA_NUMELEM == - (sizeof(GUIConfigData.UAVObject) / sizeof(GUIConfigData.UAVObject[0]))); - - for(i = 0; i < SystemSettings::GUICONFIGDATA_NUMELEM; i++) - GUIConfigData.UAVObject[i]=systemSettingsData.GUIConfigData[i]; - - UpdateCCPMUIFromOptions(); + int i; // Get existing mixer settings MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); - - //go through the user data and update the mixer matrix - for (j=0;j<5;j++) - { - MixerDataFromHeli[0][j] = mixerSettingsData.Mixer1Vector[j]; - MixerDataFromHeli[1][j] = mixerSettingsData.Mixer2Vector[j]; - MixerDataFromHeli[2][j] = mixerSettingsData.Mixer3Vector[j]; - MixerDataFromHeli[3][j] = mixerSettingsData.Mixer4Vector[j]; - MixerDataFromHeli[4][j] = mixerSettingsData.Mixer5Vector[j]; - MixerDataFromHeli[5][j] = mixerSettingsData.Mixer6Vector[j]; - MixerDataFromHeli[6][j] = mixerSettingsData.Mixer7Vector[j]; - MixerDataFromHeli[7][j] = mixerSettingsData.Mixer8Vector[j]; - } - - MixerOutputType[0] = mixerSettingsData.Mixer1Type; - MixerOutputType[1] = mixerSettingsData.Mixer2Type; - MixerOutputType[2] = mixerSettingsData.Mixer3Type; - MixerOutputType[3] = mixerSettingsData.Mixer4Type; - MixerOutputType[4] = mixerSettingsData.Mixer5Type; - MixerOutputType[5] = mixerSettingsData.Mixer6Type; - MixerOutputType[6] = mixerSettingsData.Mixer7Type; - MixerOutputType[7] = mixerSettingsData.Mixer8Type; - - EngineChannel =-1; - TailRotorChannel =-1; - for (j=0;j<5;j++) - { - ServoChannels[j]=8; - ServoCurve2[j]=0; - ServoAngles[j]=0; - SortAngles[j]=j; - } - - NumServos=0; - //process the data from Heli and try to figure out the settings... - for (i=0;i<8;i++) - { - //check if this is the engine... Throttle only - if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_MOTOR)&& - (MixerDataFromHeli[i][0]>0)&&//ThrottleCurve1 - (MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2 - (MixerDataFromHeli[i][2]==0)&&//Roll - (MixerDataFromHeli[i][3]==0)&&//Pitch - (MixerDataFromHeli[i][4]==0))//Yaw - { - EngineChannel = i; - m_ccpm->ccpmEngineChannel->setCurrentIndex(i); - - } - //check if this is the tail rotor... REVO and YAW - if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_SERVO)&& - //(MixerDataFromHeli[i][0]!=0)&&//ThrottleCurve1 - (MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2 - (MixerDataFromHeli[i][2]==0)&&//Roll - (MixerDataFromHeli[i][3]==0)&&//Pitch - (MixerDataFromHeli[i][4]!=0))//Yaw - { - TailRotorChannel = i; - m_ccpm->ccpmTailChannel->setCurrentIndex(i); - m_ccpm->ccpmRevoSlider->setValue((MixerDataFromHeli[i][0]*100)/127); - m_ccpm->ccpmREVOspinBox->setValue((MixerDataFromHeli[i][0]*100)/127); - } - //check if this is a swashplate servo... Throttle is zero - if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_SERVO)&& - (MixerDataFromHeli[i][0]==0)&&//ThrottleCurve1 - //(MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2 - //(MixerDataFromHeli[i][2]==0)&&//Roll - //(MixerDataFromHeli[i][3]==0)&&//Pitch - (MixerDataFromHeli[i][4]==0))//Yaw - { - ServoChannels[NumServos] = i;//record the channel for this servo - ServoCurve2[NumServos]=MixerDataFromHeli[i][1];//record the ThrottleCurve2 contribution to this servo - ServoAngles[NumServos]=NumServos*45;//make this 0 for the final version - - NumServos++; - } - - } //get the settings for the curve from the mixer settings for (i=0;i<5;i++) @@ -1221,7 +1158,7 @@ void ConfigccpmWidget::requestccpmUpdate() } updatingFromHardware=FALSE; - UpdateCCPMUIFromOptions(); + ccpmSwashplateUpdate(); } @@ -1229,25 +1166,15 @@ void ConfigccpmWidget::requestccpmUpdate() /** Sends the config to the board (ccpm type) */ -void ConfigccpmWidget::sendccpmUpdate() +void ConfigCcpmWidget::setMixer() { int i,j; if (SwashLvlConfigurationInProgress)return; - updatingToHardware=TRUE; - //ShowDisclaimer(1); - - UpdateCCPMOptionsFromUI(); + if (updatingToHardware == TRUE) return; + + updatingToHardware=TRUE; - // Store the data required to reconstruct - SystemSettings * systemSettings = SystemSettings::GetInstance(getObjectManager()); - Q_ASSERT(systemSettings); - SystemSettings::DataFields systemSettingsData = systemSettings->getData(); - systemSettingsData.GUIConfigData[0] = GUIConfigData.UAVObject[0]; - systemSettingsData.GUIConfigData[1] = GUIConfigData.UAVObject[1]; - systemSettings->setData(systemSettingsData); - systemSettings->updated(); - MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); Q_ASSERT(mixerSettings); MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); @@ -1276,19 +1203,23 @@ void ConfigccpmWidget::sendccpmUpdate() &mixerSettingsData.Mixer8Type }; + //reset all to Disabled + for (i=0; i<8; i++) + *mixerTypes[i] = 0; + //go through the user data and update the mixer matrix for (i=0;i<6;i++) { - if (MixerChannelData[i]<8) + if (MixerChannelData[i]>0) { //set the mixer type - *(mixerTypes[MixerChannelData[i]]) = i==0 ? + *(mixerTypes[MixerChannelData[i] - 1]) = i==0 ? MixerSettings::MIXER1TYPE_MOTOR : MixerSettings::MIXER1TYPE_SERVO; //config the vector for (j=0;j<5;j++) - mixers[MixerChannelData[i]][j] = m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt(); + mixers[MixerChannelData[i] - 1][j] = m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt(); } } @@ -1302,7 +1233,7 @@ void ConfigccpmWidget::sendccpmUpdate() //mapping of collective input to curve 2... //MixerSettings.Curve2Source = Throttle,Roll,Pitch,Yaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5 //check if we are using throttle or directly from a channel... - if (GUIConfigData.heli.ccpmCollectivePassthroughState) + if (m_ccpm->ccpmCollectivePassthrough->isChecked()) mixerSettingsData.Curve2Source = MixerSettings::CURVE2SOURCE_COLLECTIVE; else mixerSettingsData.Curve2Source = MixerSettings::CURVE2SOURCE_THROTTLE; @@ -1316,18 +1247,19 @@ void ConfigccpmWidget::sendccpmUpdate() /** Send ccpm type to the board and request saving to SD card */ -void ConfigccpmWidget::saveccpmUpdate() +void ConfigCcpmWidget::saveccpmUpdate() { if (SwashLvlConfigurationInProgress)return; ShowDisclaimer(0); // Send update so that the latest value is saved - sendccpmUpdate(); + //sendccpmUpdate(); + setMixer(); UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(obj); saveObjectToSD(obj); } -void ConfigccpmWidget::resizeEvent(QResizeEvent* event) +void ConfigCcpmWidget::resizeEvent(QResizeEvent* event) { Q_UNUSED(event); // Make the custom table columns autostretch: @@ -1339,7 +1271,7 @@ void ConfigccpmWidget::resizeEvent(QResizeEvent* event) ccpmSwashplateRedraw(); } -void ConfigccpmWidget::showEvent(QShowEvent *event) +void ConfigCcpmWidget::showEvent(QShowEvent *event) { Q_UNUSED(event) m_ccpm->ccpmAdvancedSettingsTable->resizeColumnsToContents(); @@ -1351,7 +1283,7 @@ void ConfigccpmWidget::showEvent(QShowEvent *event) } -void ConfigccpmWidget::SwashLvlStartButtonPressed() +void ConfigCcpmWidget::SwashLvlStartButtonPressed() { QMessageBox msgBox; int i; @@ -1388,7 +1320,8 @@ void ConfigccpmWidget::SwashLvlStartButtonPressed() //download the current settings to the OP hw - sendccpmUpdate(); + //sendccpmUpdate(); + setMixer(); //change control mode to gcs control / disarmed //set throttle to 0 @@ -1413,10 +1346,10 @@ void ConfigccpmWidget::SwashLvlStartButtonPressed() oldSwashLvlConfiguration.ServoChannels[2]=m_ccpm->ccpmServoYChannel->currentIndex(); oldSwashLvlConfiguration.ServoChannels[3]=m_ccpm->ccpmServoZChannel->currentIndex(); //if servos are used - oldSwashLvlConfiguration.Used[0]=((m_ccpm->ccpmServoWChannel->currentIndex()<8)&&(m_ccpm->ccpmServoWChannel->isEnabled())); - oldSwashLvlConfiguration.Used[1]=((m_ccpm->ccpmServoXChannel->currentIndex()<8)&&(m_ccpm->ccpmServoXChannel->isEnabled())); - oldSwashLvlConfiguration.Used[2]=((m_ccpm->ccpmServoYChannel->currentIndex()<8)&&(m_ccpm->ccpmServoYChannel->isEnabled())); - oldSwashLvlConfiguration.Used[3]=((m_ccpm->ccpmServoZChannel->currentIndex()<8)&&(m_ccpm->ccpmServoZChannel->isEnabled())); + oldSwashLvlConfiguration.Used[0]=((m_ccpm->ccpmServoWChannel->currentIndex()>0)&&(m_ccpm->ccpmServoWChannel->isEnabled())); + oldSwashLvlConfiguration.Used[1]=((m_ccpm->ccpmServoXChannel->currentIndex()>0)&&(m_ccpm->ccpmServoXChannel->isEnabled())); + oldSwashLvlConfiguration.Used[2]=((m_ccpm->ccpmServoYChannel->currentIndex()>0)&&(m_ccpm->ccpmServoYChannel->isEnabled())); + oldSwashLvlConfiguration.Used[3]=((m_ccpm->ccpmServoZChannel->currentIndex()>0)&&(m_ccpm->ccpmServoZChannel->isEnabled())); //min,neutral,max values for the servos for (i=0;i

Warning!!!

"); @@ -1693,7 +1626,7 @@ int ConfigccpmWidget::ShowDisclaimer(int messageID) Toggles the channel testing mode by making the GCS take over the ActuatorCommand objects */ -void ConfigccpmWidget::enableSwashplateLevellingControl(bool state) +void ConfigCcpmWidget::enableSwashplateLevellingControl(bool state) { ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); @@ -1703,10 +1636,10 @@ void ConfigccpmWidget::enableSwashplateLevellingControl(bool state) if (state) { SwashLvlaccInitialData = mdata; - mdata.flightAccess = UAVObject::ACCESS_READONLY; - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; - mdata.gcsTelemetryAcked = false; - mdata.gcsTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY); + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE); + UAVObject::SetGcsTelemetryAcked(mdata, false); + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE); mdata.gcsTelemetryUpdatePeriod = 100; SwashLvlConfigurationInProgress=1; m_ccpm->TabObject->setTabEnabled(0,0); @@ -1733,7 +1666,7 @@ void ConfigccpmWidget::enableSwashplateLevellingControl(bool state) Sets the swashplate level to a given value based on current settings for Max, Neutral and Min values. level ranges -1 to +1 */ -void ConfigccpmWidget::setSwashplateLevel(int percent) +void ConfigCcpmWidget::setSwashplateLevel(int percent) { if (percent<0)return;// -1; if (percent>100)return;// -1; @@ -1768,7 +1701,7 @@ return; } -void ConfigccpmWidget::SwashLvlSpinBoxChanged(int value) +void ConfigCcpmWidget::SwashLvlSpinBoxChanged(int value) { Q_UNUSED(value); int i; @@ -1808,3 +1741,63 @@ void ConfigccpmWidget::SwashLvlSpinBoxChanged(int value) return; } + +/** + This function displays text and color formatting in order to help the user understand what channels have not yet been configured. + */ +void ConfigCcpmWidget::throwConfigError(QString airframeType) +{ + Q_UNUSED(airframeType); + + if((m_ccpm->ccpmServoWChannel->currentIndex()==0)&&(m_ccpm->ccpmServoWChannel->isEnabled())) + { + m_ccpm->ccpmServoWLabel->setText("Servo W"); + } + else + { + m_ccpm->ccpmServoWLabel->setText("Servo W"); + } + if((m_ccpm->ccpmServoXChannel->currentIndex()==0)&&(m_ccpm->ccpmServoXChannel->isEnabled())) + { + m_ccpm->ccpmServoXLabel->setText("Servo X"); + } + else + { + m_ccpm->ccpmServoXLabel->setText("Servo X"); + } + if((m_ccpm->ccpmServoYChannel->currentIndex()==0)&&(m_ccpm->ccpmServoYChannel->isEnabled())) + { + m_ccpm->ccpmServoYLabel->setText("Servo Y"); + } + else + { + m_ccpm->ccpmServoYLabel->setText("Servo Y"); + } + if((m_ccpm->ccpmServoZChannel->currentIndex()==0)&&(m_ccpm->ccpmServoZChannel->isEnabled())) + { + m_ccpm->ccpmServoZLabel->setText("Servo Z"); + } + else + { + m_ccpm->ccpmServoZLabel->setText("Servo Z"); + } + + if((m_ccpm->ccpmEngineChannel->currentIndex()==0)&&(m_ccpm->ccpmEngineChannel->isEnabled())) + { + m_ccpm->ccpmEngineLabel->setText("Engine"); + } + else + { + m_ccpm->ccpmEngineLabel->setText("Engine"); + } + + if((m_ccpm->ccpmTailChannel->currentIndex()==0)&&(m_ccpm->ccpmTailChannel->isEnabled())) + { + m_ccpm->ccpmTailLabel->setText("Tail Rotor"); + } + else + { + m_ccpm->ccpmTailLabel->setText("Tail Rotor"); + } + +} diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h index 31a5e227d..3dceadcda 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h @@ -29,6 +29,7 @@ #include "ui_ccpm.h" #include "../uavobjectwidgetutils/configtaskwidget.h" +#include "cfg_vehicletypes/vehicleconfig.h" #include "extensionsystem/pluginmanager.h" #include "uavobjectmanager.h" #include "uavobject.h" @@ -50,36 +51,14 @@ typedef struct { int Min[CCPM_MAX_SWASH_SERVOS]; } SwashplateServoSettingsStruct; -typedef struct { - uint SwasplateType:3; - uint FirstServoIndex:2; - uint CorrectionAngle:9; - uint ccpmCollectivePassthroughState:1; - uint ccpmLinkCyclicState:1; - uint ccpmLinkRollState:1; - uint SliderValue0:7; - uint SliderValue1:7; - uint SliderValue2:7;//41bits - uint ServoIndexW:4; - uint ServoIndexX:4; - uint ServoIndexY:4; - uint ServoIndexZ:4;//57bits - uint padding:7; -} __attribute__((packed)) heliGUISettingsStruct; -typedef union -{ - uint UAVObject[2];//32bits * 2 - heliGUISettingsStruct heli;//64bits -} GUIConfigDataUnion; - -class ConfigccpmWidget: public ConfigTaskWidget +class ConfigCcpmWidget: public VehicleConfig { Q_OBJECT public: - ConfigccpmWidget(QWidget *parent = 0); - ~ConfigccpmWidget(); + ConfigCcpmWidget(QWidget *parent = 0); + ~ConfigCcpmWidget(); friend class ConfigVehicleTypeWidget; @@ -87,14 +66,6 @@ private: Ui_ccpmWidget *m_ccpm; QGraphicsSvgItem *SwashplateImg; QGraphicsSvgItem *CurveImg; - //QGraphicsSvgItem *ServoW; - //QGraphicsSvgItem *ServoX; - //QGraphicsSvgItem *ServoY; - //QGraphicsSvgItem *ServoZ; - //QGraphicsTextItem *ServoWText; - //QGraphicsTextItem *ServoXText; - //QGraphicsTextItem *ServoYText; - //QGraphicsTextItem *ServoZText; QGraphicsSvgItem *Servos[CCPM_MAX_SWASH_SERVOS]; QGraphicsTextItem *ServosText[CCPM_MAX_SWASH_SERVOS]; QGraphicsLineItem *ServoLines[CCPM_MAX_SWASH_SERVOS]; @@ -109,8 +80,6 @@ private: SwashplateServoSettingsStruct oldSwashLvlConfiguration; SwashplateServoSettingsStruct newSwashLvlConfiguration; - GUIConfigDataUnion GUIConfigData; - int MixerChannelData[6]; int ShowDisclaimer(int messageID); virtual void enableControls(bool enable) { Q_UNUSED(enable)}; // Not used by this widget @@ -118,7 +87,16 @@ private: bool updatingFromHardware; bool updatingToHardware; + virtual void ResetActuators(GUIConfigDataUnion* configData); + virtual QStringList getChannelDescriptions(); + + QString updateConfigObjects(); private slots: + virtual void setupUI(QString airframeType); + virtual void refreshWidgetsValues(QString frameType); + virtual QString updateConfigObjectsFromWidgets(); + virtual void throwConfigError(QString airframeType); + void ccpmSwashplateUpdate(); void ccpmSwashplateRedraw(); void UpdateCurveSettings(); @@ -135,11 +113,10 @@ private: void SwashLvlCancelButtonPressed(); void SwashLvlFinishButtonPressed(); - void UpdateCCPMOptionsFromUI(); - void UpdateCCPMUIFromOptions(); + //void UpdateCCPMOptionsFromUI(); + //void UpdateCCPMUIFromOptions(); void SetUIComponentVisibilities(); - void ccpmChannelCheck(); void enableSwashplateLevellingControl(bool state); void setSwashplateLevel(int percent); @@ -147,8 +124,8 @@ private: virtual void refreshValues() {}; // Not used public slots: - void requestccpmUpdate(); - void sendccpmUpdate(); + void getMixer(); + void setMixer(); void saveccpmUpdate(); protected: diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 7c641acfa..cbb7f94cf 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -24,7 +24,7 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -//#include "configfixedwingwidget.h" +#include "configfixedwingwidget.h" #include "configvehicletypewidget.h" #include "mixersettings.h" @@ -40,18 +40,38 @@ #include "mixersettings.h" #include "systemsettings.h" +#include "actuatorsettings.h" #include "actuatorcommand.h" /** - Helper function to setup the UI + Constructor */ -void ConfigVehicleTypeWidget::setupFixedWingUI(QString frameType) +ConfigFixedWingWidget::ConfigFixedWingWidget(Ui_AircraftWidget *aircraft, QWidget *parent) : VehicleConfig(parent) { + m_aircraft = aircraft; +} + +/** + Destructor + */ +ConfigFixedWingWidget::~ConfigFixedWingWidget() +{ + // Do nothing +} + + +/** + Virtual function to setup the UI + */ +void ConfigFixedWingWidget::setupUI(QString frameType) +{ + Q_ASSERT(m_aircraft); + if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") { // Setup the UI - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Fixed Wing")); - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); + setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Fixed Wing")); + setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder")); m_aircraft->fwRudder1ChannelBox->setEnabled(true); m_aircraft->fwRudder1Label->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); @@ -72,8 +92,8 @@ void ConfigVehicleTypeWidget::setupFixedWingUI(QString frameType) m_aircraft->elevonMixBox->setHidden(true); } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Fixed Wing")); - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevon")); + setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Fixed Wing")); + setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); m_aircraft->fwAileron1Label->setText("Elevon 1"); m_aircraft->fwAileron2Label->setText("Elevon 2"); m_aircraft->fwElevator1ChannelBox->setEnabled(false); @@ -91,8 +111,8 @@ void ConfigVehicleTypeWidget::setupFixedWingUI(QString frameType) m_aircraft->elevonLabel2->setText("Pitch"); } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Fixed Wing")); - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Vtail")); + setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Fixed Wing")); + setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); m_aircraft->fwRudder1ChannelBox->setEnabled(false); m_aircraft->fwRudder1Label->setEnabled(false); m_aircraft->fwRudder2ChannelBox->setEnabled(false); @@ -111,32 +131,71 @@ void ConfigVehicleTypeWidget::setupFixedWingUI(QString frameType) } } +void ConfigFixedWingWidget::ResetActuators(GUIConfigDataUnion* configData) +{ + configData->fixedwing.FixedWingPitch1 = 0; + configData->fixedwing.FixedWingPitch2 = 0; + configData->fixedwing.FixedWingRoll1 = 0; + configData->fixedwing.FixedWingRoll2 = 0; + configData->fixedwing.FixedWingYaw1 = 0; + configData->fixedwing.FixedWingYaw2 = 0; + configData->fixedwing.FixedWingThrottle = 0; +} +QStringList ConfigFixedWingWidget::getChannelDescriptions() +{ + int i; + QStringList channelDesc; + + // init a channel_numelem list of channel desc defaults + for (i=0; i < (int)(ConfigFixedWingWidget::CHANNEL_NUMELEM); i++) + { + channelDesc.append(QString("-")); + } + + // get the gui config data + GUIConfigDataUnion configData = GetConfigData(); + + if (configData.fixedwing.FixedWingPitch1 > 0) + channelDesc[configData.fixedwing.FixedWingPitch1-1] = QString("FixedWingPitch1"); + if (configData.fixedwing.FixedWingPitch2 > 0) + channelDesc[configData.fixedwing.FixedWingPitch2-1] = QString("FixedWingPitch2"); + if (configData.fixedwing.FixedWingRoll1 > 0) + channelDesc[configData.fixedwing.FixedWingRoll1-1] = QString("FixedWingRoll1"); + if (configData.fixedwing.FixedWingRoll2 > 0) + channelDesc[configData.fixedwing.FixedWingRoll2-1] = QString("FixedWingRoll2"); + if (configData.fixedwing.FixedWingYaw1 > 0) + channelDesc[configData.fixedwing.FixedWingYaw1-1] = QString("FixedWingYaw1"); + if (configData.fixedwing.FixedWingYaw2 > 0) + channelDesc[configData.fixedwing.FixedWingYaw2-1] = QString("FixedWingYaw2"); + if (configData.fixedwing.FixedWingThrottle > 0) + channelDesc[configData.fixedwing.FixedWingThrottle-1] = QString("FixedWingThrottle"); + + return channelDesc; +} /** - Helper function to update the UI widget objects + Virtual function to update the UI widget objects */ -QString ConfigVehicleTypeWidget::updateFixedWingObjectsFromWidgets() +QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() { QString airframeType = "FixedWing"; // Save the curve (common to all Fixed wing frames) - UAVDataObject *obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + // Remove Feed Forward, it is pointless on a plane: - UAVObjectField* field = obj->getField(QString("FeedForward")); + UAVObjectField* field = mixer->getField(QString("FeedForward")); field->setDouble(0); - field = obj->getField("ThrottleCurve1"); - QList curve = m_aircraft->fixedWingThrottle->getCurve(); - for (int i=0;isetValue(curve.at(i),i); - } - + // Set the throttle curve + setThrottleCurve(mixer,VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve()); + //All airframe types must start with "FixedWing" if (m_aircraft->fixedWingType->currentText() == "Elevator aileron rudder" ) { airframeType = "FixedWing"; - setupFrameFixedWing( airframeType ); + setupFrameFixedWing( airframeType ); } else if (m_aircraft->fixedWingType->currentText() == "Elevon") { airframeType = "FixedWingElevon"; setupFrameElevon( airframeType ); @@ -144,81 +203,50 @@ QString ConfigVehicleTypeWidget::updateFixedWingObjectsFromWidgets() airframeType = "FixedWingVtail"; setupFrameVtail( airframeType ); } - - // Now reflect those settings in the "Custom" panel as well - updateCustomAirframeUI(); - + return airframeType; } /** - Helper function to refresh the UI widget values + Virtual function to refresh the UI widget values */ -void ConfigVehicleTypeWidget::refreshFixedWingWidgetsValues(QString frameType) +void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) { - - UAVDataObject* obj; - UAVObjectField *field; - - // Then retrieve how channels are setup - obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - field = obj->getField(QString("FixedWingThrottle")); - Q_ASSERT(field); - m_aircraft->fwEngineChannelBox->setCurrentIndex(m_aircraft->fwEngineChannelBox->findText(field->getValue().toString())); + Q_ASSERT(m_aircraft); - field = obj->getField(QString("FixedWingRoll1")); - Q_ASSERT(field); - m_aircraft->fwAileron1ChannelBox->setCurrentIndex(m_aircraft->fwAileron1ChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("FixedWingRoll2")); - Q_ASSERT(field); - m_aircraft->fwAileron2ChannelBox->setCurrentIndex(m_aircraft->fwAileron2ChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("FixedWingPitch1")); - Q_ASSERT(field); - m_aircraft->fwElevator1ChannelBox->setCurrentIndex(m_aircraft->fwElevator1ChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("FixedWingPitch2")); - Q_ASSERT(field); - m_aircraft->fwElevator2ChannelBox->setCurrentIndex(m_aircraft->fwElevator2ChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("FixedWingYaw1")); - Q_ASSERT(field); - m_aircraft->fwRudder1ChannelBox->setCurrentIndex(m_aircraft->fwRudder1ChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("FixedWingYaw2")); - Q_ASSERT(field); - m_aircraft->fwRudder2ChannelBox->setCurrentIndex(m_aircraft->fwRudder2ChannelBox->findText(field->getValue().toString())); - + GUIConfigDataUnion config = GetConfigData(); + fixedGUISettingsStruct fixed = config.fixedwing; + + // Then retrieve how channels are setup + setComboCurrentIndex(m_aircraft->fwEngineChannelBox, fixed.FixedWingThrottle); + setComboCurrentIndex(m_aircraft->fwAileron1ChannelBox, fixed.FixedWingRoll1); + setComboCurrentIndex(m_aircraft->fwAileron2ChannelBox, fixed.FixedWingRoll2); + setComboCurrentIndex(m_aircraft->fwElevator1ChannelBox, fixed.FixedWingPitch1); + setComboCurrentIndex(m_aircraft->fwElevator2ChannelBox, fixed.FixedWingPitch2); + setComboCurrentIndex(m_aircraft->fwRudder1ChannelBox, fixed.FixedWingYaw1); + setComboCurrentIndex(m_aircraft->fwRudder2ChannelBox, fixed.FixedWingYaw2); + + UAVDataObject* mixer= dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + + int channel; if (frameType == "FixedWingElevon") { // If the airframe is elevon, restore the slider setting - // Find the channel number for Elevon1 (FixedWingRoll1) - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); - int chMixerNumber = m_aircraft->fwAileron1ChannelBox->currentIndex()-1; - if (chMixerNumber >= 0) { // If for some reason the actuators were incoherent, we might fail here, hence the check. - field = obj->getField(mixerVectors.at(chMixerNumber)); - int ti = field->getElementNames().indexOf("Roll"); - m_aircraft->elevonSlider1->setValue(field->getDouble(ti)*100); - ti = field->getElementNames().indexOf("Pitch"); - m_aircraft->elevonSlider2->setValue(field->getDouble(ti)*100); + // Find the channel number for Elevon1 (FixedWingRoll1) + channel = m_aircraft->fwAileron1ChannelBox->currentIndex()-1; + if (channel > -1) { // If for some reason the actuators were incoherent, we might fail here, hence the check. + m_aircraft->elevonSlider1->setValue(getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_ROLL)*100); + m_aircraft->elevonSlider2->setValue(getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_PITCH)*100); } } - if (frameType == "FixedWingVtail") { - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); - int chMixerNumber = m_aircraft->fwElevator1ChannelBox->currentIndex()-1; - if (chMixerNumber >=0) { - field = obj->getField(mixerVectors.at(chMixerNumber)); - int ti = field->getElementNames().indexOf("Yaw"); - m_aircraft->elevonSlider1->setValue(field->getDouble(ti)*100); - ti = field->getElementNames().indexOf("Pitch"); - m_aircraft->elevonSlider2->setValue(field->getDouble(ti)*100); - } - } - + if (frameType == "FixedWingVtail") { + channel = m_aircraft->fwElevator1ChannelBox->currentIndex()-1; + if (channel > -1) { // If for some reason the actuators were incoherent, we might fail here, hence the check. + m_aircraft->elevonSlider1->setValue(getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_YAW)*100); + m_aircraft->elevonSlider2->setValue(getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_PITCH)*100); + } + } } @@ -230,11 +258,11 @@ void ConfigVehicleTypeWidget::refreshFixedWingWidgetsValues(QString frameType) Returns False if impossible to create the mixer. */ -bool ConfigVehicleTypeWidget::setupFrameFixedWing(QString airframeType) +bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType) { // Check coherence: //Show any config errors in GUI - throwFixedWingChannelConfigError(airframeType); + throwConfigError(airframeType); // - At least Pitch and either Roll or Yaw if (m_aircraft->fwEngineChannelBox->currentText() == "None" || @@ -245,118 +273,70 @@ bool ConfigVehicleTypeWidget::setupFrameFixedWing(QString airframeType) // m_aircraft->fwStatusLabel->setText("ERROR: check channel assignment"); return false; } - // Now setup the channels: - resetActuators(); - - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - - // Elevator - UAVObjectField *field = obj->getField("FixedWingPitch1"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwElevator1ChannelBox->currentText()); - field = obj->getField("FixedWingPitch2"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwElevator2ChannelBox->currentText()); - // Aileron - field = obj->getField("FixedWingRoll1"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwAileron1ChannelBox->currentText()); - field = obj->getField("FixedWingRoll2"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwAileron2ChannelBox->currentText()); - - // Rudder - field = obj->getField("FixedWingYaw1"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwRudder1ChannelBox->currentText()); - - // Throttle - field = obj->getField("FixedWingThrottle"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwEngineChannelBox->currentText()); + // Now setup the channels: - obj->updated(); + GUIConfigDataUnion config = GetConfigData(); + ResetActuators(&config); + + config.fixedwing.FixedWingPitch1 = m_aircraft->fwElevator1ChannelBox->currentIndex(); + config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex(); + config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); + config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); + config.fixedwing.FixedWingYaw1 = m_aircraft->fwRudder1ChannelBox->currentIndex(); + config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); + + SetConfigData(config); - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + // ... and compute the matrix: // In order to make code a bit nicer, we assume: // - Channel dropdowns start with 'None', then 0 to 7 - + // 1. Assign the servo/motor/none for each channel - // Disable all - foreach(QString mixer, mixerTypes) { - field = obj->getField(mixer); - Q_ASSERT(field); - field->setValue("Disabled"); + + int channel; + //disable all + for (channel=0; channelfwEngineChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Motor"); - field = obj->getField(mixerVectors.at(tmpVal)); - // First of all reset the vector - resetField(field); - int ti = field->getElementNames().indexOf("ThrottleCurve1"); - field->setValue(127, ti); - - // Rudder - tmpVal = m_aircraft->fwRudder1ChannelBox->currentIndex()-1; - // tmpVal will be -1 if rudder is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue(127, ti); - } // Else: we have no rudder, only ailerons, we're fine with it. - - // Ailerons - tmpVal = m_aircraft->fwAileron1ChannelBox->currentIndex()-1; - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Roll"); - field->setValue(127, ti); - // Only set Aileron 2 if Aileron 1 is defined - tmpVal = m_aircraft->fwAileron2ChannelBox->currentIndex()-1; - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Roll"); - field->setValue(127, ti); - } - } // Else we have no ailerons. Our consistency check guarantees we have - // rudder in this case, so we're fine with it too. - - // Elevator - tmpVal = m_aircraft->fwElevator1ChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Pitch"); - field->setValue(127, ti); - // Only set Elevator 2 if it is defined - tmpVal = m_aircraft->fwElevator2ChannelBox->currentIndex()-1; - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Pitch"); - field->setValue(127, ti); + + //motor + channel = m_aircraft->fwEngineChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_MOTOR); + setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + + //rudder + channel = m_aircraft->fwRudder1ChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + //ailerons + channel = m_aircraft->fwAileron1ChannelBox->currentIndex()-1; + if (channel > -1) { + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); + + channel = m_aircraft->fwAileron2ChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); } - - obj->updated(); + + //elevators + channel = m_aircraft->fwElevator1ChannelBox->currentIndex()-1; + if (channel > -1) { + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, 127); + + channel = m_aircraft->fwElevator2ChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, 127); + } + m_aircraft->fwStatusLabel->setText("Mixer generated"); return true; @@ -367,11 +347,11 @@ bool ConfigVehicleTypeWidget::setupFrameFixedWing(QString airframeType) /** Setup Elevon */ -bool ConfigVehicleTypeWidget::setupFrameElevon(QString airframeType) +bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) { // Check coherence: //Show any config errors in GUI - throwFixedWingChannelConfigError(airframeType); + throwConfigError(airframeType); // - At least Aileron1 and Aileron 2, and engine if (m_aircraft->fwEngineChannelBox->currentText() == "None" || @@ -382,106 +362,67 @@ bool ConfigVehicleTypeWidget::setupFrameElevon(QString airframeType) return false; } - resetActuators(); - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - - // Elevons - UAVObjectField *field = obj->getField("FixedWingRoll1"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwAileron1ChannelBox->currentText()); - field = obj->getField("FixedWingRoll2"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwAileron2ChannelBox->currentText()); - // Rudder 1 (can be None) - field = obj->getField("FixedWingYaw1"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwRudder1ChannelBox->currentText()); - // Rudder 2 (can be None) - field = obj->getField("FixedWingYaw2"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwRudder2ChannelBox->currentText()); - // Throttle - field = obj->getField("FixedWingThrottle"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwEngineChannelBox->currentText()); - - obj->updated(); - + GUIConfigDataUnion config = GetConfigData(); + ResetActuators(&config); + + config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); + config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); + config.fixedwing.FixedWingYaw1 = m_aircraft->fwRudder1ChannelBox->currentIndex(); + config.fixedwing.FixedWingYaw2 = m_aircraft->fwRudder2ChannelBox->currentIndex(); + config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); + + SetConfigData(config); + + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + // Save the curve: - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); // ... and compute the matrix: // In order to make code a bit nicer, we assume: // - Channel dropdowns start with 'None', then 0 to 7 - + // 1. Assign the servo/motor/none for each channel - // Disable all - foreach(QString mixer, mixerTypes) { - field = obj->getField(mixer); - Q_ASSERT(field); - field->setValue("Disabled"); + + int channel; + double value; + //disable all + for (channel=0; channelfwEngineChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Motor"); - field = obj->getField(mixerVectors.at(tmpVal)); - // First of all reset the vector - resetField(field); - int ti = field->getElementNames().indexOf("ThrottleCurve1"); - field->setValue(127, ti); - - // Rudder 1 - tmpVal = m_aircraft->fwRudder1ChannelBox->currentIndex()-1; - // tmpVal will be -1 if rudder 1 is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue(127, ti); - } // Else: we have no rudder, only elevons, we're fine with it. - - // Rudder 2 - tmpVal = m_aircraft->fwRudder2ChannelBox->currentIndex()-1; - // tmpVal will be -1 if rudder 2 is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue(-127, ti); - } // Else: we have no rudder, only elevons, we're fine with it. - - tmpVal = m_aircraft->fwAileron1ChannelBox->currentIndex()-1; - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Pitch"); - field->setValue((double)m_aircraft->elevonSlider2->value()*1.27, ti); - ti = field->getElementNames().indexOf("Roll"); - field->setValue((double)m_aircraft->elevonSlider1->value()*1.27,ti); + + //motor + channel = m_aircraft->fwEngineChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_MOTOR); + setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + + //rudders + channel = m_aircraft->fwRudder1ChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + channel = m_aircraft->fwRudder2ChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); + + //ailerons + channel = m_aircraft->fwAileron1ChannelBox->currentIndex()-1; + if (channel > -1) { + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + value = (double)(m_aircraft->elevonSlider2->value()*1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value()*1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, value); + + channel = m_aircraft->fwAileron2ChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + value = (double)(m_aircraft->elevonSlider2->value()*1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value()*1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -value); } - - tmpVal = m_aircraft->fwAileron2ChannelBox->currentIndex()-1; - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Pitch"); - field->setValue((double)m_aircraft->elevonSlider2->value()*1.27, ti); - ti = field->getElementNames().indexOf("Roll"); - field->setValue(-(double)m_aircraft->elevonSlider1->value()*1.27,ti); - } - - obj->updated(); + m_aircraft->fwStatusLabel->setText("Mixer generated"); return true; } @@ -491,11 +432,11 @@ bool ConfigVehicleTypeWidget::setupFrameElevon(QString airframeType) /** Setup VTail */ -bool ConfigVehicleTypeWidget::setupFrameVtail(QString airframeType) +bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) { // Check coherence: //Show any config errors in GUI - throwFixedWingChannelConfigError(airframeType); + throwConfigError(airframeType); // - At least Pitch1 and Pitch2, and engine if (m_aircraft->fwEngineChannelBox->currentText() == "None" || @@ -506,97 +447,78 @@ bool ConfigVehicleTypeWidget::setupFrameVtail(QString airframeType) return false; } - resetActuators(); - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - - // Elevons - UAVObjectField *field = obj->getField("FixedWingPitch1"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwElevator1ChannelBox->currentText()); - field = obj->getField("FixedWingPitch2"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwElevator2ChannelBox->currentText()); - field = obj->getField("FixedWingRoll1"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwAileron1ChannelBox->currentText()); - field = obj->getField("FixedWingRoll2"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwAileron2ChannelBox->currentText()); - - // Throttle - field = obj->getField("FixedWingThrottle"); - Q_ASSERT(field); - field->setValue(m_aircraft->fwEngineChannelBox->currentText()); - - obj->updated(); - - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); + GUIConfigDataUnion config = GetConfigData(); + ResetActuators(&config); + + config.fixedwing.FixedWingPitch1 = m_aircraft->fwElevator1ChannelBox->currentIndex(); + config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex(); + config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); + config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); + config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); + + SetConfigData(config); + + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + + // Save the curve: // ... and compute the matrix: // In order to make code a bit nicer, we assume: // - Channel dropdowns start with 'None', then 0 to 7 - + // 1. Assign the servo/motor/none for each channel - // Disable all - foreach(QString mixer, mixerTypes) { - field = obj->getField(mixer); - Q_ASSERT(field); - field->setValue("Disabled"); + + int channel; + double value; + //disable all + for (channel=0; channelfwEngineChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Motor"); - field = obj->getField(mixerVectors.at(tmpVal)); - // First of all reset the vector - resetField(field); - int ti = field->getElementNames().indexOf("ThrottleCurve1"); - field->setValue(127, ti); - - tmpVal = m_aircraft->fwAileron1ChannelBox->currentIndex()-1; - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Roll"); - field->setValue(127,ti); + + //motor + channel = m_aircraft->fwEngineChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_MOTOR); + setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + + //rudders + channel = m_aircraft->fwRudder1ChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + channel = m_aircraft->fwRudder2ChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); + + //ailerons + channel = m_aircraft->fwAileron1ChannelBox->currentIndex()-1; + if (channel > -1) { + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); + + channel = m_aircraft->fwAileron2ChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127); } - - tmpVal = m_aircraft->fwAileron2ChannelBox->currentIndex()-1; - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Roll"); - field->setValue(-127,ti); + + //vtail + channel = m_aircraft->fwElevator1ChannelBox->currentIndex()-1; + if (channel > -1) { + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + value = (double)(m_aircraft->elevonSlider2->value()*1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value()*1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, value); + + channel = m_aircraft->fwElevator2ChannelBox->currentIndex()-1; + setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + value = (double)(m_aircraft->elevonSlider2->value()*1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value()*1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -value); } - - // Now compute the VTail - tmpVal = m_aircraft->fwElevator1ChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Pitch"); - field->setValue((double)m_aircraft->elevonSlider2->value()*1.27, ti); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue((double)m_aircraft->elevonSlider1->value()*1.27,ti); - - tmpVal = m_aircraft->fwElevator2ChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Pitch"); - field->setValue((double)m_aircraft->elevonSlider2->value()*1.27, ti); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue(-(double)m_aircraft->elevonSlider1->value()*1.27,ti); - - obj->updated(); + m_aircraft->fwStatusLabel->setText("Mixer generated"); return true; } @@ -604,7 +526,7 @@ bool ConfigVehicleTypeWidget::setupFrameVtail(QString airframeType) /** This function displays text and color formatting in order to help the user understand what channels have not yet been configured. */ -void ConfigVehicleTypeWidget::throwFixedWingChannelConfigError(QString airframeType) +void ConfigFixedWingWidget::throwConfigError(QString airframeType) { //Initialize configuration error flag bool error=false; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h new file mode 100644 index 000000000..8a39715f0 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -0,0 +1,74 @@ +/** + ****************************************************************************** + * + * @file configairframetwidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief Airframe configuration panel + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef CONFIGFIXEDWINGWIDGET_H +#define CONFIGFIXEDWINGWIDGET_H + +#include "ui_airframe.h" +#include "../uavobjectwidgetutils/configtaskwidget.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "uavobject.h" +#include "uavtalk/telemetrymanager.h" +#include +#include +#include + +class Ui_Widget; + +class ConfigFixedWingWidget: public VehicleConfig +{ + Q_OBJECT + +public: + ConfigFixedWingWidget(Ui_AircraftWidget *aircraft = 0, QWidget *parent = 0); + ~ConfigFixedWingWidget(); + + friend class ConfigVehicleTypeWidget; + +private: + Ui_AircraftWidget *m_aircraft; + + bool setupFrameFixedWing(QString airframeType); + bool setupFrameElevon(QString airframeType); + bool setupFrameVtail(QString airframeType); + + virtual void ResetActuators(GUIConfigDataUnion* configData); + virtual QStringList getChannelDescriptions(); + +private slots: + virtual void setupUI(QString airframeType); + virtual void refreshWidgetsValues(QString frameType); + virtual QString updateConfigObjectsFromWidgets(); + virtual void throwConfigError(QString airframeType); + + +protected: + +}; + + +#endif // CONFIGFIXEDWINGWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp index 67035ae39..1fc17cea0 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp @@ -24,7 +24,7 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -//#include "configgroundvehiclewidget.h" +#include "configgroundvehiclewidget.h" #include "configvehicletypewidget.h" #include "mixersettings.h" @@ -40,18 +40,35 @@ #include "mixersettings.h" #include "systemsettings.h" +#include "actuatorsettings.h" #include "actuatorcommand.h" /** - Helper function to setup the UI + Constructor */ -void ConfigVehicleTypeWidget::setupGroundVehicleUI(QString frameType) +ConfigGroundVehicleWidget::ConfigGroundVehicleWidget(Ui_AircraftWidget *aircraft, QWidget *parent) : VehicleConfig(parent) +{ + m_aircraft = aircraft; +} + +/** + Destructor + */ +ConfigGroundVehicleWidget::~ConfigGroundVehicleWidget() +{ + // Do nothing +} + +/** + Virtual function to setup the UI + */ +void ConfigGroundVehicleWidget::setupUI(QString frameType) { m_aircraft->differentialSteeringMixBox->setHidden(true); //STILL NEEDS WORK // Setup the UI - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Ground")); + setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Ground")); m_aircraft->gvEngineChannelBox->setEnabled(false); m_aircraft->gvEngineLabel->setEnabled(false); @@ -64,7 +81,7 @@ void ConfigVehicleTypeWidget::setupGroundVehicleUI(QString frameType) m_aircraft->gvAileron2Label->setEnabled(false); if (frameType == "GroundVehicleDifferential" || frameType == "Differential (tank)"){ //Tank - m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Differential (tank)")); + setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Differential (tank)")); m_aircraft->gvMotor1ChannelBox->setEnabled(true); m_aircraft->gvMotor1Label->setEnabled(true); @@ -89,7 +106,7 @@ void ConfigVehicleTypeWidget::setupGroundVehicleUI(QString frameType) } else if (frameType == "GroundVehicleMotorcycle" || frameType == "Motorcycle"){ //Motorcycle - m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Motorcycle")); + setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Motorcycle")); m_aircraft->gvMotor1ChannelBox->setEnabled(false); m_aircraft->gvMotor1Label->setEnabled(false); @@ -113,7 +130,7 @@ void ConfigVehicleTypeWidget::setupGroundVehicleUI(QString frameType) m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve"); } else {//Car - m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Turnable (car)")); + setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Turnable (car)")); m_aircraft->gvMotor1ChannelBox->setEnabled(true); m_aircraft->gvMotor1Label->setEnabled(true); @@ -137,12 +154,46 @@ void ConfigVehicleTypeWidget::setupGroundVehicleUI(QString frameType) } } +void ConfigGroundVehicleWidget::ResetActuators(GUIConfigDataUnion* configData) +{ + configData->ground.GroundVehicleSteering1 = 0; + configData->ground.GroundVehicleSteering2 = 0; + configData->ground.GroundVehicleThrottle1 = 0; + configData->ground.GroundVehicleThrottle2 = 0; +} + +QStringList ConfigGroundVehicleWidget::getChannelDescriptions() +{ + int i; + QStringList channelDesc; + + // init a channel_numelem list of channel desc defaults + for (i=0; i < (int)(ConfigGroundVehicleWidget::CHANNEL_NUMELEM); i++) + { + channelDesc.append(QString("-")); + } + + // get the gui config data + GUIConfigDataUnion configData = GetConfigData(); + + if (configData.ground.GroundVehicleSteering1 > 0) + channelDesc[configData.ground.GroundVehicleSteering1-1] = QString("GroundSteering1"); + if (configData.ground.GroundVehicleSteering2 > 0) + channelDesc[configData.ground.GroundVehicleSteering2-1] = QString("GroundSteering2"); + if (configData.ground.GroundVehicleThrottle1 > 0) + channelDesc[configData.ground.GroundVehicleThrottle1-1] = QString("GroundThrottle1"); + if (configData.ground.GroundVehicleThrottle2 > 0) + channelDesc[configData.ground.GroundVehicleThrottle2-1] = QString("GroundThrottle2"); + + return channelDesc; +} + /** - Helper function to update the UI widget objects + Virtual function to update the UI widget objects */ -QString ConfigVehicleTypeWidget::updateGroundVehicleObjectsFromWidgets() +QString ConfigGroundVehicleWidget::updateConfigObjectsFromWidgets() { QString airframeType = "GroundVehicleCar"; @@ -176,56 +227,29 @@ QString ConfigVehicleTypeWidget::updateGroundVehicleObjectsFromWidgets() airframeType = "GroundVehicleMotorcycle"; setupGroundVehicleMotorcycle(airframeType); } - - // Now reflect those settings in the "Custom" panel as well - updateCustomAirframeUI(); - + return airframeType; } /** - Helper function to refresh the UI widget values + Virtual function to refresh the UI widget values */ -void ConfigVehicleTypeWidget::refreshGroundVehicleWidgetsValues(QString frameType) +void ConfigGroundVehicleWidget::refreshWidgetsValues(QString frameType) { - UAVDataObject* obj; UAVObjectField *field; + GUIConfigDataUnion config = GetConfigData(); + //THIS SECTION STILL NEEDS WORK. FOR THE MOMENT, USE THE FIXED-WING ONBOARD SETTING IN ORDER TO MINIMIZE CHANCES OF BOLLOXING REAL CODE // Retrieve channel setup values - obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - field = obj->getField(QString("FixedWingThrottle")); - Q_ASSERT(field); - m_aircraft->gvEngineChannelBox->setCurrentIndex(m_aircraft->gvEngineChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("FixedWingRoll1")); - Q_ASSERT(field); - m_aircraft->gvAileron1ChannelBox->setCurrentIndex(m_aircraft->gvAileron1ChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("FixedWingRoll2")); - Q_ASSERT(field); - m_aircraft->gvAileron2ChannelBox->setCurrentIndex(m_aircraft->gvAileron2ChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("GroundVehicleThrottle1")); - Q_ASSERT(field); - m_aircraft->gvMotor1ChannelBox->setCurrentIndex(m_aircraft->gvMotor1ChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("GroundVehicleThrottle2")); - Q_ASSERT(field); - m_aircraft->gvMotor2ChannelBox->setCurrentIndex(m_aircraft->gvMotor2ChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("GroundVehicleSteering1")); - Q_ASSERT(field); - m_aircraft->gvSteering1ChannelBox->setCurrentIndex(m_aircraft->gvSteering1ChannelBox->findText(field->getValue().toString())); - - field = obj->getField(QString("GroundVehicleSteering2")); - Q_ASSERT(field); - m_aircraft->gvSteering2ChannelBox->setCurrentIndex(m_aircraft->gvSteering2ChannelBox->findText(field->getValue().toString())); - + setComboCurrentIndex(m_aircraft->gvMotor1ChannelBox, config.ground.GroundVehicleThrottle1); + setComboCurrentIndex(m_aircraft->gvMotor2ChannelBox, config.ground.GroundVehicleThrottle2); + setComboCurrentIndex(m_aircraft->gvSteering1ChannelBox, config.ground.GroundVehicleSteering1); + setComboCurrentIndex(m_aircraft->gvSteering2ChannelBox, config.ground.GroundVehicleSteering2); + if (frameType == "GroundVehicleDifferential") { //CURRENTLY BROKEN UNTIL WE DECIDE HOW DIFFERENTIAL SHOULD BEHAVE // If the vehicle type is "differential", restore the slider setting @@ -233,14 +257,11 @@ void ConfigVehicleTypeWidget::refreshGroundVehicleWidgetsValues(QString frameTyp // Find the channel number for Motor1 obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(obj); - int chMixerNumber = m_aircraft->gvMotor1ChannelBox->currentIndex()-1; - if (chMixerNumber >= 0) { // If for some reason the actuators were incoherent, we might fail here, hence the check. - field = obj->getField(mixerVectors.at(chMixerNumber)); - int ti = field->getElementNames().indexOf("Roll"); - m_aircraft->differentialSteeringSlider1->setValue(field->getDouble(ti)*100); - - ti = field->getElementNames().indexOf("Pitch"); - m_aircraft->differentialSteeringSlider2->setValue(field->getDouble(ti)*100); + int channel = m_aircraft->gvMotor1ChannelBox->currentIndex()-1; + if (channel > -1) { // If for some reason the actuators were incoherent, we might fail here, hence the check. + + m_aircraft->differentialSteeringSlider1->setValue(getMixerVectorValue(obj,channel,VehicleConfig::MIXERVECTOR_ROLL)*100); + m_aircraft->differentialSteeringSlider2->setValue(getMixerVectorValue(obj,channel,VehicleConfig::MIXERVECTOR_PITCH)*100); } } if (frameType == "GroundVehicleMotorcycle") { @@ -260,119 +281,62 @@ void ConfigVehicleTypeWidget::refreshGroundVehicleWidgetsValues(QString frameTyp } - - /** Setup balancing ground vehicle. Returns False if impossible to create the mixer. */ -bool ConfigVehicleTypeWidget::setupGroundVehicleMotorcycle(QString airframeType){ +bool ConfigGroundVehicleWidget::setupGroundVehicleMotorcycle(QString airframeType){ // Check coherence: //Show any config errors in GUI - throwGroundVehicleChannelConfigError(airframeType); + throwConfigError(airframeType); // - Motor, steering, and balance - if (m_aircraft->gvMotor1ChannelBox->currentText() == "None" || + if (m_aircraft->gvMotor2ChannelBox->currentText() == "None" || (m_aircraft->gvSteering1ChannelBox->currentText() == "None" || m_aircraft->gvSteering2ChannelBox->currentText() == "None") ) { return false; } - - // Now setup the channels: - resetActuators(); - - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - - // Left motor - UAVObjectField *field = obj->getField("GroundVehicleThrottle1"); - Q_ASSERT(field); - field->setValue(m_aircraft->gvMotor1ChannelBox->currentText()); - - // Right motor - field = obj->getField("GroundVehicleThrottle2"); - Q_ASSERT(field); - field->setValue(m_aircraft->gvMotor2ChannelBox->currentText()); - - obj->updated(); - - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); - // ... and compute the matrix: - // In order to make code a bit nicer, we assume: - // - Channel dropdowns start with 'None', then 0 to 7 - - // 1. Assign the servo/motor/none for each channel - - int tmpVal, ti; - - // Disable all output channels - foreach(QString mixer, mixerTypes) { - field = obj->getField(mixer); - Q_ASSERT(field); - - //Disable output channel - field->setValue("Disabled"); - - } - - // Set all mixer values to zero - foreach(QString mixer, mixerVectors) { - field = obj->getField(mixer); - resetField(field); - - ti = field->getElementNames().indexOf("ThrottleCurve1"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("ThrottleCurve2"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("Pitch"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("Roll"); - field->setValue(0, ti); - } - - // Motor - // Setup motor - tmpVal = m_aircraft->gvMotor2ChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); //Set motor mixer type to Servo - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("ThrottleCurve1"); //Set motor to full forward - field->setValue(127, ti); - - //Steering - // Setup steering - tmpVal = m_aircraft->gvSteering1ChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); //Set motor mixer type to Servo - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Yaw"); //Set steering response to roll - field->setValue(-127, ti); - ti = field->getElementNames().indexOf("Roll"); //Set steering response to roll - field->setValue(-127, ti); - //Balancing - // Setup balancing servo - tmpVal = m_aircraft->gvSteering2ChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); //Set motor mixer type to Servo - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Yaw"); //Set balance response to yaw - field->setValue(127, ti); - ti = field->getElementNames().indexOf("Roll"); //Set balance response to roll - field->setValue(127, ti); + // Now setup the channels: + GUIConfigDataUnion config = GetConfigData(); + ResetActuators(&config); + + config.ground.GroundVehicleThrottle1 = m_aircraft->gvMotor1ChannelBox->currentIndex(); + config.ground.GroundVehicleThrottle2 = m_aircraft->gvMotor2ChannelBox->currentIndex(); + + SetConfigData(config); - obj->updated(); - - //Output success message + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + + int channel; + //disable all + for (channel=0; channelgvMotor2ChannelBox->currentIndex()-1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + //steering + channel = m_aircraft->gvSteering1ChannelBox->currentIndex()-1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127); + + //balance + channel = m_aircraft->gvSteering2ChannelBox->currentIndex()-1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); + m_aircraft->gvStatusLabel->setText("Mixer generated"); return true; @@ -385,10 +349,10 @@ bool ConfigVehicleTypeWidget::setupGroundVehicleMotorcycle(QString airframeType) Returns False if impossible to create the mixer. */ -bool ConfigVehicleTypeWidget::setupGroundVehicleDifferential(QString airframeType){ +bool ConfigGroundVehicleWidget::setupGroundVehicleDifferential(QString airframeType){ // Check coherence: //Show any config errors in GUI - throwGroundVehicleChannelConfigError(airframeType); + throwConfigError(airframeType); // - Left and right steering if ( m_aircraft->gvMotor2ChannelBox->currentText() == "None" || @@ -397,86 +361,37 @@ bool ConfigVehicleTypeWidget::setupGroundVehicleDifferential(QString airframeTyp return false; } + + // Now setup the channels: + GUIConfigDataUnion config = GetConfigData(); + ResetActuators(&config); - // Now setup the channels: - resetActuators(); + config.ground.GroundVehicleThrottle1 = m_aircraft->gvMotor1ChannelBox->currentIndex(); + config.ground.GroundVehicleThrottle2 = m_aircraft->gvMotor2ChannelBox->currentIndex(); + + SetConfigData((config)); - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - - // Left motor - UAVObjectField *field = obj->getField("GroundVehicleThrottle1"); - Q_ASSERT(field); - field->setValue(m_aircraft->gvMotor1ChannelBox->currentText()); - - // Right motor - field = obj->getField("GroundVehicleThrottle2"); - Q_ASSERT(field); - field->setValue(m_aircraft->gvMotor2ChannelBox->currentText()); - - obj->updated(); - - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); - // ... and compute the matrix: - // In order to make code a bit nicer, we assume: - // - Channel dropdowns start with 'None', then 0 to 7 - - // 1. Assign the servo/motor/none for each channel - - int tmpVal, ti; - - // Disable all output channels - foreach(QString mixer, mixerTypes) { - field = obj->getField(mixer); - Q_ASSERT(field); - - //Disable output channel - field->setValue("Disabled"); - - } - - // Set all mixer values to zero - foreach(QString mixer, mixerVectors) { - field = obj->getField(mixer); - resetField(field); - - ti = field->getElementNames().indexOf("ThrottleCurve1"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("ThrottleCurve2"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("Pitch"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("Roll"); - field->setValue(0, ti); - } - - // Motor - // Setup left motor - tmpVal = m_aircraft->gvMotor1ChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); //Set motor mixer type to Servo - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("ThrottleCurve1"); //Set motor to full forward - field->setValue(127, ti); - ti = field->getElementNames().indexOf("Yaw"); //Set motor to turn right with increasing throttle - field->setValue(127, ti); - - // Setup right motor - tmpVal = m_aircraft->gvMotor2ChannelBox->currentIndex()-1; - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); //Set motor mixer type to Servo - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("ThrottleCurve2"); //Set motor to full forward - field->setValue(127, ti); - ti = field->getElementNames().indexOf("Yaw"); //Set motor to turn left with increasing throttle - field->setValue(-127, ti); - - obj->updated(); + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + + int channel; + //disable all + for (channel=0; channelgvMotor1ChannelBox->currentIndex()-1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + //right motor + channel = m_aircraft->gvMotor2ChannelBox->currentIndex()-1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2, 127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); //Output success message m_aircraft->gvStatusLabel->setText("Mixer generated"); @@ -492,11 +407,11 @@ bool ConfigVehicleTypeWidget::setupGroundVehicleDifferential(QString airframeTyp Returns False if impossible to create the mixer. */ -bool ConfigVehicleTypeWidget::setupGroundVehicleCar(QString airframeType) +bool ConfigGroundVehicleWidget::setupGroundVehicleCar(QString airframeType) { // Check coherence: //Show any config errors in GUI - throwGroundVehicleChannelConfigError(airframeType); + throwConfigError(airframeType); // - At least one motor and one steering servo if ((m_aircraft->gvMotor1ChannelBox->currentText() == "None" && @@ -506,147 +421,43 @@ bool ConfigVehicleTypeWidget::setupGroundVehicleCar(QString airframeType) { return false; } -// else{ -// // m_aircraft->gvStatusLabel->setText("Mixer generated"); -// QTextEdit* htmlText=new QTextEdit(m_aircraft->gvSteering1Label->text()); // HtmlText is any QString with html tags. -// m_aircraft->gvSteering1Label->setText(htmlText->toPlainText()); -// delete htmlText; -// -// htmlText=new QTextEdit(m_aircraft->gvSteering2Label->text()); // HtmlText is any QString with html tags. -// m_aircraft->gvSteering2Label->setText(htmlText->toPlainText()); -// delete htmlText; -// -// htmlText=new QTextEdit(m_aircraft->gvMotor1Label->text()); // HtmlText is any QString with html tags. -// m_aircraft->gvMotor1Label->setText(htmlText->toPlainText()); -// delete htmlText; -// -// htmlText=new QTextEdit(m_aircraft->gvMotor2Label->text()); // HtmlText is any QString with html tags. -// m_aircraft->gvMotor2Label->setText(htmlText->toPlainText()); -// } + + // Now setup the channels: + GUIConfigDataUnion config = GetConfigData(); + ResetActuators(&config); - // Now setup the channels: - resetActuators(); - - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - - // Front motor - UAVObjectField *field = obj->getField("GroundVehicleThrottle1"); - Q_ASSERT(field); - field->setValue(m_aircraft->gvMotor1ChannelBox->currentText()); - - // Rear motor - field = obj->getField("GroundVehicleThrottle2"); - Q_ASSERT(field); - field->setValue(m_aircraft->gvMotor2ChannelBox->currentText()); + config.ground.GroundVehicleThrottle1 = m_aircraft->gvMotor1ChannelBox->currentIndex(); + config.ground.GroundVehicleThrottle2 = m_aircraft->gvMotor2ChannelBox->currentIndex(); + config.ground.GroundVehicleSteering1 = m_aircraft->gvSteering1ChannelBox->currentIndex(); + config.ground.GroundVehicleSteering2 = m_aircraft->gvSteering2ChannelBox->currentIndex(); -// // Aileron -// field = obj->getField("FixedWingRoll1"); -// Q_ASSERT(field); -// field->setValue(m_aircraft->fwAileron1ChannelBox->currentText()); -// -// field = obj->getField("FixedWingRoll2"); -// Q_ASSERT(field); -// field->setValue(m_aircraft->fwAileron2ChannelBox->currentText()); + SetConfigData(config); - // Front steering - field = obj->getField("GroundVehicleSteering1"); - Q_ASSERT(field); - field->setValue(m_aircraft->gvSteering1ChannelBox->currentText()); + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); - // Rear steering - field = obj->getField("GroundVehicleSteering2"); - Q_ASSERT(field); - field->setValue(m_aircraft->gvSteering2ChannelBox->currentText()); - - obj->updated(); - - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); - // ... and compute the matrix: - // In order to make code a bit nicer, we assume: - // - Channel dropdowns start with 'None', then 0 to 7 - - // 1. Assign the servo/motor/none for each channel - - int tmpVal, ti; - - // Disable all output channels - foreach(QString mixer, mixerTypes) { - field = obj->getField(mixer); - Q_ASSERT(field); - - //Disable output channel - field->setValue("Disabled"); - - } - - // Set all mixer values to zero - foreach(QString mixer, mixerVectors) { - field = obj->getField(mixer); - resetField(field); - - ti = field->getElementNames().indexOf("ThrottleCurve1"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("ThrottleCurve2"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("Pitch"); - field->setValue(0, ti); - ti = field->getElementNames().indexOf("Roll"); - field->setValue(0, ti); - } - - // Steering - // Only set front steering if it is defined - tmpVal = m_aircraft->gvSteering1ChannelBox->currentIndex()-1; - // tmpVal will be -1 if steering is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue(127, ti); - } // Else: we have no front steering. We're fine with it as long as we have rear steering - - // Only set rear steering if it is defined - tmpVal = m_aircraft->gvSteering2ChannelBox->currentIndex()-1; - // tmpVal will be -1 if steering is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue(-127, ti); - } // Else: we have no rear steering. We're fine with it as long as we have front steering - - // Motor - // Only set front motor if it is defined - tmpVal = m_aircraft->gvMotor1ChannelBox->currentIndex()-1; - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("ThrottleCurve1"); - field->setValue(127, ti); - } - - // Only set rear motor if it is defined - tmpVal = m_aircraft->gvMotor2ChannelBox->currentIndex()-1; - if (tmpVal > -1) { - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - ti = field->getElementNames().indexOf("ThrottleCurve2"); - field->setValue(127, ti); + int channel; + //disable all + for (channel=0; channelupdated(); + + channel = m_aircraft->gvSteering1ChannelBox->currentIndex()-1; + setMixerType(mixer,channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + channel = m_aircraft->gvSteering2ChannelBox->currentIndex()-1; + setMixerType(mixer,channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); + + channel = m_aircraft->gvMotor1ChannelBox->currentIndex()-1; + setMixerType(mixer,channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + + channel = m_aircraft->gvMotor2ChannelBox->currentIndex()-1; + setMixerType(mixer,channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2, 127); //Output success message m_aircraft->gvStatusLabel->setText("Mixer generated"); @@ -657,7 +468,7 @@ bool ConfigVehicleTypeWidget::setupGroundVehicleCar(QString airframeType) /** This function displays text and color formatting in order to help the user understand what channels have not yet been configured. */ -void ConfigVehicleTypeWidget::throwGroundVehicleChannelConfigError(QString airframeType) +void ConfigGroundVehicleWidget::throwConfigError(QString airframeType) { //Initialize configuration error flag bool error=false; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h new file mode 100644 index 000000000..1e7b378e4 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h @@ -0,0 +1,74 @@ +/** + ****************************************************************************** + * + * @file configairframetwidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief Airframe configuration panel + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef CONFIGGROUNDVEHICLEWIDGET_H +#define CONFIGGROUNDVEHICLEWIDGET_H + +#include "ui_airframe.h" +#include "../uavobjectwidgetutils/configtaskwidget.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "uavobject.h" +#include "uavtalk/telemetrymanager.h" +#include +#include +#include + +class Ui_Widget; + +class ConfigGroundVehicleWidget: public VehicleConfig +{ + Q_OBJECT + +public: + ConfigGroundVehicleWidget(Ui_AircraftWidget *aircraft = 0, QWidget *parent = 0); + ~ConfigGroundVehicleWidget(); + + friend class ConfigVehicleTypeWidget; + +private: + Ui_AircraftWidget *m_aircraft; + + bool setupGroundVehicleCar(QString airframeType); + bool setupGroundVehicleDifferential(QString airframeType); + bool setupGroundVehicleMotorcycle(QString airframeType); + + virtual void ResetActuators(GUIConfigDataUnion* configData); + virtual QStringList getChannelDescriptions(); + +private slots: + virtual void setupUI(QString airframeType); + virtual void refreshWidgetsValues(QString frameType); + virtual QString updateConfigObjectsFromWidgets(); + virtual void throwConfigError(QString airframeType); + + +protected: + +}; + + +#endif // CONFIGGROUNDVEHICLEWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index c0d4972f0..5b390c0e3 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -24,9 +24,7 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -//#include "configmultirotorwidget.h" -#include "configvehicletypewidget.h" -#include "mixersettings.h" +#include "configmultirotorwidget.h" #include #include @@ -34,200 +32,192 @@ #include #include #include +#include #include #include #include #include "mixersettings.h" #include "systemsettings.h" +#include "actuatorsettings.h" #include "actuatorcommand.h" //#define Pi 3.14159265358979323846 /** - Helper function to setup the UI + Constructor */ -void ConfigVehicleTypeWidget::setupMultiRotorUI(QString frameType) +ConfigMultiRotorWidget::ConfigMultiRotorWidget(Ui_AircraftWidget *aircraft, QWidget *parent) : VehicleConfig(parent) { - if (frameType == "Tri" || frameType == "Tricopter Y") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor")); - m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Tricopter Y")); + m_aircraft = aircraft; +} + +/** + Destructor + */ +ConfigMultiRotorWidget::~ConfigMultiRotorWidget() +{ + // Do nothing +} + + +void ConfigMultiRotorWidget::setupUI(QString frameType) +{ + Q_ASSERT(m_aircraft); + Q_ASSERT(uiowner); + Q_ASSERT(quad); + + int i; + + // set aircraftType to Multirotor, disable triyaw channel + setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Multirotor")); + m_aircraft->triYawChannelBox->setEnabled(false); + + // disable all motor channel boxes + for (i=1; i <=8; i++) { + // do it manually so we can turn off any error decorations + QComboBox *combobox = qFindChild(uiowner, "multiMotorChannelBox" + QString::number(i)); + if (combobox) { + combobox->setEnabled(false); + combobox->setItemData(0, 0, Qt::DecorationRole); + } + } + + if (frameType == "Tri" || frameType == "Tricopter Y") { + setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y")); quad->setElementId("tri"); //Enable all necessary motor channel boxes... - for (int i=1; i <=3; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(true); - } - //and grey out all unused motor channel boxes - for (int i=4; i <=8; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(false); + for (i=1; i <=3; i++) { + enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); } - m_aircraft->triYawChannelBox->setEnabled(true); - } else if (frameType == "QuadX" || frameType == "Quad X") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor")); - m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Quad X")); + m_aircraft->triYawChannelBox->setEnabled(true); + } + else if (frameType == "QuadX" || frameType == "Quad X") { + setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); quad->setElementId("quad-X"); //Enable all necessary motor channel boxes... - for (int i=1; i <=4; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(true); + for (i=1; i <=4; i++) { + enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); } - //and grey out all unused motor channel boxes - for (int i=5; i <=8; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(false); - } - - m_aircraft->triYawChannelBox->setEnabled(false); + m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50); m_aircraft->mrYawMixLevel->setValue(50); - } else if (frameType == "QuadP" || frameType == "Quad +") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor")); - m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Quad +")); + } + else if (frameType == "QuadP" || frameType == "Quad +") { + setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); quad->setElementId("quad-plus"); //Enable all necessary motor channel boxes... - for (int i=1; i <=4; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(true); - } - //and grey out all unused motor channel boxes - for (int i=5; i <=8; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(false); + for (i=1; i <=4; i++) { + enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); } - m_aircraft->triYawChannelBox->setEnabled(false); m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); m_aircraft->mrYawMixLevel->setValue(50); - } else if (frameType == "Hexa" || frameType == "Hexacopter") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor")); - m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Hexacopter")); + } + else if (frameType == "Hexa" || frameType == "Hexacopter") + { + setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter")); quad->setElementId("quad-hexa"); //Enable all necessary motor channel boxes... - for (int i=1; i <=6; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(true); + for (i=1; i <=6; i++) { + enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); } - //and grey out all unused motor channel boxes - for (int i=7; i <=8; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(false); - } - - m_aircraft->triYawChannelBox->setEnabled(false); + m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(33); m_aircraft->mrYawMixLevel->setValue(33); - } else if (frameType == "HexaX" || frameType == "Hexacopter X" ) { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor")); - m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Hexacopter X")); + } + else if (frameType == "HexaX" || frameType == "Hexacopter X" ) { + setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter X")); quad->setElementId("quad-hexa-H"); //Enable all necessary motor channel boxes... - for (int i=1; i <=6; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(true); + for (i=1; i <=6; i++) { + enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); } - //and grey out all unused motor channel boxes - for (int i=7; i <=8; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(false); - } - - m_aircraft->triYawChannelBox->setEnabled(false); + m_aircraft->mrRollMixLevel->setValue(33); m_aircraft->mrPitchMixLevel->setValue(50); m_aircraft->mrYawMixLevel->setValue(33); - } else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor")); - m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); + } + else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") + { + setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); quad->setElementId("hexa-coax"); //Enable all necessary motor channel boxes... - for (int i=1; i <=6; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(true); + for (i=1; i <=6; i++) { + enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); } - //and grey out all unused motor channel boxes - for (int i=7; i <=8; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(false); - } - - m_aircraft->triYawChannelBox->setEnabled(false); + m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(50); m_aircraft->mrYawMixLevel->setValue(66); - } else if (frameType == "Octo" || frameType == "Octocopter") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor")); - m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Octocopter")); + } + else if (frameType == "Octo" || frameType == "Octocopter") + { + setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter")); quad->setElementId("quad-octo"); //Enable all necessary motor channel boxes - for (int i=1; i <=8; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(true); + for (i=1; i <=8; i++) { + enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); } - - m_aircraft->triYawChannelBox->setEnabled(false); + m_aircraft->mrRollMixLevel->setValue(33); m_aircraft->mrPitchMixLevel->setValue(33); m_aircraft->mrYawMixLevel->setValue(25); - } else if (frameType == "OctoV" || frameType == "Octocopter V") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor")); - m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Octocopter V")); + } + else if (frameType == "OctoV" || frameType == "Octocopter V") + { + setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter V")); quad->setElementId("quad-octo-v"); //Enable all necessary motor channel boxes - for (int i=1; i <=8; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(true); + for (i=1; i <=8; i++) { + enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); } - m_aircraft->triYawChannelBox->setEnabled(false); m_aircraft->mrRollMixLevel->setValue(25); m_aircraft->mrPitchMixLevel->setValue(25); m_aircraft->mrYawMixLevel->setValue(25); - } else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor")); - m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Octo Coax +")); + } + else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") + { + setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +")); quad->setElementId("octo-coax-P"); //Enable all necessary motor channel boxes - for (int i=1; i <=8; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(true); + for (int i=1; i <=8; i++) { + enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); } - m_aircraft->triYawChannelBox->setEnabled(false); m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); m_aircraft->mrYawMixLevel->setValue(50); - } else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor")); - m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Octo Coax X")); + } + else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") + { + setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X")); quad->setElementId("octo-coax-X"); //Enable all necessary motor channel boxes - for (int i=1; i <=8; i++) { - QComboBox *combobox = qFindChild(this, "multiMotorChannelBox" + QString::number(i)); - combobox->setEnabled(true); + for (int i=1; i <=8; i++) { + enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); } - m_aircraft->triYawChannelBox->setEnabled(false); m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50); m_aircraft->mrYawMixLevel->setValue(50); @@ -235,12 +225,61 @@ void ConfigVehicleTypeWidget::setupMultiRotorUI(QString frameType) } } +void ConfigMultiRotorWidget::ResetActuators(GUIConfigDataUnion* configData) +{ + configData->multi.VTOLMotorN = 0; + configData->multi.VTOLMotorNE = 0; + configData->multi.VTOLMotorE = 0; + configData->multi.VTOLMotorSE = 0; + configData->multi.VTOLMotorS = 0; + configData->multi.VTOLMotorSW = 0; + configData->multi.VTOLMotorW = 0; + configData->multi.VTOLMotorNW = 0; + configData->multi.TRIYaw = 0; +} + +QStringList ConfigMultiRotorWidget::getChannelDescriptions() +{ + int i; + QStringList channelDesc; + + // init a channel_numelem list of channel desc defaults + for (i=0; i < (int)(ConfigMultiRotorWidget::CHANNEL_NUMELEM); i++) + { + channelDesc.append(QString("-")); + } + + // get the gui config data + GUIConfigDataUnion configData = GetConfigData(); + multiGUISettingsStruct multi = configData.multi; + + if (multi.VTOLMotorN > 0 && multi.VTOLMotorN < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.VTOLMotorN-1] = QString("VTOLMotorN"); + if (multi.VTOLMotorNE > 0 && multi.VTOLMotorNE < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.VTOLMotorNE-1] = QString("VTOLMotorNE"); + if (multi.VTOLMotorNW > 0 && multi.VTOLMotorNW < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.VTOLMotorNW-1] = QString("VTOLMotorNW"); + if (multi.VTOLMotorS > 0 && multi.VTOLMotorS < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.VTOLMotorS-1] = QString("VTOLMotorS"); + if (multi.VTOLMotorSE > 0 && multi.VTOLMotorSE < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.VTOLMotorSE-1] = QString("VTOLMotorSE"); + if (multi.VTOLMotorSW > 0 && multi.VTOLMotorSW < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.VTOLMotorSW-1] = QString("VTOLMotorSW"); + if (multi.VTOLMotorW > 0 && multi.VTOLMotorW < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.VTOLMotorW-1] = QString("VTOLMotorW"); + if (multi.VTOLMotorE > 0 && multi.VTOLMotorE < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.VTOLMotorE-1] = QString("VTOLMotorE"); + + return channelDesc; +} + + /** Helper function to update the UI widget objects */ -QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() +QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() { QString airframeType; QList motorList; @@ -256,12 +295,8 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() field = obj->getField(QString("MaxAccel")); field->setDouble(m_aircraft->maxAccelSlider->value()); - // Curve is also common to all quads: - field = obj->getField("ThrottleCurve1"); - QList curve = m_aircraft->multiThrottleCurve->getCurve(); - for (int i=0;isetValue(curve.at(i),i); - } + // Curve is also common to all quads: + setThrottleCurve(obj, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->multiThrottleCurve->getCurve() ); if (m_aircraft->multirotorFrameType->currentText() == "Quad +") { airframeType = "QuadP"; @@ -279,7 +314,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() airframeType = "HexaCoax"; //Show any config errors in GUI - throwMultiRotorChannelConfigError(6); + throwConfigError(6); if (m_aircraft->multiMotorChannelBox1->currentText() == "None" || m_aircraft->multiMotorChannelBox2->currentText() == "None" || @@ -313,7 +348,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() airframeType = "Octo"; //Show any config errors in GUI - throwMultiRotorChannelConfigError(8); + throwConfigError(8); if (m_aircraft->multiMotorChannelBox1->currentText() == "None" || m_aircraft->multiMotorChannelBox2->currentText() == "None" || @@ -348,7 +383,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() airframeType = "OctoV"; //Show any config errors in GUI - throwMultiRotorChannelConfigError(8); + throwConfigError(8); if (m_aircraft->multiMotorChannelBox1->currentText() == "None" || m_aircraft->multiMotorChannelBox2->currentText() == "None" || @@ -384,7 +419,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() airframeType = "OctoCoaxP"; //Show any config errors in GUI - throwMultiRotorChannelConfigError(8); + throwConfigError(8); if (m_aircraft->multiMotorChannelBox1->currentText() == "None" || m_aircraft->multiMotorChannelBox2->currentText() == "None" || @@ -419,7 +454,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() airframeType = "OctoCoaxX"; //Show any config errors in GUI - throwMultiRotorChannelConfigError(8); + throwConfigError(8); if (m_aircraft->multiMotorChannelBox1->currentText() == "None" || m_aircraft->multiMotorChannelBox2->currentText() == "None" || @@ -454,7 +489,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() airframeType = "Tri"; //Show any config errors in GUI - throwMultiRotorChannelConfigError(3); + throwConfigError(3); if (m_aircraft->multiMotorChannelBox1->currentText() == "None" || m_aircraft->multiMotorChannelBox2->currentText() == "None" || m_aircraft->multiMotorChannelBox3->currentText() == "None" ) { @@ -467,10 +502,11 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() } motorList << "VTOLMotorNW" << "VTOLMotorNE" << "VTOLMotorS"; setupMotors(motorList); - obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - field = obj->getField("FixedWingYaw1"); - field->setValue(m_aircraft->triYawChannelBox->currentText()); + + GUIConfigDataUnion config = GetConfigData(); + config.multi.TRIYaw = m_aircraft->triYawChannelBox->currentIndex(); + SetConfigData(config); + // Motor 1 to 6, Y6 Layout: // pitch roll yaw @@ -485,21 +521,20 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() { 0, 0, 0} }; setupMultiRotorMixer(mixer); - - int tmpVal = m_aircraft->triYawChannelBox->currentIndex()-1; - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - field = obj->getField(mixerTypes.at(tmpVal)); - field->setValue("Servo"); - field = obj->getField(mixerVectors.at(tmpVal)); - resetField(field); - int ti = field->getElementNames().indexOf("Yaw"); - field->setValue(127,ti); + + //tell the mixer about tricopter yaw channel + UAVDataObject* mixerObj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixerObj); + + int channel = m_aircraft->triYawChannelBox->currentIndex()-1; + if (channel > -1){ + setMixerType(mixerObj, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixerObj, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + } m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); - } - // Now reflect those settings in the "Custom" panel as well - updateCustomAirframeUI(); + } return airframeType; } @@ -509,342 +544,253 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets() /** Helper function to refresh the UI widget values */ -void ConfigVehicleTypeWidget::refreshMultiRotorWidgetsValues(QString frameType) +void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) { - ////////////////////////////////////////////////////////////////// - // Retrieve settings - ////////////////////////////////////////////////////////////////// - - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - UAVObjectField *field; - + int channel; + double value; + + GUIConfigDataUnion config = GetConfigData(); + multiGUISettingsStruct multi = config.multi; + + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + if (frameType == "QuadP") { - // Motors 1/2/3/4 are: N / E / S / W - field = obj->getField(QString("VTOLMotorN")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorE")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorS")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorW")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - + // Motors 1/2/3/4 are: N / E / S / W + setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorS); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorW); + // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. // This assumes that all vectors are identical - if not, the user should use the // "custom" setting. - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); - int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1; - // tmpVal will be -1 if value is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerVectors.at(tmpVal)); - int i = field->getElementNames().indexOf("Pitch"); - double val = field->getDouble(i)/1.27; - m_aircraft->mrPitchMixLevel->setValue(val); - i = field->getElementNames().indexOf("Yaw"); - val = (1-field->getDouble(i)/1.27); - m_aircraft->mrYawMixLevel->setValue(val); - tmpVal = m_aircraft->multiMotorChannelBox2->currentIndex()-1; - field = obj->getField(mixerVectors.at(tmpVal)); - i = field->getElementNames().indexOf("Roll"); - val = -field->getDouble(i)/1.27; - m_aircraft->mrRollMixLevel->setValue(val); - } + + channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; + if (channel > -1) + { + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); + m_aircraft->mrPitchMixLevel->setValue( value/1.27 ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + m_aircraft->mrYawMixLevel->setValue( 1-value/1.27 ); + + channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + m_aircraft->mrRollMixLevel->setValue( -value/1.27); + + } } else if (frameType == "QuadX") { - // Motors 1/2/3/4 are: NW / NE / SE / SW - field = obj->getField(QString("VTOLMotorNW")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorNE")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSE")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSW")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); - int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1; - // tmpVal will be -1 if value is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerVectors.at(tmpVal)); - int i = field->getElementNames().indexOf("Pitch"); - double val = field->getDouble(i)/1.27; - m_aircraft->mrPitchMixLevel->setValue(val); - i = field->getElementNames().indexOf("Yaw"); - val = 1-field->getDouble(i)/1.27; - m_aircraft->mrYawMixLevel->setValue(val); - i = field->getElementNames().indexOf("Roll"); - val = field->getDouble(i)/1.27; - m_aircraft->mrRollMixLevel->setValue(val); - } + // Motors 1/2/3/4 are: NW / NE / SE / SW + setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorSE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorSW); + + // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. + // This assumes that all vectors are identical - if not, the user should use the + // "custom" setting. + channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; + if (channel > -1) + { + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); + m_aircraft->mrPitchMixLevel->setValue( value/1.27 ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + m_aircraft->mrYawMixLevel->setValue( 1-value/1.27 ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + m_aircraft->mrRollMixLevel->setValue( value/1.27); + + } + } else if (frameType == "Hexa") { // Motors 1/2/3 4/5/6 are: N / NE / SE / S / SW / NW - field = obj->getField(QString("VTOLMotorN")); - m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorNE")); - m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSE")); - m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorS")); - m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSW")); - m_aircraft->multiMotorChannelBox5->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorNW")); - m_aircraft->multiMotorChannelBox6->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1; - // tmpVal will be -1 if value is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerVectors.at(tmpVal)); - int i = field->getElementNames().indexOf("Pitch"); - double val = floor(field->getDouble(i)/1.27); - m_aircraft->mrPitchMixLevel->setValue(val); - i = field->getElementNames().indexOf("Yaw"); - val = floor(-field->getDouble(i)/1.27); - m_aircraft->mrYawMixLevel->setValue(val); - tmpVal = m_aircraft->multiMotorChannelBox2->currentIndex()-1; - if(tmpVal>-1) - { - field = obj->getField(mixerVectors.at(tmpVal)); - i = field->getElementNames().indexOf("Roll"); - val = floor(1-field->getDouble(i)/1.27); - m_aircraft->mrRollMixLevel->setValue(val); - } - } + + setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorSE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorS); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox5,multi.VTOLMotorSW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox6,multi.VTOLMotorNW); + + // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. + // This assumes that all vectors are identical - if not, the user should use the + // "custom" setting. + + channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; + if (channel > -1) + { + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); + m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + + //change channels + channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + m_aircraft->mrRollMixLevel->setValue( floor(1-value/1.27) ); + + } + + } else if (frameType == "HexaX") { - // Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW - field = obj->getField(QString("VTOLMotorNE")); - m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorE")); - m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSE")); - m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSW")); - m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorW")); - m_aircraft->multiMotorChannelBox5->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorNW")); - m_aircraft->multiMotorChannelBox6->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1; - // tmpVal will be -1 if value is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerVectors.at(tmpVal)); - int i = field->getElementNames().indexOf("Pitch"); - double val = floor(field->getDouble(i)/1.27); - m_aircraft->mrPitchMixLevel->setValue(val); - i = field->getElementNames().indexOf("Yaw"); - val = floor(-field->getDouble(i)/1.27); - m_aircraft->mrYawMixLevel->setValue(val); - tmpVal = m_aircraft->multiMotorChannelBox2->currentIndex()-1; - field = obj->getField(mixerVectors.at(tmpVal)); - i = field->getElementNames().indexOf("Roll"); - val = floor(1-field->getDouble(i)/1.27); - m_aircraft->mrRollMixLevel->setValue(val); - } + // Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW + + setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorSE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorSW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox5,multi.VTOLMotorW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox6,multi.VTOLMotorNW); + + // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. + // This assumes that all vectors are identical - if not, the user should use the + // "custom" setting. + + channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; + if (channel > -1) + { + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); + m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + + channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + m_aircraft->mrRollMixLevel->setValue( floor(1-value/1.27) ); + } } else if (frameType == "HexaCoax") { - // Motors 1/2/3 4/5/6 are: NW/W NE/E S/SE - field = obj->getField(QString("VTOLMotorNW")); - m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorW")); - m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorNE")); - m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorE")); - m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorS")); - m_aircraft->multiMotorChannelBox5->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSE")); - m_aircraft->multiMotorChannelBox6->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1; - // tmpVal will be -1 if value is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerVectors.at(tmpVal)); - int i = field->getElementNames().indexOf("Pitch"); - double val = floor(2*field->getDouble(i)/1.27); - m_aircraft->mrPitchMixLevel->setValue(val); - i = field->getElementNames().indexOf("Yaw"); - val = floor(-field->getDouble(i)/1.27); - m_aircraft->mrYawMixLevel->setValue(val); - i = field->getElementNames().indexOf("Roll"); - val = floor(field->getDouble(i)/1.27); - m_aircraft->mrRollMixLevel->setValue(val); - } + // Motors 1/2/3 4/5/6 are: NW/W NE/E S/SE + + setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorNE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox5,multi.VTOLMotorS); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox6,multi.VTOLMotorSE); + + // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. + // This assumes that all vectors are identical - if not, the user should use the + // "custom" setting. + channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; + if (channel > -1) + { + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); + m_aircraft->mrPitchMixLevel->setValue( value/1.27 ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + m_aircraft->mrYawMixLevel->setValue( value/1.27 ); + + channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + m_aircraft->mrRollMixLevel->setValue( value/1.27); + } } else if (frameType == "Octo" || frameType == "OctoV" || frameType == "OctoCoaxP") { - // Motors 1 to 8 are N / NE / E / etc - field = obj->getField(QString("VTOLMotorN")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorNE")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorE")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSE")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorS")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox5->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSW")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox6->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorW")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox7->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorNW")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox8->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1; - // tmpVal will be -1 if value is set to "None" - if (tmpVal > -1) { - if (frameType == "Octo") { - field = obj->getField(mixerVectors.at(tmpVal)); - int i = field->getElementNames().indexOf("Pitch"); - double val = floor(field->getDouble(i)/1.27); - m_aircraft->mrPitchMixLevel->setValue(val); - i = field->getElementNames().indexOf("Yaw"); - val = floor(-field->getDouble(i)/1.27); - m_aircraft->mrYawMixLevel->setValue(val); - tmpVal = m_aircraft->multiMotorChannelBox2->currentIndex()-1; - field = obj->getField(mixerVectors.at(tmpVal)); - i = field->getElementNames().indexOf("Roll"); - val = floor(-field->getDouble(i)/1.27); - m_aircraft->mrRollMixLevel->setValue(val); - } else if (frameType == "OctoV") { - field = obj->getField(mixerVectors.at(tmpVal)); - int i = field->getElementNames().indexOf("Yaw"); - double val = floor(-field->getDouble(i)/1.27); - m_aircraft->mrYawMixLevel->setValue(val); - i = field->getElementNames().indexOf("Roll"); - val = floor(-field->getDouble(i)/1.27); - m_aircraft->mrRollMixLevel->setValue(val); - tmpVal = m_aircraft->multiMotorChannelBox2->currentIndex()-1; - field = obj->getField(mixerVectors.at(tmpVal)); - i = field->getElementNames().indexOf("Pitch"); - val = floor(field->getDouble(i)/1.27); - m_aircraft->mrPitchMixLevel->setValue(val); - - } else if (frameType == "OctoCoaxP") { - field = obj->getField(mixerVectors.at(tmpVal)); - int i = field->getElementNames().indexOf("Pitch"); - double val = floor(field->getDouble(i)/1.27); - m_aircraft->mrPitchMixLevel->setValue(val); - i = field->getElementNames().indexOf("Yaw"); - val = floor(-field->getDouble(i)/1.27); - m_aircraft->mrYawMixLevel->setValue(val); - tmpVal = m_aircraft->multiMotorChannelBox3->currentIndex()-1; - field = obj->getField(mixerVectors.at(tmpVal)); - i = field->getElementNames().indexOf("Roll"); - val = floor(-field->getDouble(i)/1.27); - m_aircraft->mrRollMixLevel->setValue(val); - - } - } + // Motors 1 to 8 are N / NE / E / etc + + setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorSE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox5,multi.VTOLMotorS); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox6,multi.VTOLMotorSW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox7,multi.VTOLMotorW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox8,multi.VTOLMotorNW); + + // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. + // This assumes that all vectors are identical - if not, the user should use the + // "custom" setting. + channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; + if (channel > -1) + { + if (frameType == "Octo") { + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); + m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + + //change channels + channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + m_aircraft->mrRollMixLevel->setValue( floor(-value/1.27) ); + } + else if (frameType == "OctoV") { + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); + m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + + //change channels + channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + m_aircraft->mrRollMixLevel->setValue( floor(-value/1.27) ); + } + else if (frameType == "OctoCoaxP") { + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); + m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + + //change channels + channel = m_aircraft->multiMotorChannelBox3->currentIndex() - 1; + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + m_aircraft->mrRollMixLevel->setValue( floor(-value/1.27) ); + } + + } } else if (frameType == "OctoCoaxX") { - // Motors 1 to 8 are N / NE / E / etc - field = obj->getField(QString("VTOLMotorNW")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorN")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorNE")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorE")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSE")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox5->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorS")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox6->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorSW")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox7->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorW")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox8->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString())); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1; - // tmpVal will be -1 if value is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerVectors.at(tmpVal)); - int i = field->getElementNames().indexOf("Pitch"); - double val = floor(field->getDouble(i)/1.27); - m_aircraft->mrPitchMixLevel->setValue(val); - i = field->getElementNames().indexOf("Yaw"); - val = floor(-field->getDouble(i)/1.27); - m_aircraft->mrYawMixLevel->setValue(val); - i = field->getElementNames().indexOf("Roll"); - val = floor(field->getDouble(i)/1.27); - m_aircraft->mrRollMixLevel->setValue(val); - } + // Motors 1 to 8 are N / NE / E / etc + + setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorN); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorNE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox5,multi.VTOLMotorSE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox6,multi.VTOLMotorS); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox7,multi.VTOLMotorSW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox8,multi.VTOLMotorW); + + // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. + // This assumes that all vectors are identical - if not, the user should use the + // "custom" setting. + channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; + if (channel > -1) + { + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); + m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) ); + } } else if (frameType == "Tri") { - // Motors 1 to 8 are N / NE / E / etc - field = obj->getField(QString("VTOLMotorNW")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorNE")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString())); - field = obj->getField(QString("VTOLMotorS")); - Q_ASSERT(field); - m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString())); - field = obj->getField(QString("FixedWingYaw1")); - Q_ASSERT(field); - m_aircraft->triYawChannelBox->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString())); - - obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1; - // tmpVal will be -1 if value is set to "None" - if (tmpVal > -1) { - field = obj->getField(mixerVectors.at(tmpVal)); - int i = field->getElementNames().indexOf("Pitch"); - double val = floor(2*field->getDouble(i)/1.27); - m_aircraft->mrPitchMixLevel->setValue(val); - i = field->getElementNames().indexOf("Roll"); - val = floor(field->getDouble(i)/1.27); - m_aircraft->mrRollMixLevel->setValue(val); - } + // Motors 1 to 8 are N / NE / E / etc + + setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorS); + setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorS); + setComboCurrentIndex(m_aircraft->triYawChannelBox,multi.TRIYaw); + + channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; + if (channel > -1) + { + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); + m_aircraft->mrPitchMixLevel->setValue( floor(2*value/1.27) ); + + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) ); + + } } } @@ -853,27 +799,20 @@ void ConfigVehicleTypeWidget::refreshMultiRotorWidgetsValues(QString frameType) /** Helper function: setupQuadMotor */ -void ConfigVehicleTypeWidget::setupQuadMotor(int channel, double pitch, double roll, double yaw) +void ConfigMultiRotorWidget::setupQuadMotor(int channel, double pitch, double roll, double yaw) { qDebug()<(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); - UAVObjectField *field = obj->getField(mixerTypes.at(channel)); - field->setValue("Motor"); - field = obj->getField(mixerVectors.at(channel)); - // First of all reset the vector - resetField(field); - int ti = field->getElementNames().indexOf("ThrottleCurve1"); - field->setValue(127, ti); - ti = field->getElementNames().indexOf("Roll"); - field->setValue(roll*127,ti); - qDebug()<<"Set roll="<getElementNames().indexOf("Pitch"); - field->setValue(pitch*127,ti); - qDebug()<<"Set pitch="<getElementNames().indexOf("Yaw"); - field->setValue(yaw*127,ti); - qDebug()<<"Set yaw="<(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR); + + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2, 0); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, roll*127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, pitch*127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, yaw*127); } @@ -881,21 +820,42 @@ void ConfigVehicleTypeWidget::setupQuadMotor(int channel, double pitch, double r /** Helper function: setup motors. Takes a list of channel names in input. */ -void ConfigVehicleTypeWidget::setupMotors(QList motorList) +void ConfigMultiRotorWidget::setupMotors(QList motorList) { - resetActuators(); - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - UAVObjectField *field; QList mmList; mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3 << m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6 << m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8; + + GUIConfigDataUnion configData = GetConfigData(); + ResetActuators(&configData); + + int index; foreach (QString motor, motorList) { - field = obj->getField(motor); - field->setValue(mmList.takeFirst()->currentText()); + + index = mmList.takeFirst()->currentIndex(); + + //qDebug()<updated(); // Save... + SetConfigData(configData); + } @@ -903,12 +863,12 @@ void ConfigVehicleTypeWidget::setupMotors(QList motorList) /** Set up a Quad-X or Quad-P mixer */ -bool ConfigVehicleTypeWidget::setupQuad(bool pLayout) +bool ConfigMultiRotorWidget::setupQuad(bool pLayout) { // Check coherence: //Show any config errors in GUI - throwMultiRotorChannelConfigError(4); + throwConfigError(4); // - Four engines have to be defined if (m_aircraft->multiMotorChannelBox1->currentText() == "None" || @@ -979,11 +939,11 @@ bool ConfigVehicleTypeWidget::setupQuad(bool pLayout) /** Set up a Hexa-X or Hexa-P mixer */ -bool ConfigVehicleTypeWidget::setupHexa(bool pLayout) +bool ConfigMultiRotorWidget::setupHexa(bool pLayout) { // Check coherence: //Show any config errors in GUI - throwMultiRotorChannelConfigError(6); + throwConfigError(6); // - Four engines have to be defined if (m_aircraft->multiMotorChannelBox1->currentText() == "None" || @@ -1060,7 +1020,7 @@ bool ConfigVehicleTypeWidget::setupHexa(bool pLayout) /** This function sets up the multirotor mixer values. */ -bool ConfigVehicleTypeWidget::setupMultiRotorMixer(double mixerFactors[8][3]) +bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3]) { qDebug()<<"Mixer factors"; qDebug()< mmList; mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3 << m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6 << m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8; - UAVDataObject *obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - // 1. Assign the servo/motor/none for each channel - // Disable all - foreach(QString mixer, mixerTypes) { - field = obj->getField(mixer); - Q_ASSERT(field); - field->setValue("Disabled"); + + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + + //disable all + for (int channel=0; channelmrPitchMixLevel->value()/100; double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100; @@ -1107,34 +1069,25 @@ bool ConfigVehicleTypeWidget::setupMultiRotorMixer(double mixerFactors[8][3]) /** This function displays text and color formatting in order to help the user understand what channels have not yet been configured. */ -void ConfigVehicleTypeWidget::throwMultiRotorChannelConfigError(int numMotors) -{ +void ConfigMultiRotorWidget::throwConfigError(int numMotors) +{ //Initialize configuration error flag bool error=false; //Iterate through all instances of multiMotorChannelBox for (int i=0; i(this, "multiMotorChannelBox" + QString::number(i+1)); - if (combobox){ //if QLabel exists - QLabel *label = qFindChild(this, "MotorOutputLabel" + QString::number(i+1)); - if (combobox->currentText() == "None") { - -// label->setText("" + label->text() + ""); - + QComboBox *combobox = qFindChild(uiowner, "multiMotorChannelBox" + QString::number(i+1)); + if (combobox){ + if (combobox->currentText() == "None") { int size = combobox->style()->pixelMetric(QStyle::PM_SmallIconSize); QPixmap pixmap(size,size); pixmap.fill(QColor("red")); - combobox->setItemData(0, pixmap, Qt::DecorationRole);//Set color palettes -// combobox->setStyleSheet("QComboBox { color: red}"); + combobox->setItemData(0, pixmap, Qt::DecorationRole);//Set color palettes error=true; - } else { - combobox->setItemData(0, 0, Qt::DecorationRole);//Reset color palettes -// combobox->setStyleSheet("color: black;"); -// QTextEdit* htmlText=new QTextEdit(label->text()); // htmlText is any QString with html tags. -// label->setText(htmlText->toPlainText()); + combobox->setItemData(0, 0, Qt::DecorationRole);//Reset color palettes } } } @@ -1143,4 +1096,6 @@ void ConfigVehicleTypeWidget::throwMultiRotorChannelConfigError(int numMotors) if (error){ m_aircraft->mrStatusLabel->setText(QString("ERROR: Assign all %1 motor channels").arg(numMotors)); } -} \ No newline at end of file +} + + diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h new file mode 100644 index 000000000..3ccc0de6b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h @@ -0,0 +1,85 @@ +/** + ****************************************************************************** + * + * @file configairframetwidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief Airframe configuration panel + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef CONFIGMULTIROTORWIDGET_H +#define CONFIGMULTIROTORWIDGET_H + +#include "ui_airframe.h" +#include "../uavobjectwidgetutils/configtaskwidget.h" +#include "cfg_vehicletypes/vehicleconfig.h" + +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "uavobject.h" +#include "uavtalk/telemetrymanager.h" +#include +#include +#include + +class Ui_Widget; + +class ConfigMultiRotorWidget: public VehicleConfig +{ + Q_OBJECT + +public: + ConfigMultiRotorWidget(Ui_AircraftWidget *aircraft = 0, QWidget *parent = 0); + ~ConfigMultiRotorWidget(); + + friend class ConfigVehicleTypeWidget; + +private: + Ui_AircraftWidget *m_aircraft; + + QWidget *uiowner; + QGraphicsSvgItem *quad; + + bool setupQuad(bool pLayout); + bool setupHexa(bool pLayout); + bool setupOcto(); + bool setupMultiRotorMixer(double mixerFactors[8][3]); + void setupMotors(QList motorList); + void setupQuadMotor(int channel, double roll, double pitch, double yaw); + + virtual void ResetActuators(GUIConfigDataUnion* configData); + virtual QStringList getChannelDescriptions(); + +private slots: + virtual void setupUI(QString airframeType); + virtual void refreshWidgetsValues(QString frameType); + virtual QString updateConfigObjectsFromWidgets(); + void throwConfigError(int numMotors); + + +protected: + +signals: + void configurationChanged(); + +}; + + +#endif // CONFIGMULTIROTORWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp new file mode 100644 index 000000000..549778540 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -0,0 +1,310 @@ + +/** + ****************************************************************************** + * + * @file vehicleconfig.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief bit storage of config ui settings + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "cfg_vehicletypes/vehicleconfig.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "uavobject.h" + +#include "systemsettings.h" + +#include + +VehicleConfig::VehicleConfig(QWidget *parent) : ConfigTaskWidget(parent) +{ + //Generate lists of mixerTypeNames, mixerVectorNames, channelNames + channelNames << "None"; + for (int i = 0; i < (int)(VehicleConfig::CHANNEL_NUMELEM); i++) { + mixerTypes << QString("Mixer%1Type").arg(i+1); + mixerVectors << QString("Mixer%1Vector").arg(i+1); + channelNames << QString("Channel%1").arg(i+1); + } + +// typedef enum { MIXERTYPE_DISABLED=0, MIXERTYPE_MOTOR=1, MIXERTYPE_SERVO=2, + //MIXERTYPE_CAMERAROLL=3, MIXERTYPE_CAMERAPITCH=4, MIXERTYPE_CAMERAYAW=5, + //MIXERTYPE_ACCESSORY0=6, MIXERTYPE_ACCESSORY1=7, MIXERTYPE_ACCESSORY2=8, + //MIXERTYPE_ACCESSORY3=9, MIXERTYPE_ACCESSORY4=10, MIXERTYPE_ACCESSORY5=11 } MixerTypeElem; + + mixerTypeDescriptions << "Disabled" << "Motor" << "Servo" << "CameraRoll" << "CameraPitch" + << "CameraYaw" << "Accessory0" << "Accessory1" << "Accessory2" + << "Accessory3" << "Accessory4" << "Accessory5"; + + // This is needed because new style tries to compact things as much as possible in grid + // and on OSX the widget sizes of PushButtons is reported incorrectly: + // https://bugreports.qt-project.org/browse/QTBUG-14591 + foreach( QPushButton * btn, findChildren() ) { + btn->setAttribute(Qt::WA_LayoutUsesWidgetRect); + } +} + +VehicleConfig::~VehicleConfig() +{ + // Do nothing +} + +GUIConfigDataUnion VehicleConfig::GetConfigData() { + + int i; + GUIConfigDataUnion configData; + + // get an instance of systemsettings + SystemSettings * systemSettings = SystemSettings::GetInstance(getUAVObjectManager()); + Q_ASSERT(systemSettings); + SystemSettings::DataFields systemSettingsData = systemSettings->getData(); + + // copy systemsettings -> local configData + for(i = 0; i < (int)(SystemSettings::GUICONFIGDATA_NUMELEM); i++) + configData.UAVObject[i]=systemSettingsData.GUIConfigData[i]; + + // sanity check + Q_ASSERT(SystemSettings::GUICONFIGDATA_NUMELEM == + (sizeof(configData.UAVObject) / sizeof(configData.UAVObject[0]))); + + return configData; +} + +void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) { + + int i; + + // sanity check + Q_ASSERT(SystemSettings::GUICONFIGDATA_NUMELEM == + (sizeof(configData.UAVObject) / sizeof(configData.UAVObject[0]))); + + // get an instance of systemsettings + SystemSettings * systemSettings = SystemSettings::GetInstance(getUAVObjectManager()); + Q_ASSERT(systemSettings); + SystemSettings::DataFields systemSettingsData = systemSettings->getData(); + + // copy parameter configData -> systemsettings + for (i = 0; i < (int)(SystemSettings::GUICONFIGDATA_NUMELEM); i++) + systemSettingsData.GUIConfigData[i] = configData.UAVObject[i]; + + systemSettings->setData(systemSettingsData); + systemSettings->updated(); + + //emit ConfigurationChanged(); +} + +void VehicleConfig::ResetActuators(GUIConfigDataUnion* configData) +{ +} +QStringList VehicleConfig::getChannelDescriptions() +{ + QStringList channelDesc; + + // init a channel_numelem list of channel desc defaults + for (int i=0; i < (int)(VehicleConfig::CHANNEL_NUMELEM); i++) + { + channelDesc.append(QString("-")); + } + return channelDesc; +} + +/** + Helper function: + Sets the current index on supplied combobox to index + if it is within bounds 0 <= index < combobox.count() + */ +void VehicleConfig::setComboCurrentIndex(QComboBox* box, int index) +{ + Q_ASSERT(box); + + if (index >= 0 && index < box->count()) + box->setCurrentIndex(index); +} + +/** + Helper function: + enables/disables the named combobox within supplied uiowner + */ +void VehicleConfig::enableComboBox(QWidget* owner, QString boxName, bool enable) +{ + QComboBox* box = qFindChild(owner, boxName); + if (box) + box->setEnabled(enable); +} + +QString VehicleConfig::getMixerType(UAVDataObject* mixer, int channel) +{ + Q_ASSERT(mixer); + + QString mixerType = mixerTypeDescriptions[0]; //default to disabled + + if (channel >= 0 && channel < mixerTypes.count()) { + UAVObjectField *field = mixer->getField(mixerTypes.at(channel)); + Q_ASSERT(field); + + if (field) + mixerType = field->getValue().toString(); + } + + return mixerType; +} + +void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeElem mixerType) +{ + Q_ASSERT(mixer); + + qDebug() << QString("setMixerType channel %0, type %1").arg(channel).arg(mixerType); + + if (channel >= 0 && channel < mixerTypes.count()) { + UAVObjectField *field = mixer->getField(mixerTypes.at(channel)); + Q_ASSERT(field); + + if (field) { + if (mixerType >= 0 && mixerType < mixerTypeDescriptions.count()) + { + field->setValue(mixerTypeDescriptions[mixerType]); + mixer->updated(); + } + } + } +} + +void VehicleConfig::resetMixerVector(UAVDataObject* mixer, int channel) +{ + Q_ASSERT(mixer); + + if (channel >= 0 && channel < mixerVectors.count()) { + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 0); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2, 0); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, 0); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 0); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 0); + } +} + +double VehicleConfig::getMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName) +{ + Q_ASSERT(mixer); + + double value = 0; + + if (channel >= 0 && channel < mixerVectors.count()) { + UAVObjectField *field = mixer->getField(mixerVectors.at(channel)); + Q_ASSERT(field); + + if (field) { + value = field->getDouble(elementName); + } + } + return value; +} + +void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName, double value) +{ + Q_ASSERT(mixer); + + qDebug() << QString("setMixerVectorValue channel %0, name %1, value %2").arg(channel).arg(elementName).arg(value); + + if (channel >= 0 && channel < mixerVectors.count()) { + UAVObjectField *field = mixer->getField(mixerVectors.at(channel)); + Q_ASSERT(field); + + if (field) { + field->setDouble(value, elementName); + mixer->updated(); + } + } +} + +void VehicleConfig::setThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList curve) +{ + QPointer field; + + switch (curveType) + { + case MIXER_THROTTLECURVE1: + { + field = mixer->getField("ThrottleCurve1"); + break; + } + case MIXER_THROTTLECURVE2: + { + field = mixer->getField("ThrottleCurve2"); + break; + } + } + + if (field && field->getNumElements() == curve.length()) { + for (int i=0;isetValue(curve.at(i),i); + } + } +} + +void VehicleConfig::getThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList* curve) +{ + Q_ASSERT(mixer); + Q_ASSERT(curve); + + QPointer field; + + switch (curveType) + { + case MIXER_THROTTLECURVE1: + { + field = mixer->getField("ThrottleCurve1"); + break; + } + case MIXER_THROTTLECURVE2: + { + field = mixer->getField("ThrottleCurve2"); + break; + } + } + + if (field) { + curve->clear(); + for (unsigned int i=0; i < field->getNumElements(); i++) { + curve->append(field->getValue(i).toDouble()); + } + } +} + +/** + Reset the contents of a field + */ +void VehicleConfig::resetField(UAVObjectField * field) +{ + for (unsigned int i=0;igetNumElements();i++) { + field->setValue(0,i); + } +} + + +/** + * Util function to get a pointer to the object manager + * @return pointer to the UAVObjectManager + */ +UAVObjectManager* VehicleConfig::getUAVObjectManager() { + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager * objMngr = pm->getObject(); + Q_ASSERT(objMngr); + return objMngr; +} diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h new file mode 100644 index 000000000..343cfcf0c --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h @@ -0,0 +1,161 @@ +/** + ****************************************************************************** + * + * @file vehicleconfig.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief bit storage of config ui settings + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef GUIVEHICLECONFIG_H +#define GUIVEHICLECONFIG_H + +#include "../uavobjectwidgetutils/configtaskwidget.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "uavobject.h" + + +typedef struct { + uint VTOLMotorN:4; + uint VTOLMotorS:4; + uint VTOLMotorE:4; + uint VTOLMotorW:4; + uint VTOLMotorNW:4; + uint VTOLMotorNE:4; + uint VTOLMotorSW:4; + uint VTOLMotorSE:4; //32bits + uint TRIYaw:4; + quint32 padding:28; //64bits + quint32 padding1; + quint32 padding2; //128bits +} __attribute__((packed)) multiGUISettingsStruct; + +typedef struct { + uint SwashplateType:3; + uint FirstServoIndex:2; + uint CorrectionAngle:9; + uint ccpmCollectivePassthroughState:1; + uint ccpmLinkCyclicState:1; + uint ccpmLinkRollState:1; + uint SliderValue0:7; + uint SliderValue1:7; + uint SliderValue2:7;//41bits + uint ServoIndexW:4; + uint ServoIndexX:4; + uint ServoIndexY:4; + uint ServoIndexZ:4;//57bits + uint Throttle:4; + uint Tail:4; //65bits + quint32 padding:31; //96bits + quint32 padding1; //128bits +} __attribute__((packed)) heliGUISettingsStruct; + +typedef struct { + uint FixedWingThrottle:4; + uint FixedWingRoll1:4; + uint FixedWingRoll2:4; + uint FixedWingPitch1:4; + uint FixedWingPitch2:4; + uint FixedWingYaw1:4; + uint FixedWingYaw2:4; + uint padding:4; //32bits + quint32 padding1; + quint32 padding2; + quint32 padding3; //128bits +} __attribute__((packed)) fixedGUISettingsStruct; + +typedef struct { + uint GroundVehicleThrottle1:4; + uint GroundVehicleThrottle2:4; + uint GroundVehicleSteering1:4; + uint GroundVehicleSteering2:4; + uint padding:16; //32bits + quint32 padding1; + quint32 padding2; + quint32 padding3; //128bits +} __attribute__((packed)) groundGUISettingsStruct; + +typedef union +{ + uint UAVObject[4]; //32bits * 4 + heliGUISettingsStruct heli; //128bits + fixedGUISettingsStruct fixedwing; + multiGUISettingsStruct multi; + groundGUISettingsStruct ground; +} GUIConfigDataUnion; + + +class VehicleConfig: public ConfigTaskWidget +{ + Q_OBJECT + + public: + VehicleConfig(QWidget *parent = 0); + ~VehicleConfig(); + + /* Enumeration options for ThrottleCurves */ + typedef enum { MIXER_THROTTLECURVE1=0, MIXER_THROTTLECURVE2=1 } MixerThrottleCurveElem; + + /* Enumeration options for field MixerType */ + typedef enum { MIXERTYPE_DISABLED=0, MIXERTYPE_MOTOR=1, MIXERTYPE_SERVO=2, MIXERTYPE_CAMERAROLL=3, MIXERTYPE_CAMERAPITCH=4, MIXERTYPE_CAMERAYAW=5, MIXERTYPE_ACCESSORY0=6, MIXERTYPE_ACCESSORY1=7, MIXERTYPE_ACCESSORY2=8, MIXERTYPE_ACCESSORY3=9, MIXERTYPE_ACCESSORY4=10, MIXERTYPE_ACCESSORY5=11 } MixerTypeElem; + /* Array element names for field MixerVector */ + typedef enum { MIXERVECTOR_THROTTLECURVE1=0, MIXERVECTOR_THROTTLECURVE2=1, MIXERVECTOR_ROLL=2, MIXERVECTOR_PITCH=3, MIXERVECTOR_YAW=4 } MixerVectorElem; + + static GUIConfigDataUnion GetConfigData(); + static void SetConfigData(GUIConfigDataUnion configData); + static void resetField(UAVObjectField * field); + static void setComboCurrentIndex(QComboBox* box, int index); + static void enableComboBox(QWidget* owner, QString boxName, bool enable); + + double getMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName); + void setMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName, double value); + void resetMixerVector(UAVDataObject* mixer, int channel); + QString getMixerType(UAVDataObject* mixer, int channel); + void setMixerType(UAVDataObject* mixer, int channel, MixerTypeElem mixerType); + void setThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList curve); + void getThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList* curve); + + virtual void ResetActuators(GUIConfigDataUnion* configData); + virtual QStringList getChannelDescriptions(); + + QStringList channelNames; + QStringList mixerTypes; + QStringList mixerVectors; + QStringList mixerTypeDescriptions; + + static const quint32 CHANNEL_NUMELEM = 10; + + private: + + static UAVObjectManager* getUAVObjectManager(); + + private slots: + + public slots: + + signals: + //void ConfigurationChanged(); + +protected: + +}; + +#endif // GUIVEHICLECONFIG_H diff --git a/ground/openpilotgcs/src/plugins/config/config.pro b/ground/openpilotgcs/src/plugins/config/config.pro index 52a2b394a..8e49cb54d 100644 --- a/ground/openpilotgcs/src/plugins/config/config.pro +++ b/ground/openpilotgcs/src/plugins/config/config.pro @@ -19,8 +19,8 @@ HEADERS += configplugin.h \ configvehicletypewidget.h \ config_pro_hw_widget.h \ config_cc_hw_widget.h \ - configahrswidget.h \ configccattitudewidget.h \ + configpipxtremewidget.h \ cfg_vehicletypes/configccpmwidget.h \ configstabilizationwidget.h \ assertions.h \ @@ -30,7 +30,12 @@ HEADERS += configplugin.h \ inputchannelform.h \ configcamerastabilizationwidget.h \ configtxpidwidget.h \ - outputchannelform.h \ + outputchannelform.h \ + cfg_vehicletypes/configmultirotorwidget.h \ + cfg_vehicletypes/configgroundvehiclewidget.h \ + cfg_vehicletypes/configfixedwingwidget.h \ + cfg_vehicletypes/vehicleconfig.h \ + configrevowidget.h \ config_global.h SOURCES += configplugin.cpp \ configgadgetconfiguration.cpp \ @@ -44,9 +49,9 @@ SOURCES += configplugin.cpp \ configvehicletypewidget.cpp \ config_pro_hw_widget.cpp \ config_cc_hw_widget.cpp \ - configahrswidget.cpp \ configccattitudewidget.cpp \ configstabilizationwidget.cpp \ + configpipxtremewidget.cpp \ twostep.cpp \ legacy-calibration.cpp \ gyro-calibration.cpp \ @@ -55,16 +60,17 @@ SOURCES += configplugin.cpp \ defaulthwsettingswidget.cpp \ inputchannelform.cpp \ configcamerastabilizationwidget.cpp \ + configrevowidget.cpp \ configtxpidwidget.cpp \ cfg_vehicletypes/configmultirotorwidget.cpp \ cfg_vehicletypes/configgroundvehiclewidget.cpp \ cfg_vehicletypes/configfixedwingwidget.cpp \ cfg_vehicletypes/configccpmwidget.cpp \ - outputchannelform.cpp + outputchannelform.cpp \ + cfg_vehicletypes/vehicleconfig.cpp FORMS += airframe.ui \ cc_hw_settings.ui \ pro_hw_settings.ui \ - ahrs.ui \ ccpm.ui \ stabilization.ui \ input.ui \ @@ -75,5 +81,7 @@ FORMS += airframe.ui \ inputchannelform.ui \ camerastabilization.ui \ outputchannelform.ui \ - txpid.ui + revosensors.ui \ + txpid.ui \ + pipxtreme.ui RESOURCES += configgadget.qrc diff --git a/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp index c554cae31..0f050cbc2 100644 --- a/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp @@ -43,7 +43,7 @@ ConfigProHWWidget::ConfigProHWWidget(QWidget *parent) : ConfigTaskWidget(parent) addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_telemetry->telemetrySpeed); enableControls(false); populateWidgets(); - refreshWidgetsValues(); + refreshWidgetsValues(NULL); } ConfigProHWWidget::~ConfigProHWWidget() diff --git a/ground/openpilotgcs/src/plugins/config/configahrswidget.cpp b/ground/openpilotgcs/src/plugins/config/configahrswidget.cpp deleted file mode 100644 index 75cb57f78..000000000 --- a/ground/openpilotgcs/src/plugins/config/configahrswidget.cpp +++ /dev/null @@ -1,1231 +0,0 @@ -/** - ****************************************************************************** - * - * @file configahrswidget.h - * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup ConfigPlugin Config Plugin - * @{ - * @brief The Configuration Gadget used to update settings in the firmware - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#include "configahrswidget.h" - -#include "math.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "assertions.h" -#include "calibration.h" - -#define sign(x) ((x < 0) ? -1 : 1) - -const double ConfigAHRSWidget::maxVarValue = 0.1; -const int ConfigAHRSWidget::calibrationDelay = 7; // Time to wait for the AHRS to do its calibration - -// ***************** - -class Thread : public QThread -{ -public: - static void usleep(unsigned long usecs) - { - QThread::usleep(usecs); - } -}; - -// ***************** - -ConfigAHRSWidget::ConfigAHRSWidget(QWidget *parent) : ConfigTaskWidget(parent) -{ - m_ahrs = new Ui_AHRSWidget(); - m_ahrs->setupUi(this); - - collectingData = false; - - // Initialization of the Paper plane widget - m_ahrs->sixPointsHelp->setScene(new QGraphicsScene(this)); - - paperplane = new QGraphicsSvgItem(); - paperplane->setSharedRenderer(new QSvgRenderer()); - paperplane->renderer()->load(QString(":/configgadget/images/paper-plane.svg")); - paperplane->setElementId("plane-horizontal"); - m_ahrs->sixPointsHelp->scene()->addItem(paperplane); - m_ahrs->sixPointsHelp->setSceneRect(paperplane->boundingRect()); - - // Initialization of the AHRS bargraph graph - - m_ahrs->ahrsBargraph->setScene(new QGraphicsScene(this)); - - QSvgRenderer *renderer = new QSvgRenderer(); - ahrsbargraph = new QGraphicsSvgItem(); - renderer->load(QString(":/configgadget/images/ahrs-calib.svg")); - ahrsbargraph->setSharedRenderer(renderer); - ahrsbargraph->setElementId("background"); - ahrsbargraph->setObjectName("background"); - m_ahrs->ahrsBargraph->scene()->addItem(ahrsbargraph); - m_ahrs->ahrsBargraph->setSceneRect(ahrsbargraph->boundingRect()); - - // Initialize the 9 bargraph values: - - QMatrix lineMatrix = renderer->matrixForElement("accel_x"); - QRectF rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_x")); - qreal startX = rect.x(); - qreal startY = rect.y()+ rect.height(); - // maxBarHeight will be used for scaling it later. - maxBarHeight = rect.height(); - // Then once we have the initial location, we can put it - // into a QGraphicsSvgItem which we will display at the same - // place: we do this so that the heading scale can be clipped to - // the compass dial region. - accel_x = new QGraphicsSvgItem(); - accel_x->setSharedRenderer(renderer); - accel_x->setElementId("accel_x"); - m_ahrs->ahrsBargraph->scene()->addItem(accel_x); - accel_x->setPos(startX, startY); - accel_x->setTransform(QTransform::fromScale(1,0),true); - - lineMatrix = renderer->matrixForElement("accel_y"); - rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_y")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - accel_y = new QGraphicsSvgItem(); - accel_y->setSharedRenderer(renderer); - accel_y->setElementId("accel_y"); - m_ahrs->ahrsBargraph->scene()->addItem(accel_y); - accel_y->setPos(startX,startY); - accel_y->setTransform(QTransform::fromScale(1,0),true); - - lineMatrix = renderer->matrixForElement("accel_z"); - rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_z")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - accel_z = new QGraphicsSvgItem(); - accel_z->setSharedRenderer(renderer); - accel_z->setElementId("accel_z"); - m_ahrs->ahrsBargraph->scene()->addItem(accel_z); - accel_z->setPos(startX,startY); - accel_z->setTransform(QTransform::fromScale(1,0),true); - - lineMatrix = renderer->matrixForElement("gyro_x"); - rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_x")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - gyro_x = new QGraphicsSvgItem(); - gyro_x->setSharedRenderer(renderer); - gyro_x->setElementId("gyro_x"); - m_ahrs->ahrsBargraph->scene()->addItem(gyro_x); - gyro_x->setPos(startX,startY); - gyro_x->setTransform(QTransform::fromScale(1,0),true); - - lineMatrix = renderer->matrixForElement("gyro_y"); - rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_y")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - gyro_y = new QGraphicsSvgItem(); - gyro_y->setSharedRenderer(renderer); - gyro_y->setElementId("gyro_y"); - m_ahrs->ahrsBargraph->scene()->addItem(gyro_y); - gyro_y->setPos(startX,startY); - gyro_y->setTransform(QTransform::fromScale(1,0),true); - - - lineMatrix = renderer->matrixForElement("gyro_z"); - rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_z")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - gyro_z = new QGraphicsSvgItem(); - gyro_z->setSharedRenderer(renderer); - gyro_z->setElementId("gyro_z"); - m_ahrs->ahrsBargraph->scene()->addItem(gyro_z); - gyro_z->setPos(startX,startY); - gyro_z->setTransform(QTransform::fromScale(1,0),true); - - lineMatrix = renderer->matrixForElement("mag_x"); - rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_x")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - mag_x = new QGraphicsSvgItem(); - mag_x->setSharedRenderer(renderer); - mag_x->setElementId("mag_x"); - m_ahrs->ahrsBargraph->scene()->addItem(mag_x); - mag_x->setPos(startX,startY); - mag_x->setTransform(QTransform::fromScale(1,0),true); - - lineMatrix = renderer->matrixForElement("mag_y"); - rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_y")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - mag_y = new QGraphicsSvgItem(); - mag_y->setSharedRenderer(renderer); - mag_y->setElementId("mag_y"); - m_ahrs->ahrsBargraph->scene()->addItem(mag_y); - mag_y->setPos(startX,startY); - mag_y->setTransform(QTransform::fromScale(1,0),true); - - lineMatrix = renderer->matrixForElement("mag_z"); - rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_z")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - mag_z = new QGraphicsSvgItem(); - mag_z->setSharedRenderer(renderer); - mag_z->setElementId("mag_z"); - m_ahrs->ahrsBargraph->scene()->addItem(mag_z); - mag_z->setPos(startX,startY); - mag_z->setTransform(QTransform::fromScale(1,0),true); - - position = -1; - - // Fill the dropdown menus: - UAVObject *obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSSettings"))); - UAVObjectField *field = obj->getField(QString("Algorithm")); - m_ahrs->algorithm->addItems(field->getOptions()); - - // Register for Home Location state changes - obj = dynamic_cast(getObjectManager()->getObject(QString("HomeLocation"))); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this , SLOT(enableHomeLocSave(UAVObject*))); - - // Don't enable multi-point calibration until HomeLocation is set. - m_ahrs->sixPointsStart->setEnabled(obj->getField("Set")->getValue().toBool()); - - // Connect the signals - connect(m_ahrs->ahrsCalibStart, SIGNAL(clicked()), this, SLOT(launchAHRSCalibration())); - connect(m_ahrs->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration())); - - obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSSettings"))); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues())); - obj = getObjectManager()->getObject(QString("HomeLocation")); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues())); - - connect(m_ahrs->ahrsSettingsSaveRAM, SIGNAL(clicked()), this, SLOT(ahrsSettingsSaveRAM())); - connect(m_ahrs->ahrsSettingsSaveSD, SIGNAL(clicked()), this, SLOT(ahrsSettingsSaveSD())); - connect(m_ahrs->sixPointsStart, SIGNAL(clicked()), this, SLOT(multiPointCalibrationMode())); - connect(m_ahrs->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); - connect(m_ahrs->startDriftCalib, SIGNAL(clicked()),this, SLOT(launchGyroDriftCalibration())); - - // Order is important: 1st request the settings (it will also enable the controls) - // then explicitely disable them. They will be re-enabled right afterwards by the - // configgadgetwidget if the autopilot is actually connected. - refreshValues(); - // when the AHRS Widget is instanciated, the autopilot is always connected // enableControls(false); - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect())); - - // Connect the help button - connect(m_ahrs->ahrsHelp, SIGNAL(clicked()), this, SLOT(openHelp())); -} - -ConfigAHRSWidget::~ConfigAHRSWidget() -{ - // Do nothing -} - - -void ConfigAHRSWidget::showEvent(QShowEvent *event) -{ - Q_UNUSED(event) - // Thit fitInView method should only be called now, once the - // widget is shown, otherwise it cannot compute its values and - // the result is usually a ahrsbargraph that is way too small. - m_ahrs->ahrsBargraph->fitInView(ahrsbargraph, Qt::KeepAspectRatio); - m_ahrs->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); -} - -void ConfigAHRSWidget::resizeEvent(QResizeEvent *event) -{ - Q_UNUSED(event) - m_ahrs->ahrsBargraph->fitInView(ahrsbargraph, Qt::KeepAspectRatio); - m_ahrs->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); -} - - -void ConfigAHRSWidget::enableControls(bool enable) -{ - //m_ahrs->ahrsSettingsSaveRAM->setEnabled(enable); - m_ahrs->ahrsSettingsSaveSD->setEnabled(enable); -} - -/** - Starts an accelerometer bias calibration. - */ -void ConfigAHRSWidget::launchAccelBiasCalibration() -{ - m_ahrs->accelBiasStart->setEnabled(false); - m_ahrs->accelBiasProgress->setValue(0); - - // Setup the AHRS to give us the right data at the right rate: - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSSettings"))); - UAVObjectField* field = obj->getField(QString("BiasCorrectedRaw")); - field->setValue("FALSE"); - obj->updated(); - - accel_accum_x.clear(); - accel_accum_y.clear(); - accel_accum_z.clear(); - -// UAVDataObject* ahrsCalib = dynamic_cast(getObjectManager()->getObject(QString("AHRSCalibration"))); -// ahrsCalib->getField("accel_bias")->setDouble(0,0); -// ahrsCalib->getField("accel_bias")->setDouble(0,1); -// ahrsCalib->getField("accel_bias")->setDouble(0,2); -// ahrsCalib->updated(); - - /* Need to get as many AttitudeRaw updates as possible */ - obj = dynamic_cast(getObjectManager()->getObject(QString("AttitudeRaw"))); - initialMdata = obj->getMetadata(); - UAVObject::Metadata mdata = initialMdata; - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; - mdata.flightTelemetryUpdatePeriod = 100; - obj->setMetadata(mdata); - - // Now connect to the attituderaw updates, gather for 100 samples - collectingData = true; - obj = dynamic_cast(getObjectManager()->getObject(QString("AttitudeRaw"))); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(accelBiasattitudeRawUpdated(UAVObject*))); - -} - -/** - Updates the accel bias raw values - */ -void ConfigAHRSWidget::accelBiasattitudeRawUpdated(UAVObject *obj) -{ - // TODO: THis one gets replaced with the multipoint calibratino below. - UAVObjectField *accel_field = obj->getField(QString("accels")); - Q_ASSERT(accel_field != 0); - - // This is necessary to prevent a race condition on disconnect signal and another update - if (collectingData == true) { - accel_accum_x.append(accel_field->getValue(0).toDouble()); - accel_accum_y.append(accel_field->getValue(1).toDouble()); - accel_accum_z.append(accel_field->getValue(2).toDouble()); - } - - m_ahrs->accelBiasProgress->setValue(m_ahrs->accelBiasProgress->value()+1); - - if(accel_accum_x.size() >= 100 && collectingData == true) { - collectingData = false; - disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(accelBiasattitudeRawUpdated(UAVObject*))); - m_ahrs->accelBiasStart->setEnabled(true); - - UAVDataObject* ahrsCalib = dynamic_cast(getObjectManager()->getObject(QString("AHRSCalibration"))); - UAVObjectField* field = ahrsCalib->getField("accel_bias"); - double xBias = field->getDouble(0)- listMean(accel_accum_x); - double yBias = field->getDouble(1) - listMean(accel_accum_y); - double zBias = -9.81 + field->getDouble(2) - listMean(accel_accum_z); - - field->setDouble(xBias,0); - field->setDouble(yBias,1); - field->setDouble(zBias,2); - - ahrsCalib->updated(); - - getObjectManager()->getObject(QString("AttitudeRaw"))->setMetadata(initialMdata); - - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSSettings"))); - field = obj->getField(QString("BiasCorrectedRaw")); - field->setValue("TRUE"); - obj->updated(); - - saveAHRSCalibration(); - - } - -} - - -/** - Starts a Gyro temperature drift calibration. - */ -void ConfigAHRSWidget::launchGyroDriftCalibration() -{ - if (!collectingData) { - // m_ahrs->startDriftCalib->setEnabled(false); - m_ahrs->startDriftCalib->setText("Stop"); - m_ahrs->accelBiasStart->setEnabled(false); - m_ahrs->ahrsCalibStart->setEnabled(false); - m_ahrs->sixPointsStart->setEnabled(false); - - // Setup the AHRS to give us the right data at the right rate: - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSSettings"))); - UAVObjectField* field = obj->getField(QString("BiasCorrectedRaw")); - field->setValue("FALSE"); - obj->updated(); - - /* Need to get as many AttitudeRaw updates as possible */ - obj = dynamic_cast(getObjectManager()->getObject(QString("AttitudeRaw"))); - initialMdata = obj->getMetadata(); - UAVObject::Metadata mdata = initialMdata; - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; - mdata.flightTelemetryUpdatePeriod = 100; - obj->setMetadata(mdata); - - // Now connect to the attituderaw updates until we stop - collectingData = true; - obj = dynamic_cast(getObjectManager()->getObject(QString("BaroAltitude"))); - field = obj->getField(QString("Temperature")); - double temp = field->getValue().toDouble(); - m_ahrs->gyroTempSlider->setRange(temp*10,temp*10); - m_ahrs->gyroMaxTemp->setText(QString::number(temp,'g',3)); - m_ahrs->gyroMinTemp->setText(QString::number(temp,'g',3)); - - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(driftCalibrationAttitudeRawUpdated(UAVObject*))); - } else { - // Stop all the gathering: - collectingData = false; - m_ahrs->startDriftCalib->setText("Start"); - m_ahrs->accelBiasStart->setEnabled(true); - m_ahrs->ahrsCalibStart->setEnabled(true); - m_ahrs->sixPointsStart->setEnabled(true); - - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("AttitudeRaw"))); - disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(driftCalibrationAttitudeRawUpdated(UAVObject*))); - - getObjectManager()->getObject(QString("AttitudeRaw"))->setMetadata(initialMdata); - - obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSSettings"))); - UAVObjectField* field = obj->getField(QString("BiasCorrectedRaw")); - field->setValue("TRUE"); - obj->updated(); - - // TODO: Now compute the drift here - computeGyroDrift(); - - } -} - -/** - Updates the gyro drift calibration values in real time - */ -void ConfigAHRSWidget::driftCalibrationAttitudeRawUpdated(UAVObject* obj) { - - Q_UNUSED(obj) - // This is necessary to prevent a race condition on disconnect signal and another update - if (collectingData == true) { - /** - First of all, update the temperature user feedback - This is not what we will use for our calculations, but it it easier for the - user to have the real temperature rather than an obscure unit... - */ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("BaroAltitude"))); - UAVObjectField *tempField = obj->getField(QString("Temperature")); - Q_ASSERT(tempField != 0); - double mbTemp = tempField->getValue().toDouble(); - if (mbTemp*10 < m_ahrs->gyroTempSlider->minimum()) { - m_ahrs->gyroTempSlider->setMinimum(mbTemp*10); - m_ahrs->gyroMinTemp->setText(QString::number(mbTemp,'g',3)); - } else if (mbTemp*10 > m_ahrs->gyroTempSlider->maximum()) { - m_ahrs->gyroTempSlider->setMaximum(mbTemp*10); - m_ahrs->gyroMaxTemp->setText(QString::number(mbTemp,'g',3)); - } - m_ahrs->gyroTempSlider->setValue(mbTemp*10); - // TODO: - // - Add an indicator to show that we have a significant - // temperature difference in our gathered data (red/yellow/green) - - /** - Now, append gyro values + gyro temp data into our buffers - */ - // TODO: - // - choose a storage type for this data - // - Check it's not getting too big - // - do the actual appending - // - That's it, really... - - - } -} - -/** - Computes gyro drift based on sampled data - */ -void ConfigAHRSWidget::computeGyroDrift() { - // TODO - - // TODO: if this is not too computing-intensive, we could consider - // calling this with a timer when data sampling is enabled, to get - // a real-time view of the computed drift convergence and let the - // user stop sampling when it becomes stable enough... - // - // Hint for whoever wants to implement that: - // The formula I use for computing the temperature compensation factor from - // two nicely filtered (downsampled) sample points is as follows: - // - // gyro_tempcompfactor == -(raw_gyro1 - raw_gyro2)/(gyro_temp1 - gyro_temp2) - // - // where raw_gyro1 and raw_gyro2 are gyroscope raw measurement values and - // gyro_temp1 and gyro_temp2 are the measurements from the gyroscope internal - // temperature sensors, each at two measure points T1 and T2 - // note that the X and Y gyroscopes share one temperature sensor while - // Z has its own. - // - // the formula that calculates the AttitudeRav.gyros[X,Y,Z] values is - // currently as follows: - // - // gyro = 180/Pi * ( ( ( raw_gyro + raw_gyro * gyro_tempcompfactor ) * gyro_scale) + gyro_bias ) - // - // so to get gyro_raw do the following: - // 1. set AHRSSettings.BiasCorrectedRaw to FALSE before measuring! (already done right now) - // 2. set AHRSCalibration.gyro_tempcompfactor to 0 before measuring! - // 3. gyro_raw = ( ( gyro * Pi / 180 ) - gyro_bias ) / gyro_scale - // - // a nice trick is to set gyro_bias to 0 and gyro_scale to (Pi / 180) in which case gyro = raw_gyro - // note that Pi/180 is very close to the "real" scale of the AHRS gyros anyway (though with switched signs) - -} - - - - -/** - Launches the AHRS sensors calibration - */ -void ConfigAHRSWidget::launchAHRSCalibration() -{ - m_ahrs->calibInstructions->setText("Estimating sensor variance..."); - m_ahrs->ahrsCalibStart->setEnabled(false); - - UAVObject *obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSCalibration"))); - UAVObjectField *field = obj->getField(QString("measure_var")); - field->setValue("MEASURE"); - obj->updated(); - - QTimer::singleShot(calibrationDelay*1000, this, SLOT(calibPhase2())); - m_ahrs->calibProgress->setRange(0,calibrationDelay); - phaseCounter = 0; - progressBarIndex = 0; - connect(&progressBarTimer, SIGNAL(timeout()), this, SLOT(incrementProgress())); - progressBarTimer.start(1000); -} - -/** - Increment progress bar - */ -void ConfigAHRSWidget::incrementProgress() -{ - m_ahrs->calibProgress->setValue(progressBarIndex++); - if (progressBarIndex > m_ahrs->calibProgress->maximum()) { - progressBarTimer.stop(); - progressBarIndex = 0; - } -} - - -/** - Callback once calibration is done on the board. - - Currently we don't have a way to tell if calibration is finished, so we - have to use a timer. - - calibPhase2 is also connected to the AHRSCalibration object update signal. - - - */ -void ConfigAHRSWidget::calibPhase2() -{ - - UAVObject *obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSCalibration"))); -// UAVObjectField *field = obj->getField(QString("measure_var")); - - // This is a bit weird, but it is because we are expecting an update from the - // OP board with the correct calibration values, and those only arrive on the object update - // which comes back from the board, and not the first object update signal which is in fast - // the object update we did ourselves... Clear ? - switch (phaseCounter) { - case 0: - phaseCounter++; - m_ahrs->calibInstructions->setText("Getting results..."); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(calibPhase2())); - // We need to echo back the results of calibration before changing to set mode - obj->requestUpdate(); - break; - case 1: // This is the update with the right values (coming from the board) - disconnect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(calibPhase2())); - // Now update size of all the graphs - drawVariancesGraph(); - saveAHRSCalibration(); - m_ahrs->calibInstructions->setText(QString("Calibration saved.")); - m_ahrs->ahrsCalibStart->setEnabled(true); - break; - } -} - -/** - Saves the AHRS sensors calibration (to RAM and SD) - */ -void ConfigAHRSWidget::saveAHRSCalibration() -{ - UAVObject *obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSCalibration"))); - UAVObjectField *field = obj->getField(QString("measure_var")); - field->setValue("SET"); - obj->updated(); - saveObjectToSD(obj); -} - -FORCE_ALIGN_FUNC -void ConfigAHRSWidget::attitudeRawUpdated(UAVObject * obj) -{ - QMutexLocker lock(&attitudeRawUpdateLock); - - UAVObjectField *accel_field = obj->getField(QString("accels")); - UAVObjectField *gyro_field = obj->getField(QString("gyros")); - UAVObjectField *mag_field = obj->getField(QString("magnetometers")); - - Q_ASSERT(gyro_field != 0 && accel_field != 0 && mag_field != 0); - - // This is necessary to prevent a race condition on disconnect signal and another update - if (collectingData == true) { - accel_accum_x.append(accel_field->getValue(0).toDouble()); - accel_accum_y.append(accel_field->getValue(1).toDouble()); - accel_accum_z.append(accel_field->getValue(2).toDouble()); - // Note gyros actually (-y,-x,-z) but since we consistent here no prob - mag_accum_x.append(mag_field->getValue(0).toDouble()); - mag_accum_y.append(mag_field->getValue(1).toDouble()); - mag_accum_z.append(mag_field->getValue(2).toDouble()); - - gyro_accum_x.append(gyro_field->getValue(0).toDouble()); - gyro_accum_y.append(gyro_field->getValue(1).toDouble()); - gyro_accum_z.append(gyro_field->getValue(2).toDouble()); - } - - if(accel_accum_x.size() >= 8 && collectingData == true) { - collectingData = false; - disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(attitudeRawUpdated(UAVObject*))); - m_ahrs->sixPointsSave->setEnabled(true); - - accel_data[position] << listMean(accel_accum_x), - listMean(accel_accum_y), - listMean(accel_accum_z); - - mag_data[position] << listMean(mag_accum_x), - listMean(mag_accum_y), - listMean(mag_accum_z); - - gyro_data[position] << listMean(gyro_accum_x), - listMean(gyro_accum_y), - listMean(gyro_accum_z); - - - std::cout << "observed accel: " << accel_data[position].transpose() - << "\nobserved mag: " << mag_data[position].transpose() - << "\nobserved gyro: " << gyro_data[position].transpose() - << std::endl; - - struct { - const char* instructions; - const char* display; - } instructions[] = { - { "Pitch up 45 deg and click save position...", "plane-horizontal" }, - { "Pitch down 45 deg and click save position...", "plane-horizontal" }, - { "Roll left 45 deg and click save position...", "plane-left" }, - { "Roll right 45 deg and click save position...", "plane-left" }, - - { "Turn left 90 deg to 09:00 position and click save position...", "plane-horizontal" }, - { "Pitch up 45 deg and click save position...", "plane-horizontal" }, - { "Pitch down 45 deg and click save position...", "plane-horizontal" }, - { "Roll left 45 deg and click save position...", "plane-left" }, - { "Roll right 45 deg and click save position...", "plane-left" }, - - { "Turn left 90 deg to 06:00 position and click save position...", "plane-horizontal" }, - { "Pitch up 45 deg and click save position...", "plane-horizontal" }, - { "Pitch down 45 deg and click save position...", "plane-horizontal" }, - { "Roll left 45 deg and click save position...", "plane-left" }, - { "Roll right 45 deg and click save position...", "plane-left" }, - - { "Turn left 90 deg to 03:00 position and click save position...", "plane-horizontal" }, - { "Pitch up 45 deg and click save position...", "plane-horizontal" }, - { "Pitch down 45 deg and click save position...", "plane-horizontal" }, - { "Roll left 45 deg and click save position...", "plane-left" }, - { "Roll right 45 deg and click save position...", "plane-left" }, - - { "Place with nose vertically up and click save position...", "plane-up" }, - { "Place with nose straight down and click save position...", "plane-down" }, - { "Place upside down and click save position...", "plane-flip" }, - }; - - n_positions = sizeof(instructions) / sizeof(instructions[0]); - position = (position + 1) % n_positions; - - if (position != 0 && position < n_positions) { - - m_ahrs->sixPointCalibInstructions->append(instructions[position-1].instructions); - displayPlane(instructions[position-1].display); - } - else if(position == 0) { - position = n_positions; - computeScaleBias(); - m_ahrs->sixPointsStart->setEnabled(true); - m_ahrs->sixPointsSave->setEnabled(false); - saveAHRSCalibration(); // Saves the result to SD. - - /* Cleanup original settings */ - getObjectManager()->getObject(QString("AttitudeRaw"))->setMetadata(initialMdata); - } - } -} - -/** - * Saves the data from the aircraft in one of six positions - */ -void ConfigAHRSWidget::savePositionData() -{ - QMutexLocker lock(&attitudeRawUpdateLock); - m_ahrs->sixPointsSave->setEnabled(false); - - accel_accum_x.clear(); - accel_accum_y.clear(); - accel_accum_z.clear(); - mag_accum_x.clear(); - mag_accum_y.clear(); - mag_accum_z.clear(); - gyro_accum_x.clear(); - gyro_accum_y.clear(); - gyro_accum_z.clear(); - - collectingData = true; - UAVObject *obj = dynamic_cast(getObjectManager()->getObject(QString("AttitudeRaw"))); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(attitudeRawUpdated(UAVObject*))); - - m_ahrs->sixPointCalibInstructions->append("Hold..."); -} - -//***************************************************************** -namespace { - -/* - * Calibrated scale factors should be real values with scale factor less than 10% from nominal - */ -bool checkScaleFactors(const Vector3f& scalars) -{ - return isReal(scalars) && - scalars.cwise().abs().maxCoeff() < 1.10f; -} - -/* - * Calibrated offsets should be real values. TODO: Add range checks - */ -bool checkOffsets(const Vector3f& offsets) -{ - return isReal(offsets); -} - -/** - * Given a UAVObjectField that is a 3-tuple, produce an Eigen::Vector3f - * from it. - */ -Vector3f -tupleToVector(UAVObjectField *tuple) -{ - return (Vector3f() << tuple->getDouble(0), - tuple->getDouble(1), - tuple->getDouble(2)).finished(); -} - -/** - * Convert a 3-vector to a 3-tuple - * @param v A 3-vector - * @param tuple[in] Assign the elements of this three-tuple to the elements of v - */ -void -vectorToTuple(UAVObjectField *tuple, const Vector3f& v) -{ - for (int i = 0; i < 3; ++i) { - tuple->setDouble(v(i), i); - } -} - -/** - * Updates the offsets for a calibrated gyro field. - * @param scale[in] Non-null pointer to a 3-element scale factor field. - * @param bias[out] Non-null pointer to a 3-element bias field. - * @param updateBias the source bias matrix. - */ -void -updateBias(UAVObjectField *scale, - UAVObjectField *bias , - const Vector3f& updateBias) -{ - Vector3f scale_factor = (Vector3f() << scale->getDouble(0), - scale->getDouble(1), - scale->getDouble(2)).finished(); - Vector3f old_bias = (Vector3f() << bias->getDouble(0), - bias->getDouble(1), - bias->getDouble(2)).finished(); - - // Convert to radians/second - Vector3f final_bias = -(M_PI)/180.0f * updateBias + old_bias; - - bias->setDouble(final_bias(0), 0); - bias->setDouble(final_bias(1), 1); - bias->setDouble(final_bias(2), 2); -} - -void -updateRotation(UAVObjectField *rotation, const Vector3f& updateRotation) -{ - for (int i = 0; i < 3; ++i) { - rotation->setDouble(updateRotation[i], i); - } -} - -} // !namespace (anon) - - -/** - * Updates the scale factors and offsets for a calibrated vector field. - * @param scale[out] Non-null pointer to a 3-element scale factor field. - * @param bias[out] Non-null pointer to a 3-element bias field. - * @param ortho[out] Optional pointer to a 3-element orthogonal correction field - * @param updateScale the source scale factor matrix. - * @param updateBias the source bias matrix. - * @param oldScale The original sensor scale factor - * @param oldBias The original bias value - * @param oldOrtho Optional. The original orthogonality scale factor value. - * @return true if successful, false otherwise. - */ -bool -ConfigAHRSWidget::updateScaleFactors(UAVObjectField *scale, - UAVObjectField *bias , - UAVObjectField *ortho, - const Matrix3f& updateScale, - const Vector3f& updateBias, - const Vector3f& oldScale, - const Vector3f& oldBias, - const Vector3f& oldOrtho) -{ - // Compose a 4x4 affine transformation matrix composed of the scale factor, - // orthogonality correction, and bias. - Matrix4f calibration; - calibration << tupleToVector(scale).asDiagonal(), - tupleToVector(bias), - Vector4f::UnitW().transpose(); - - if (ortho) { - Vector3f orthof = tupleToVector(ortho); - calibration(1, 0) = calibration(0, 1) = orthof(0); - calibration(2, 0) = calibration(0, 2) = orthof(1); - calibration(1, 2) = calibration(2, 1) = orthof(2); - } - - std::cout << "old calibration matrix: \n" << calibration << "\n"; - - Matrix4f update; - update << updateScale, updateBias, Vector4f::UnitW().transpose(); - std::cout << "new calibration matrix update: \n" << update << "\n"; - - calibration = update * calibration; - - if (checkOffsets(updateBias) && checkScaleFactors(updateScale.diagonal())) { - // Apply the new calibration - vectorToTuple(scale, calibration.diagonal().start<3>()); - vectorToTuple(bias, calibration.col(3).start<3>()); - - if (ortho) { - ortho->setDouble(calibration(0, 1), 0); - ortho->setDouble(calibration(0, 2), 1); - ortho->setDouble(calibration(1, 2), 2); - } - return true; - } - else { - // Give the user the calibration data and restore their settings. - std::ostringstream msg; - msg << "Scale factors and/or offsets are out of range.\n"; - msg << "Please see the troubleshooting section of the manual and retry.\n\n" - "The following values were computed:\n"; - msg << qPrintable(scale->getName()) << ": " - << calibration.diagonal().start<3>().transpose() << "\n"; - vectorToTuple(scale, oldScale); - - if (ortho) { - msg << qPrintable(ortho->getName()) << ": " - << calibration(0,1) << ", " << calibration(0,2) << ", " << calibration(1,2) << "\n"; - vectorToTuple(ortho, oldOrtho); - } - - msg << qPrintable(bias->getName()) << ": " - << calibration.col(3).start<3>().transpose() << "\n"; - vectorToTuple(bias, oldBias); - - m_ahrs->sixPointCalibInstructions->append(msg.str().c_str()); - return false; - } -} - -FORCE_ALIGN_FUNC -void ConfigAHRSWidget::computeScaleBias() -{ - // Extract the local magnetic and gravitational field vectors from HomeLocation. - UAVObject *home = dynamic_cast(getObjectManager()->getObject(QString("HomeLocation"))); - Vector3f localMagField; - localMagField << home->getField("Be")->getValue(0).toDouble(), - home->getField("Be")->getValue(1).toDouble(), - home->getField("Be")->getValue(2).toDouble(); - - float localGravity = home->getField("g_e")->getDouble(); - - Vector3f referenceField = Vector3f::UnitZ()*localGravity; - double noise = 0.04; - Vector3f accelBias; - Matrix3f accelScale; - std::cout << "number of samples: " << n_positions << "\n"; - twostep_bias_scale(accelBias, accelScale, accel_data, n_positions, referenceField, noise*noise); - // Twostep computes an offset from the identity scalar, and a negative bias offset - accelScale += Matrix3f::Identity(); - accelBias = -accelBias; - std::cout << "computed accel bias: " << accelBias.transpose() - << "\ncomputed accel scale:\n" << accelScale<< std::endl; - - // Apply the computed scale factor and bias to each sample - for (int i = 0; i < n_positions; ++i) { - accel_data[i] = accelScale * accel_data[i] + accelBias; - } - - // Magnetometer has excellent orthogonality, so only calibrate the scale factors. - Vector3f magBias; - Vector3f magScale; - noise = 4.0; - twostep_bias_scale(magBias, magScale, mag_data, n_positions, localMagField, noise*noise); - magScale += Vector3f::Ones(); - magBias = -magBias; - std::cout << "computed mag bias: " << magBias.transpose() - << "\ncomputed mag scale:\n" << magScale << std::endl; - - // Apply the computed scale factor and bias to each sample - for (int i = 0; i < n_positions; ++i) { - mag_data[i] = magScale.asDiagonal() * mag_data[i] + magBias; - } - - // Calibrate gyro bias and acceleration sensitivity - Matrix3f accelSensitivity; - Vector3f gyroBias; - gyroscope_calibration(gyroBias, accelSensitivity, gyro_data, accel_data, n_positions); - std::cout << "gyro bias: " << gyroBias.transpose() - << "\ngyro's acceleration sensitivity:\n" << accelSensitivity << std::endl; - - // Calibrate alignment between the accelerometer and magnetometer, taking the mag as the - // reference. - Vector3f accelRotation; - calibration_misalignment(accelRotation, accel_data, -Vector3f::UnitZ()*localGravity, - mag_data, localMagField, n_positions); - std::cout << "magnetometer rotation vector: " << accelRotation.transpose() << std::endl; - - // Update the calibration scalars with a clear message box - m_ahrs->sixPointCalibInstructions->clear(); - UAVObject *obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSCalibration"))); - - - bool success = updateScaleFactors(obj->getField(QString("accel_scale")), - obj->getField(QString("accel_bias")), - obj->getField(QString("accel_ortho")), - accelScale, - accelBias, - saved_accel_scale, - saved_accel_bias, - saved_accel_ortho); - - success &= updateScaleFactors(obj->getField(QString("mag_scale")), - obj->getField(QString("mag_bias")), - NULL, - magScale.asDiagonal(), - magBias, - saved_mag_scale, - saved_mag_bias); - - updateBias(obj->getField(QString("gyro_scale")), - obj->getField(QString("gyro_bias")), - gyroBias); - -#if 0 - // TODO: Enable after v1.0 feature freeze is lifted. - updateRotation(obj->getField(QString("accel_rotation")), accelRotation); -#endif - - obj->updated(); - - position = -1; //set to run again - if (success) - m_ahrs->sixPointCalibInstructions->append("Computed new accel and mag scale and bias."); - -} - -/** - Multi-point calibration mode - */ -FORCE_ALIGN_FUNC -void ConfigAHRSWidget::multiPointCalibrationMode() -{ - cacheCurrentCalibration(); - resetCalibrationDefaults(); - - UAVObject* obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSSettings"))); - UAVObjectField *field = obj->getField(QString("BiasCorrectedRaw")); - field->setValue("FALSE"); - obj->updated(); - - - Thread::usleep(100000); - - gyro_accum_x.clear(); - gyro_accum_y.clear(); - gyro_accum_z.clear(); - - /* Need to get as many AttitudeRaw updates as possible */ - obj = getObjectManager()->getObject(QString("AttitudeRaw")); - initialMdata = obj->getMetadata(); - UAVObject::Metadata mdata = initialMdata; - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; - mdata.flightTelemetryUpdatePeriod = 100; - obj->setMetadata(mdata); - - /* Show instructions and enable controls */ - m_ahrs->sixPointCalibInstructions->clear(); - m_ahrs->sixPointCalibInstructions->append("Stand facing Earth's magnetic N or S. Place the vehicle horizontally facing forward and click save position..."); - displayPlane("plane-horizontal"); - m_ahrs->sixPointsStart->setEnabled(false); - m_ahrs->sixPointsSave->setEnabled(true); - position = 0; - -} - -/** - * Read the current calibration scalars and offsets from the target board, and - * save them for later use. In the event of a calibration failure, if the - * calibration method began by resetting calibration values, they may be - * restored later with this information. - */ -void ConfigAHRSWidget::cacheCurrentCalibration() -{ - UAVObject *obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSCalibration"))); - struct field_t { - const char* field_name; - Vector3f& cache; - } fields[] = { - { "accel_scale", this->saved_accel_scale }, - { "accel_bias", this->saved_accel_bias }, - { "accel_ortho", this->saved_accel_ortho }, -// TODO: Enable after V1.0 feature freeze is lifted. -// { "accel_rotation", this->saved_accel_rotation }, - { "gyro_bias", this->saved_gyro_bias }, - { "mag_scale", this->saved_mag_scale }, - { "mag_bias", this->saved_mag_bias }, - { NULL, this->saved_mag_bias }, // sentinnel - }; - for (field_t* i = fields; i->field_name != NULL; ++i) { - UAVObjectField* field = obj->getField(QString(i->field_name)); - if (field) { - i->cache = tupleToVector(field); - } - else { - qDebug() << "WARNING: AHRSCalibration field not found: " << i->field_name << "\n"; - } - } -} - -/** - * Reset all calibration scalars to their default values. - */ -void ConfigAHRSWidget::resetCalibrationDefaults() -{ - UAVObject *obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSCalibration"))); - - // set accels to unity gain - UAVObjectField *field = obj->getField(QString("accel_scale")); - // TODO: Figure out how to load these directly from the saved metadata - // about default values - field->setDouble(0.0359, 0); - field->setDouble(0.0359, 1); - field->setDouble(0.0359, 2); - - field = obj->getField(QString("accel_bias")); - field->setDouble(-73.5, 0); - field->setDouble(-73.5, 1); - field->setDouble(73.5, 2); - - field = obj->getField(QString("accel_ortho")); - for (int i = 0; i < 3; ++i) { - field->setDouble(0, i); - } - - field = obj->getField(QString("gyro_bias")); - UAVObjectField *field2 = obj->getField(QString("gyro_scale")); - field->setDouble(28/-0.017*field2->getDouble(0),0); - field->setDouble(-28/0.017*field2->getDouble(1),1); - field->setDouble(28/-0.017*field2->getDouble(2),2); - - field = obj->getField(QString("mag_scale")); - for (int i = 0; i < 3; ++i) { - field->setDouble(-1, i); - } - - field = obj->getField(QString("mag_bias")); - for (int i = 0; i < 3; ++i) { - field->setDouble(0, i); - } - -#if 0 - // TODO: Enable after v1.0 feature freeze is lifted. - field = obj->getField(QString("accel_rotation")); - for (int i = 0; i < 3; ++i) { - field->setDouble(0, i); - } -#endif - obj->updated(); -} - -/** - Rotate the paper plane - */ -void ConfigAHRSWidget::displayPlane(QString elementID) -{ - paperplane->setElementId(elementID); - m_ahrs->sixPointsHelp->setSceneRect(paperplane->boundingRect()); - m_ahrs->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); - -} - - -/** - Draws the sensor variances bargraph - */ -void ConfigAHRSWidget::drawVariancesGraph() -{ - UAVObject *obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSCalibration"))); - // Now update size of all the graphs - // I have not found a way to do this elegantly... - UAVObjectField *field = obj->getField(QString("accel_var")); - // The expected range is from 1E-6 to 1E-1 - double steps = 6; // 6 bars on the graph - float accel_x_var = -1/steps*(1+steps+log10(field->getValue(0).toFloat())); - accel_x->setTransform(QTransform::fromScale(1,accel_x_var),false); - float accel_y_var = -1/steps*(1+steps+log10(field->getValue(1).toFloat())); - accel_y->setTransform(QTransform::fromScale(1,accel_y_var),false); - float accel_z_var = -1/steps*(1+steps+log10(field->getValue(2).toFloat())); - accel_z->setTransform(QTransform::fromScale(1,accel_z_var),false); - - field = obj->getField(QString("gyro_var")); - float gyro_x_var = -1/steps*(1+steps+log10(field->getValue(0).toFloat())); - gyro_x->setTransform(QTransform::fromScale(1,gyro_x_var),false); - float gyro_y_var = -1/steps*(1+steps+log10(field->getValue(1).toFloat())); - gyro_y->setTransform(QTransform::fromScale(1,gyro_y_var),false); - float gyro_z_var = -1/steps*(1+steps+log10(field->getValue(2).toFloat())); - gyro_z->setTransform(QTransform::fromScale(1,gyro_z_var),false); - - // Scale by 1e-3 because mag vars are much higher. - // TODO: Really? This is the scale factor from mG to T - field = obj->getField(QString("mag_var")); - float mag_x_var = -1/steps*(1+steps+log10(1e-3*field->getValue(0).toFloat())); - mag_x->setTransform(QTransform::fromScale(1,mag_x_var),false); - float mag_y_var = -1/steps*(1+steps+log10(1e-3*field->getValue(1).toFloat())); - mag_y->setTransform(QTransform::fromScale(1,mag_y_var),false); - float mag_z_var = -1/steps*(1+steps+log10(1e-3*field->getValue(2).toFloat())); - mag_z->setTransform(QTransform::fromScale(1,mag_z_var),false); - -} - -/** - Request current settings from the AHRS - */ -void ConfigAHRSWidget::refreshValues() -{ - - UAVObject *obj = getObjectManager()->getObject(QString("AHRSSettings")); - UAVObjectField *field = obj->getField(QString("Algorithm")); - if (field) - m_ahrs->algorithm->setCurrentIndex(m_ahrs->algorithm->findText(field->getValue().toString())); - drawVariancesGraph(); - - obj = getObjectManager()->getObject(QString("HomeLocation")); - field = obj->getField(QString("Set")); - if (field) - m_ahrs->homeLocationSet->setEnabled(field->getValue().toBool()); - - m_ahrs->ahrsCalibStart->setEnabled(true); - m_ahrs->sixPointsStart->setEnabled(true); - m_ahrs->accelBiasStart->setEnabled(true); - m_ahrs->startDriftCalib->setEnabled(true); - - m_ahrs->calibInstructions->setText(QString("Press \"Start\" above to calibrate.")); - -} - -/** - Enables/disables the Home Location saving button depending on whether the - home location is set-able - */ -void ConfigAHRSWidget::enableHomeLocSave(UAVObject * obj) -{ - UAVObjectField *field = obj->getField(QString("Set")); - if (field) { - m_ahrs->homeLocationSet->setEnabled(field->getValue().toBool()); - m_ahrs->sixPointsStart->setEnabled(obj->getField("Set")->getValue().toBool()); - } -} - - -/** - Save current settings to RAM - */ -void ConfigAHRSWidget::ahrsSettingsSaveRAM() -{ - UAVDataObject *obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSSettings"))); - UAVObjectField *field = obj->getField(QString("Algorithm")); - field->setValue(m_ahrs->algorithm->currentText()); - obj->updated(); - obj = dynamic_cast(getObjectManager()->getObject(QString("HomeLocation"))); - field = obj->getField(QString("Set")); - if (m_ahrs->homeLocationSet->isChecked()) - field->setValue(QString("TRUE")); - else - field->setValue(QString("FALSE")); - obj->updated(); - -} - -/** -Save AHRS Settings and home location to SD - */ -void ConfigAHRSWidget::ahrsSettingsSaveSD() -{ - ahrsSettingsSaveRAM(); - UAVDataObject *obj = dynamic_cast(getObjectManager()->getObject(QString("HomeLocation"))); - saveObjectToSD(obj); - obj = dynamic_cast(getObjectManager()->getObject(QString("AHRSSettings"))); - saveObjectToSD(obj); - -} - -void ConfigAHRSWidget::openHelp() -{ - - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/INS+Configuration", QUrl::StrictMode) ); -} - -/** - @} - @} - */ diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index eece2e214..3e757de63 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -89,6 +89,8 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent connect(m_camerastabilization->camerastabilizationSaveRAM, SIGNAL(clicked()), this, SLOT(applySettings())); connect(m_camerastabilization->camerastabilizationSaveSD, SIGNAL(clicked()), this, SLOT(saveSettings())); connect(m_camerastabilization->camerastabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + + disableMouseWheelEvents(); } ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget() diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h index 41fd5dc4d..743435adb 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h @@ -41,7 +41,6 @@ class ConfigCameraStabilizationWidget: public ConfigTaskWidget public: ConfigCameraStabilizationWidget(QWidget *parent = 0); ~ConfigCameraStabilizationWidget(); - private: Ui_CameraStabilizationWidget *m_camerastabilization; virtual void enableControls(bool enable); diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index 4ffabef66..10064b835 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -33,6 +33,8 @@ #include #include #include +#include "accels.h" +#include "gyros.h" ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) : ConfigTaskWidget(parent), @@ -61,25 +63,29 @@ ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget() delete ui; } -void ConfigCCAttitudeWidget::attitudeRawUpdated(UAVObject * obj) { +void ConfigCCAttitudeWidget::accelsUpdated(UAVObject * obj) { QMutexLocker locker(&startStop); ui->zeroBiasProgress->setValue((float) updates / NUM_ACCEL_UPDATES * 100); if(updates < NUM_ACCEL_UPDATES) { updates++; - UAVObjectField * field = obj->getField(QString("accels")); - x_accum.append(field->getDouble(0)); - y_accum.append(field->getDouble(1)); - z_accum.append(field->getDouble(2)); - field = obj->getField(QString("gyros")); - x_gyro_accum.append(field->getDouble(0)); - y_gyro_accum.append(field->getDouble(1)); - z_gyro_accum.append(field->getDouble(2));; + Accels * accels = Accels::GetInstance(getObjectManager()); + Accels::DataFields accelsData = accels->getData(); + x_accum.append(accelsData.x); + y_accum.append(accelsData.y); + z_accum.append(accelsData.z); + + Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Gyros::DataFields gyrosData = gyros->getData(); + + x_gyro_accum.append(gyrosData.x); + y_gyro_accum.append(gyrosData.y); + z_gyro_accum.append(gyrosData.z); } else if ( updates == NUM_ACCEL_UPDATES ) { updates++; timer.stop(); - disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(attitudeRawUpdated(UAVObject*))); + disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(accelsUpdated(UAVObject*))); disconnect(&timer,SIGNAL(timeout()),this,SLOT(timeout())); float x_bias = listMean(x_accum) / ACCEL_SCALE; @@ -101,7 +107,6 @@ void ConfigCCAttitudeWidget::attitudeRawUpdated(UAVObject * obj) { attitudeSettingsData.GyroBias[2] = -z_gyro_bias; attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE; AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); - } else { // Possible to get here if weird threading stuff happens. Just ignore updates. qDebug("Unexpected accel update received."); @@ -110,8 +115,8 @@ void ConfigCCAttitudeWidget::attitudeRawUpdated(UAVObject * obj) { void ConfigCCAttitudeWidget::timeout() { QMutexLocker locker(&startStop); - UAVDataObject * obj = dynamic_cast(getObjectManager()->getObject(QString("AttitudeRaw"))); - disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(attitudeRawUpdated(UAVObject*))); + UAVDataObject * obj = Accels::GetInstance(getObjectManager()); + disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(accelsUpdated(UAVObject*))); disconnect(&timer,SIGNAL(timeout()),this,SLOT(timeout())); QMessageBox msgBox; @@ -139,8 +144,8 @@ void ConfigCCAttitudeWidget::startAccelCalibration() { AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); // Set up to receive updates - UAVDataObject * obj = dynamic_cast(getObjectManager()->getObject(QString("AttitudeRaw"))); - connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(attitudeRawUpdated(UAVObject*))); + UAVDataObject * obj = Accels::GetInstance(getObjectManager()); + connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(accelsUpdated(UAVObject*))); // Set up timeout timer timer.start(10000); @@ -149,7 +154,7 @@ void ConfigCCAttitudeWidget::startAccelCalibration() { // Speed up updates initialMdata = obj->getMetadata(); UAVObject::Metadata mdata = initialMdata; - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); mdata.flightTelemetryUpdatePeriod = 100; obj->setMetadata(mdata); @@ -168,3 +173,10 @@ void ConfigCCAttitudeWidget::enableControls(bool enable) ConfigTaskWidget::enableControls(enable); } + +void ConfigCCAttitudeWidget::updateObjectsFromWidgets() +{ + ConfigTaskWidget::updateObjectsFromWidgets(); + + ui->zeroBiasProgress->setValue(0); +} diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h index 0d0581ba3..28d389df6 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h @@ -46,8 +46,10 @@ public: explicit ConfigCCAttitudeWidget(QWidget *parent = 0); ~ConfigCCAttitudeWidget(); + virtual void updateObjectsFromWidgets(); + private slots: - void attitudeRawUpdated(UAVObject * obj); + void accelsUpdated(UAVObject * obj); void timeout(); void startAccelCalibration(); void openHelp(); diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index 95dc176a4..c12dbaee8 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -25,7 +25,6 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "configahrswidget.h" #include "configgadgetwidget.h" #include "configvehicletypewidget.h" @@ -37,6 +36,8 @@ #include "configtxpidwidget.h" #include "config_pro_hw_widget.h" #include "config_cc_hw_widget.h" +#include "configpipxtremewidget.h" +#include "configrevowidget.h" #include "defaultattitudewidget.h" #include "defaulthwsettingswidget.h" #include "uavobjectutilmanager.h" @@ -78,7 +79,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) ftw->insertTab(ConfigGadgetWidget::output, qwd, QIcon(":/configgadget/images/Servo.png"), QString("Output")); qwd = new DefaultAttitudeWidget(this); - ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); qwd = new ConfigStabilizationWidget(this); ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, QIcon(":/configgadget/images/gyroscope.png"), QString("Stabilization")); @@ -89,9 +90,6 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) qwd = new ConfigTxPIDWidget(this); ftw->insertTab(ConfigGadgetWidget::txpid, qwd, QIcon(":/configgadget/images/txpid.png"), QString("TxPID")); -// qwd = new ConfigPipXtremeWidget(this); -// ftw->insertTab(5, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme")); - // ********************* // Listen to autopilot connection events @@ -107,6 +105,19 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) help = 0; connect(ftw,SIGNAL(currentAboutToShow(int,bool*)),this,SLOT(tabAboutToChange(int,bool*)));//,Qt::BlockingQueuedConnection); + // Connect to the PipXStatus object updates + UAVObjectManager *objManager = pm->getObject(); + pipxStatusObj = dynamic_cast(objManager->getObject("PipXStatus")); + if (pipxStatusObj != NULL ) { + connect(pipxStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updatePipXStatus(UAVObject*))); + } else { + qDebug() << "Error: Object is unknown (PipXStatus)."; + } + + // Create the timer that is used to timeout the connection to the PipX. + pipxTimeout = new QTimer(this); + connect(pipxTimeout, SIGNAL(timeout()),this,SLOT(onPipxtremeDisconnect())); + pipxConnected = false; } ConfigGadgetWidget::~ConfigGadgetWidget() @@ -124,9 +135,9 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event) void ConfigGadgetWidget::onAutopilotDisconnect() { ftw->setCurrentIndex(ConfigGadgetWidget::hardware); - ftw->removeTab(ConfigGadgetWidget::ins); + ftw->removeTab(ConfigGadgetWidget::sensors); QWidget *qwd = new DefaultAttitudeWidget(this); - ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); ftw->removeTab(ConfigGadgetWidget::hardware); qwd = new DefaultHwSettingsWidget(this); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); @@ -144,24 +155,36 @@ void ConfigGadgetWidget::onAutopilotConnect() { UAVObjectUtilManager* utilMngr = pm->getObject(); if (utilMngr) { int board = utilMngr->getBoardModel(); - qDebug() << "Board model: " << board; if ((board & 0xff00) == 1024) { // CopterControl family // Delete the INS panel, replace with CC Panel: ftw->setCurrentIndex(ConfigGadgetWidget::hardware); - ftw->removeTab(ConfigGadgetWidget::ins); + ftw->removeTab(ConfigGadgetWidget::sensors); QWidget *qwd = new ConfigCCAttitudeWidget(this); - ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("Attitude")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("Attitude")); ftw->removeTab(ConfigGadgetWidget::hardware); qwd = new ConfigCCHWWidget(this); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); ftw->setCurrentIndex(ConfigGadgetWidget::hardware); } else if ((board & 0xff00) == 256 ) { // Mainboard family + Q_ASSERT(0); + /* ftw->setCurrentIndex(ConfigGadgetWidget::hardware); - ftw->removeTab(ConfigGadgetWidget::ins); + ftw->removeTab(ConfigGadgetWidget::sensors); QWidget *qwd = new ConfigAHRSWidget(this); - ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); + ftw->removeTab(ConfigGadgetWidget::hardware); + qwd = new ConfigProHWWidget(this); + ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); + ftw->setCurrentIndex(ConfigGadgetWidget::hardware); + */ + } else if ((board & 0xff00) == 0x0900) { + // Revolution sensor calibration + ftw->setCurrentIndex(ConfigGadgetWidget::hardware); + ftw->removeTab(ConfigGadgetWidget::sensors); + QWidget *qwd = new ConfigRevoWidget(this); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("Revo")); ftw->removeTab(ConfigGadgetWidget::hardware); qwd = new ConfigProHWWidget(this); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); @@ -190,5 +213,27 @@ void ConfigGadgetWidget::tabAboutToChange(int i,bool * proceed) } } +/*! + \brief Called by updates to @PipXStatus + */ +void ConfigGadgetWidget::updatePipXStatus(UAVObject *object) +{ + // Restart the disconnection timer. + pipxTimeout->start(5000); + if (!pipxConnected) + { + qDebug()<<"ConfigGadgetWidget onPipxtremeConnect"; + QWidget *qwd = new ConfigPipXtremeWidget(this); + ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme")); + ftw->setCurrentIndex(ConfigGadgetWidget::pipxtreme); + pipxConnected = true; + } +} +void ConfigGadgetWidget::onPipxtremeDisconnect() { + qDebug()<<"ConfigGadgetWidget onPipxtremeDisconnect"; + pipxTimeout->stop(); + ftw->removeTab(ConfigGadgetWidget::pipxtreme); + pipxConnected = false; +} diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h index 3c7294eac..9e5156198 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h @@ -48,20 +48,31 @@ class ConfigGadgetWidget: public QWidget public: ConfigGadgetWidget(QWidget *parent = 0); ~ConfigGadgetWidget(); - enum widgetTabs { hardware = 0, aircraft, input, output, ins, stabilization, camerastabilization, txpid }; + enum widgetTabs {hardware=0, aircraft, input, output, sensors, stabilization, camerastabilization, txpid, pipxtreme}; public slots: void onAutopilotConnect(); void onAutopilotDisconnect(); void tabAboutToChange(int i,bool *); + void updatePipXStatus(UAVObject *object); + void onPipxtremeDisconnect(); signals: void autopilotConnected(); void autopilotDisconnected(); + void pipxtremeConnect(); + void pipxtremeDisconnect(); protected: void resizeEvent(QResizeEvent * event); MyTabbedStackWidget *ftw; + +private: + UAVDataObject* pipxStatusObj; + + // A timer that timesout the connction to the PipX. + QTimer *pipxTimeout; + bool pipxConnected; }; #endif // CONFIGGADGETWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 1e8efef1f..4a2130b26 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -604,7 +604,7 @@ void ConfigInputWidget::fastMdata() { manualControlMdata = manualCommandObj->getMetadata(); UAVObject::Metadata mdata = manualControlMdata; - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); mdata.flightTelemetryUpdatePeriod = 150; manualCommandObj->setMetadata(mdata); } diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index 718965f7d..9b3e6e01b 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -27,6 +27,7 @@ #include "configoutputwidget.h" #include "outputchannelform.h" +#include "configvehicletypewidget.h" #include "uavtalk/telemetrymanager.h" @@ -39,9 +40,11 @@ #include #include #include +#include "mixersettings.h" #include "actuatorcommand.h" #include "actuatorsettings.h" #include "systemalarms.h" +#include "systemsettings.h" #include "uavsettingsimportexport/uavsettingsimportexportfactory.h" ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false) @@ -50,15 +53,10 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren m_config->setupUi(this); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); - addUAVObject("ActuatorSettings"); UAVSettingsImportExportFactory * importexportplugin = pm->getObject(); connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(stopTests())); - addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); - addUAVObject("ActuatorSettings"); - // NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10. // Register for ActuatorSettings changes: for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) @@ -73,25 +71,31 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool))); - refreshWidgetsValues(); - - firstUpdate = true; - - connect(m_config->spinningArmed, SIGNAL(toggled(bool)), this, SLOT(setSpinningArmed(bool))); - + // Configure the task widget // Connect the help button connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + + addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); + + // Track the ActuatorSettings object + addUAVObject("ActuatorSettings"); + + // Associate the buttons with their UAVO fields addWidget(m_config->cb_outputRate4); addWidget(m_config->cb_outputRate3); addWidget(m_config->cb_outputRate2); addWidget(m_config->cb_outputRate1); addWidget(m_config->spinningArmed); + disconnect(this, SLOT(refreshWidgetsValues(UAVObject*))); + UAVObjectManager *objManager = pm->getObject(); UAVObject* obj = objManager->getObject(QString("ActuatorCommand")); - if(obj->getMetadata().gcsTelemetryUpdateMode == UAVObject::UPDATEMODE_ONCHANGE) + if(UAVObject::GetGcsTelemetryUpdateMode(obj->getMetadata()) == UAVObject::UPDATEMODE_ONCHANGE) this->setEnabled(false); connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(disableIfNotMe(UAVObject*))); + + refreshWidgetsValues(); } void ConfigOutputWidget::enableControls(bool enable) { @@ -115,7 +119,6 @@ ConfigOutputWidget::~ConfigOutputWidget() */ void ConfigOutputWidget::runChannelTests(bool state) { - qDebug()<<"configoutputwidget runChannelTests"<getData(); @@ -152,10 +155,10 @@ void ConfigOutputWidget::runChannelTests(bool state) { wasItMe=true; accInitialData = mdata; - mdata.flightAccess = UAVObject::ACCESS_READONLY; - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; - mdata.gcsTelemetryAcked = false; - mdata.gcsTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY); + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE); + UAVObject::SetGcsTelemetryAcked(mdata, false); + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE); mdata.gcsTelemetryUpdatePeriod = 100; } else @@ -196,24 +199,6 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str) outputChannelForm->setAssignment(str); } -/** - * Set the "Spin motors at neutral when armed" flag in ActuatorSettings - */ -void ConfigOutputWidget::setSpinningArmed(bool val) -{ - ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager()); - Q_ASSERT(actuatorSettings); - ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData(); - - if(val) - actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_TRUE; - else - actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_FALSE; - - // Apply settings - actuatorSettings->setData(actuatorSettingsData); -} - /** Sends the channel value to the UAV to move the servo. Returns immediately if we are not in testing mode @@ -242,37 +227,35 @@ void ConfigOutputWidget::sendChannelTest(int index, int value) /** Request the current config from the board (RC Output) */ -void ConfigOutputWidget::refreshWidgetsValues() +void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj) { + Q_UNUSED(obj); + bool dirty=isDirty(); - // Reset all channel assignements: - QList outputChannelForms = findChildren(); - foreach(OutputChannelForm *outputChannelForm, outputChannelForms) - { - outputChannelForm->setAssignment("-"); - } - - // FIXME: Use static accessor method for retrieving channel assignments - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - Q_ASSERT(pm); - UAVObjectManager *objManager = pm->getObject(); - Q_ASSERT(objManager); - - // Get the channel assignements: - UAVDataObject * obj = dynamic_cast(objManager->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - if (field->getUnits().contains("channel")) { - assignOutputChannel(obj,field->getName()); - } - } - + // Get Actuator Settings ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager()); Q_ASSERT(actuatorSettings); ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData(); + // get channel descriptions + QStringList ChannelDesc = ConfigVehicleTypeWidget::getChannelDescriptions(); + + // Initialize output forms + QList outputChannelForms = findChildren(); + foreach(OutputChannelForm *outputChannelForm, outputChannelForms) + { + outputChannelForm->setAssignment(ChannelDesc[outputChannelForm->index()]); + + // init min,max,neutral + int minValue = actuatorSettingsData.ChannelMin[outputChannelForm->index()]; + int maxValue = actuatorSettingsData.ChannelMax[outputChannelForm->index()]; + outputChannelForm->minmax(minValue, maxValue); + + int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()]; + outputChannelForm->neutral(neutral); + } + // Get the SpinWhileArmed setting m_config->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE); @@ -288,6 +271,8 @@ void ConfigOutputWidget::refreshWidgetsValues() m_config->cb_outputRate1->setCurrentIndex(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))); m_config->cb_outputRate2->setCurrentIndex(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))); + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pm); UAVObjectUtilManager* utilMngr = pm->getObject(); if (utilMngr) { int board = utilMngr->getBoardModel(); @@ -338,8 +323,6 @@ void ConfigOutputWidget::refreshWidgetsValues() int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()]; outputChannelForm->neutral(neutral); } - - setDirty(dirty); } /** @@ -347,26 +330,36 @@ void ConfigOutputWidget::refreshWidgetsValues() */ void ConfigOutputWidget::updateObjectsFromWidgets() { + emit updateObjectsFromWidgetsRequested(); + ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager()); Q_ASSERT(actuatorSettings); - ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData(); + if(actuatorSettings) { + ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData(); - // Set channel ranges - QList outputChannelForms = findChildren(); - foreach(OutputChannelForm *outputChannelForm, outputChannelForms) - { - actuatorSettingsData.ChannelMax[outputChannelForm->index()] = outputChannelForm->max(); - actuatorSettingsData.ChannelMin[outputChannelForm->index()] = outputChannelForm->min(); - actuatorSettingsData.ChannelNeutral[outputChannelForm->index()] = outputChannelForm->neutral(); + // Set channel ranges + QList outputChannelForms = findChildren(); + foreach(OutputChannelForm *outputChannelForm, outputChannelForms) + { + actuatorSettingsData.ChannelMax[outputChannelForm->index()] = outputChannelForm->max(); + actuatorSettingsData.ChannelMin[outputChannelForm->index()] = outputChannelForm->min(); + actuatorSettingsData.ChannelNeutral[outputChannelForm->index()] = outputChannelForm->neutral(); + } + + // Set update rates + actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt(); + + if(m_config->spinningArmed->isChecked() == true) + actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_TRUE; + else + actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_FALSE; + + // Apply settings + actuatorSettings->setData(actuatorSettingsData); } - - // Set update rates - actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt(); - // Apply settings - actuatorSettings->setData(actuatorSettingsData); } void ConfigOutputWidget::openHelp() @@ -382,7 +375,7 @@ void ConfigOutputWidget::stopTests() void ConfigOutputWidget::disableIfNotMe(UAVObject* obj) { - if(obj->getMetadata().gcsTelemetryUpdateMode == UAVObject::UPDATEMODE_ONCHANGE) + if(UAVObject::GetGcsTelemetryUpdateMode(obj->getMetadata()) == UAVObject::UPDATEMODE_ONCHANGE) { if(!wasItMe) this->setEnabled(false); diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h index b20839aa4..9a347d3f9 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h @@ -33,6 +33,7 @@ #include "uavobjectmanager.h" #include "uavobject.h" #include "uavobjectutilmanager.h" +#include "cfg_vehicletypes/vehicleconfig.h" #include #include @@ -57,23 +58,19 @@ private: void assignChannel(UAVDataObject *obj, QString str); void assignOutputChannel(UAVDataObject *obj, QString str); - OutputChannelForm* getOutputChannelForm(const int index) const; - + OutputChannelForm* getOutputChannelForm(const int index) const; int mccDataRate; UAVObject::Metadata accInitialData; - bool firstUpdate; - bool wasItMe; private slots: void stopTests(); void disableIfNotMe(UAVObject *obj); - virtual void refreshWidgetsValues(); + virtual void refreshWidgetsValues(UAVObject * obj=NULL); void updateObjectsFromWidgets(); void runChannelTests(bool state); void sendChannelTest(int index, int value); - void setSpinningArmed(bool val); void openHelp(); protected: void enableControls(bool enable); diff --git a/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp new file mode 100644 index 000000000..fb1223607 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp @@ -0,0 +1,317 @@ +/** +****************************************************************************** +* +* @file configtxpidswidget.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @addtogroup GCSPlugins GCS Plugins +* @{ +* @addtogroup ConfigPlugin Config Plugin +* @{ +* @brief The Configuration Gadget used to configure the PipXtreme +*****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "configpipxtremewidget.h" + +#include +#include + +ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget(parent) +{ + m_pipx = new Ui_PipXtremeWidget(); + m_pipx->setupUi(this); + + // Connect to the PipXStatus object updates + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + pipxStatusObj = dynamic_cast(objManager->getObject("PipXStatus")); + if (pipxStatusObj != NULL ) { + connect(pipxStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateStatus(UAVObject*))); + } else { + qDebug() << "Error: Object is unknown (PipXStatus)."; + } + + // Connect to the PipXSettings object updates + pipxSettingsObj = dynamic_cast(objManager->getObject("PipXSettings")); + if (pipxSettingsObj != NULL ) { + connect(pipxSettingsObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateSettings(UAVObject*))); + } else { + qDebug() << "Error: Object is unknown (PipXSettings)."; + } + + addApplySaveButtons(m_pipx->Apply, m_pipx->Save); + + addUAVObjectToWidgetRelation("PipXSettings", "TelemetryConfig", m_pipx->TelemPortConfig); + addUAVObjectToWidgetRelation("PipXSettings", "TelemetrySpeed", m_pipx->TelemPortSpeed); + addUAVObjectToWidgetRelation("PipXSettings", "FlexiConfig", m_pipx->FlexiPortConfig); + addUAVObjectToWidgetRelation("PipXSettings", "FlexiSpeed", m_pipx->FlexiPortSpeed); + addUAVObjectToWidgetRelation("PipXSettings", "VCPConfig", m_pipx->VCPConfig); + addUAVObjectToWidgetRelation("PipXSettings", "VCPSpeed", m_pipx->VCPSpeed); + addUAVObjectToWidgetRelation("PipXSettings", "RFSpeed", m_pipx->MaxRFDatarate); + addUAVObjectToWidgetRelation("PipXSettings", "MaxRFPower", m_pipx->MaxRFTxPower); + addUAVObjectToWidgetRelation("PipXSettings", "SendTimeout", m_pipx->SendTimeout); + addUAVObjectToWidgetRelation("PipXSettings", "MinPacketSize", m_pipx->MinPacketSize); + addUAVObjectToWidgetRelation("PipXSettings", "FrequencyCalibration", m_pipx->FrequencyCalibration); + addUAVObjectToWidgetRelation("PipXSettings", "Frequency", m_pipx->Frequency); + + addUAVObjectToWidgetRelation("PipXStatus", "MinFrequency", m_pipx->MinFrequency); + addUAVObjectToWidgetRelation("PipXStatus", "MaxFrequency", m_pipx->MaxFrequency); + addUAVObjectToWidgetRelation("PipXStatus", "FrequencyStepSize", m_pipx->FrequencyStepSize); + addUAVObjectToWidgetRelation("PipXStatus", "AFC", m_pipx->RxAFC); + addUAVObjectToWidgetRelation("PipXStatus", "Retries", m_pipx->Retries); + addUAVObjectToWidgetRelation("PipXStatus", "Errors", m_pipx->Errors); + addUAVObjectToWidgetRelation("PipXStatus", "UAVTalkErrors", m_pipx->UAVTalkErrors); + addUAVObjectToWidgetRelation("PipXStatus", "Resets", m_pipx->Resets); + addUAVObjectToWidgetRelation("PipXStatus", "Dropped", m_pipx->Dropped); + addUAVObjectToWidgetRelation("PipXStatus", "RXRate", m_pipx->RXRate); + addUAVObjectToWidgetRelation("PipXStatus", "TXRate", m_pipx->TXRate); + + // Connect to the pair ID radio buttons. + connect(m_pipx->PairSelect1, SIGNAL(toggled(bool)), this, SLOT(pair1Toggled(bool))); + connect(m_pipx->PairSelect2, SIGNAL(toggled(bool)), this, SLOT(pair2Toggled(bool))); + connect(m_pipx->PairSelect3, SIGNAL(toggled(bool)), this, SLOT(pair3Toggled(bool))); + connect(m_pipx->PairSelect4, SIGNAL(toggled(bool)), this, SLOT(pair4Toggled(bool))); + + //Add scroll bar when necessary + QScrollArea *scroll = new QScrollArea; + scroll->setWidget(m_pipx->frame_3); + m_pipx->verticalLayout_3->addWidget(scroll); + + // Request and update of the setting object. + settingsUpdated = false; + //pipxSettingsObj->requestUpdate(); + + disableMouseWheelEvents(); +} + +ConfigPipXtremeWidget::~ConfigPipXtremeWidget() +{ + // Do nothing +} + +void ConfigPipXtremeWidget::refreshValues() +{ +} + +void ConfigPipXtremeWidget::applySettings() +{ + PipXSettings *pipxSettings = PipXSettings::GetInstance(getObjectManager()); + PipXSettings::DataFields pipxSettingsData = pipxSettings->getData(); + + // Get the pair ID. + quint32 pairID = 0; + bool okay; + if (m_pipx->PairSelect1->isChecked()) + pairID = m_pipx->PairID1->text().toUInt(&okay, 16); + else if (m_pipx->PairSelect2->isChecked()) + pairID = m_pipx->PairID2->text().toUInt(&okay, 16); + else if (m_pipx->PairSelect3->isChecked()) + pairID = m_pipx->PairID3->text().toUInt(&okay, 16); + else if (m_pipx->PairSelect4->isChecked()) + pairID = m_pipx->PairID4->text().toUInt(&okay, 16); + pipxSettingsData.PairID = pairID; + pipxSettings->setData(pipxSettingsData); +} + +void ConfigPipXtremeWidget::saveSettings() +{ + //applySettings(); + UAVObject *obj = PipXSettings::GetInstance(getObjectManager()); + saveObjectToSD(obj); +} + +/*! + \brief Called by updates to @PipXStatus + */ +void ConfigPipXtremeWidget::updateStatus(UAVObject *object) +{ + + // Request and update of the setting object if we haven't received it yet. + if (!settingsUpdated) + pipxSettingsObj->requestUpdate(); + + // Get the current pairID + PipXSettings *pipxSettings = PipXSettings::GetInstance(getObjectManager()); + quint32 pairID = 0; + if (pipxSettings) + pipxSettings->getPairID(); + + // Update the detected devices. + UAVObjectField* pairIdField = object->getField("PairIDs"); + if (pairIdField) { + quint32 pairid1 = pairIdField->getValue(0).toUInt(); + m_pipx->PairID1->setText(QString::number(pairid1, 16).toUpper()); + m_pipx->PairID1->setEnabled(false); + m_pipx->PairSelect1->setChecked(pairID && (pairID == pairid1)); + m_pipx->PairSelect1->setEnabled(pairid1); + quint32 pairid2 = pairIdField->getValue(1).toUInt(); + m_pipx->PairID2->setText(QString::number(pairIdField->getValue(1).toUInt(), 16).toUpper()); + m_pipx->PairID2->setEnabled(false); + m_pipx->PairSelect2->setChecked(pairID && (pairID == pairid2)); + m_pipx->PairSelect2->setEnabled(pairid2); + quint32 pairid3 = pairIdField->getValue(2).toUInt(); + m_pipx->PairID3->setText(QString::number(pairIdField->getValue(2).toUInt(), 16).toUpper()); + m_pipx->PairID3->setEnabled(false); + m_pipx->PairSelect3->setChecked(pairID && (pairID == pairid3)); + m_pipx->PairSelect3->setEnabled(pairid3); + quint32 pairid4 = pairIdField->getValue(3).toUInt(); + m_pipx->PairID4->setText(QString::number(pairIdField->getValue(3).toUInt(), 16).toUpper()); + m_pipx->PairID4->setEnabled(false); + m_pipx->PairSelect4->setChecked(pairID && (pairID == pairid4)); + m_pipx->PairSelect4->setEnabled(pairid4); + } else { + qDebug() << "PipXtremeGadgetWidget: Count not read PairID field."; + } + UAVObjectField* pairRssiField = object->getField("PairSignalStrengths"); + if (pairRssiField) { + m_pipx->PairSignalStrengthBar1->setValue(pairRssiField->getValue(0).toInt()); + m_pipx->PairSignalStrengthBar2->setValue(pairRssiField->getValue(1).toInt()); + m_pipx->PairSignalStrengthBar3->setValue(pairRssiField->getValue(2).toInt()); + m_pipx->PairSignalStrengthBar4->setValue(pairRssiField->getValue(3).toInt()); + m_pipx->PairSignalStrengthLabel1->setText(QString("%1dB").arg(pairRssiField->getValue(0).toInt())); + m_pipx->PairSignalStrengthLabel2->setText(QString("%1dB").arg(pairRssiField->getValue(1).toInt())); + m_pipx->PairSignalStrengthLabel3->setText(QString("%1dB").arg(pairRssiField->getValue(2).toInt())); + m_pipx->PairSignalStrengthLabel4->setText(QString("%1dB").arg(pairRssiField->getValue(3).toInt())); + } else { + qDebug() << "PipXtremeGadgetWidget: Count not read PairID field."; + } + + // Update the Description field + UAVObjectField* descField = object->getField("Description"); + if (descField) { + /* + * This looks like a binary with a description at the end + * 4 bytes: header: "OpFw" + * 4 bytes: git commit hash (short version of SHA1) + * 4 bytes: Unix timestamp of last git commit + * 2 bytes: target platform. Should follow same rule as BOARD_TYPE and BOARD_REVISION in board define files. + * 26 bytes: commit tag if it is there, otherwise "Unreleased". Zero-padded + * ---- 40 bytes limit --- + * 20 bytes: SHA1 sum of the firmware. + * 40 bytes: free for now. + */ + char buf[PipXStatus::DESCRIPTION_NUMELEM]; + for (unsigned int i = 0; i < 26; ++i) + buf[i] = descField->getValue(i + 14).toChar().toAscii(); + buf[26] = '\0'; + QString descstr(buf); + quint32 gitDate = descField->getValue(11).toChar().toAscii() & 0xFF; + for (int i = 1; i < 4; i++) { + gitDate = gitDate << 8; + gitDate += descField->getValue(11-i).toChar().toAscii() & 0xFF; + } + QString date = QDateTime::fromTime_t(gitDate).toUTC().toString("yyyy-MM-dd HH:mm"); + m_pipx->FirmwareVersion->setText(descstr + " " + date); + } else { + qDebug() << "PipXtremeGadgetWidget: Count not read Description field."; + } + + // Update the serial number field + UAVObjectField* serialField = object->getField("CPUSerial"); + if (serialField) { + char buf[PipXStatus::CPUSERIAL_NUMELEM * 2 + 1]; + for (unsigned int i = 0; i < PipXStatus::CPUSERIAL_NUMELEM; ++i) + { + unsigned char val = serialField->getValue(i).toUInt() >> 4; + buf[i * 2] = ((val < 10) ? '0' : '7') + val; + val = serialField->getValue(i).toUInt() & 0xf; + buf[i * 2 + 1] = ((val < 10) ? '0' : '7') + val; + } + buf[PipXStatus::CPUSERIAL_NUMELEM * 2] = '\0'; + m_pipx->SerialNumber->setText(buf); + } else { + qDebug() << "PipXtremeGadgetWidget: Count not read Description field."; + } + + // Update the DeviceID field + UAVObjectField* idField = object->getField("DeviceID"); + if (idField) { + m_pipx->DeviceID->setText(QString::number(idField->getValue().toUInt(), 16).toUpper()); + } else { + qDebug() << "PipXtremeGadgetWidget: Count not read DeviceID field."; + } + + // Update the link state + UAVObjectField* linkField = object->getField("LinkState"); + if (linkField) { + m_pipx->LinkState->setText(linkField->getValue().toString()); + } else { + qDebug() << "PipXtremeGadgetWidget: Count not read link state field."; + } +} + +/*! + \brief Called by updates to @PipXSettings + */ +void ConfigPipXtremeWidget::updateSettings(UAVObject *object) +{ + if (!settingsUpdated) + { + settingsUpdated = true; + enableControls(true); + } +} + +void ConfigPipXtremeWidget::disconnected() +{ + if (settingsUpdated) + { + settingsUpdated = false; + enableControls(false); + } +} + +void ConfigPipXtremeWidget::pairIDToggled(bool checked, quint8 idx) +{ + if(checked) + { + PipXStatus *pipxStatus = PipXStatus::GetInstance(getObjectManager()); + PipXSettings *pipxSettings = PipXSettings::GetInstance(getObjectManager()); + + if (pipxStatus && pipxSettings) + { + quint32 pairID = pipxStatus->getPairIDs(idx); + if (pairID) + pipxSettings->setPairID(pairID); + } + } +} + +void ConfigPipXtremeWidget::pair1Toggled(bool checked) +{ + pairIDToggled(checked, 0); +} + +void ConfigPipXtremeWidget::pair2Toggled(bool checked) +{ + pairIDToggled(checked, 1); +} + +void ConfigPipXtremeWidget::pair3Toggled(bool checked) +{ + pairIDToggled(checked, 2); +} + +void ConfigPipXtremeWidget::pair4Toggled(bool checked) +{ + pairIDToggled(checked, 3); +} + +/** + @} + @} +*/ diff --git a/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.h b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.h new file mode 100644 index 000000000..b702326e8 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.h @@ -0,0 +1,68 @@ +/** +****************************************************************************** +* +* @file configpipxtremewidget.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @addtogroup GCSPlugins GCS Plugins +* @{ +* @addtogroup ConfigPlugin Config Plugin +* @{ +* @brief The Configuration Gadget used to configure PipXtreme +*****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef CONFIGPIPXTREMEWIDGET_H +#define CONFIGPIPXTREMEWIDGET_H + +#include "ui_pipxtreme.h" +#include "configtaskwidget.h" + +class ConfigPipXtremeWidget : public ConfigTaskWidget +{ + Q_OBJECT + +public: + ConfigPipXtremeWidget(QWidget *parent = 0); + ~ConfigPipXtremeWidget(); + +public slots: + void updateStatus(UAVObject *object1); + void updateSettings(UAVObject *object1); + +private: + Ui_PipXtremeWidget *m_pipx; + + // The PipXtreme status UAVObject + UAVDataObject* pipxStatusObj; + + // The PipXtreme ssettins UAVObject + UAVDataObject* pipxSettingsObj; + + bool settingsUpdated; + +private slots: + void refreshValues(); + void applySettings(); + void saveSettings(); + void disconnected(); + void pairIDToggled(bool checked, quint8 idx); + void pair1Toggled(bool checked); + void pair2Toggled(bool checked); + void pair3Toggled(bool checked); + void pair4Toggled(bool checked); +}; + +#endif // CONFIGTXPIDWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/configplugin.cpp b/ground/openpilotgcs/src/plugins/config/configplugin.cpp index 622b3db9b..30418094c 100644 --- a/ground/openpilotgcs/src/plugins/config/configplugin.cpp +++ b/ground/openpilotgcs/src/plugins/config/configplugin.cpp @@ -145,7 +145,7 @@ void ConfigPlugin::eraseAllSettings() // based on UAVO meta data objper->setData(data); objper->updated(); - QTimer::singleShot(6000,this,SLOT(eraseFailed())); + QTimer::singleShot(FLASH_ERASE_TIMEOUT_MS,this,SLOT(eraseFailed())); } @@ -163,7 +163,7 @@ void ConfigPlugin::eraseFailed() data.Selection = ObjectPersistence::SELECTION_ALLSETTINGS; objper->setData(data); objper->updated(); - QTimer::singleShot(1500,this,SLOT(eraseFailed())); + QTimer::singleShot(FLASH_ERASE_TIMEOUT_MS,this,SLOT(eraseFailed())); } else { disconnect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *))); QMessageBox msgBox; @@ -190,7 +190,7 @@ void ConfigPlugin::eraseDone(UAVObject * obj) if (data.Operation == ObjectPersistence::OPERATION_COMPLETED) { settingsErased = true; msgBox.setText(tr("Settings are now erased.")); - msgBox.setInformativeText(tr("Please now power-cycle your board to complete reset.")); + msgBox.setInformativeText(tr("Please wait for the status LED to begin flashing regularly (up to a minute) then power-cycle your board to complete reset.")); } else { msgBox.setText(tr("Error trying to erase settings.")); msgBox.setInformativeText(tr("Power-cycle your board after removing all blades. Settings might be inconsistent.")); diff --git a/ground/openpilotgcs/src/plugins/config/configplugin.h b/ground/openpilotgcs/src/plugins/config/configplugin.h index 7091ad460..d0d6ec09a 100644 --- a/ground/openpilotgcs/src/plugins/config/configplugin.h +++ b/ground/openpilotgcs/src/plugins/config/configplugin.h @@ -65,6 +65,8 @@ private slots: Core::Command* cmd; bool settingsErased; + static const int FLASH_ERASE_TIMEOUT_MS = 45000; + }; #endif // CONFIGPLUGIN_H diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp new file mode 100644 index 000000000..77cbeb5db --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -0,0 +1,764 @@ +/** + ****************************************************************************** + * + * @file ConfigRevoWidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief The Configuration Gadget used to update settings in the firmware + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "configrevowidget.h" + +#include "math.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define GRAVITY 9.81f +#include "assertions.h" +#include "calibration.h" + +#define sign(x) ((x < 0) ? -1 : 1) + +const double ConfigRevoWidget::maxVarValue = 0.1; + +// ***************** + +class Thread : public QThread +{ +public: + static void usleep(unsigned long usecs) + { + QThread::usleep(usecs); + } +}; + +// ***************** + +ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : + ConfigTaskWidget(parent), + collectingData(false), + position(-1), + m_ui(new Ui_RevoSensorsWidget()) +{ + m_ui->setupUi(this); + + // Initialization of the Paper plane widget + m_ui->sixPointsHelp->setScene(new QGraphicsScene(this)); + + paperplane = new QGraphicsSvgItem(); + paperplane->setSharedRenderer(new QSvgRenderer()); + paperplane->renderer()->load(QString(":/configgadget/images/paper-plane.svg")); + paperplane->setElementId("plane-horizontal"); + m_ui->sixPointsHelp->scene()->addItem(paperplane); + m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect()); + + // Initialization of the Revo sensor noise bargraph graph + m_ui->ahrsBargraph->setScene(new QGraphicsScene(this)); + + QSvgRenderer *renderer = new QSvgRenderer(); + ahrsbargraph = new QGraphicsSvgItem(); + renderer->load(QString(":/configgadget/images/ahrs-calib.svg")); + ahrsbargraph->setSharedRenderer(renderer); + ahrsbargraph->setElementId("background"); + ahrsbargraph->setObjectName("background"); + m_ui->ahrsBargraph->scene()->addItem(ahrsbargraph); + m_ui->ahrsBargraph->setSceneRect(ahrsbargraph->boundingRect()); + + // Initialize the 9 bargraph values: + + QMatrix lineMatrix = renderer->matrixForElement("accel_x"); + QRectF rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_x")); + qreal startX = rect.x(); + qreal startY = rect.y()+ rect.height(); + // maxBarHeight will be used for scaling it later. + maxBarHeight = rect.height(); + // Then once we have the initial location, we can put it + // into a QGraphicsSvgItem which we will display at the same + // place: we do this so that the heading scale can be clipped to + // the compass dial region. + accel_x = new QGraphicsSvgItem(); + accel_x->setSharedRenderer(renderer); + accel_x->setElementId("accel_x"); + m_ui->ahrsBargraph->scene()->addItem(accel_x); + accel_x->setPos(startX, startY); + accel_x->setTransform(QTransform::fromScale(1,0),true); + + lineMatrix = renderer->matrixForElement("accel_y"); + rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_y")); + startX = rect.x(); + startY = rect.y()+ rect.height(); + accel_y = new QGraphicsSvgItem(); + accel_y->setSharedRenderer(renderer); + accel_y->setElementId("accel_y"); + m_ui->ahrsBargraph->scene()->addItem(accel_y); + accel_y->setPos(startX,startY); + accel_y->setTransform(QTransform::fromScale(1,0),true); + + lineMatrix = renderer->matrixForElement("accel_z"); + rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_z")); + startX = rect.x(); + startY = rect.y()+ rect.height(); + accel_z = new QGraphicsSvgItem(); + accel_z->setSharedRenderer(renderer); + accel_z->setElementId("accel_z"); + m_ui->ahrsBargraph->scene()->addItem(accel_z); + accel_z->setPos(startX,startY); + accel_z->setTransform(QTransform::fromScale(1,0),true); + + lineMatrix = renderer->matrixForElement("gyro_x"); + rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_x")); + startX = rect.x(); + startY = rect.y()+ rect.height(); + gyro_x = new QGraphicsSvgItem(); + gyro_x->setSharedRenderer(renderer); + gyro_x->setElementId("gyro_x"); + m_ui->ahrsBargraph->scene()->addItem(gyro_x); + gyro_x->setPos(startX,startY); + gyro_x->setTransform(QTransform::fromScale(1,0),true); + + lineMatrix = renderer->matrixForElement("gyro_y"); + rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_y")); + startX = rect.x(); + startY = rect.y()+ rect.height(); + gyro_y = new QGraphicsSvgItem(); + gyro_y->setSharedRenderer(renderer); + gyro_y->setElementId("gyro_y"); + m_ui->ahrsBargraph->scene()->addItem(gyro_y); + gyro_y->setPos(startX,startY); + gyro_y->setTransform(QTransform::fromScale(1,0),true); + + + lineMatrix = renderer->matrixForElement("gyro_z"); + rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_z")); + startX = rect.x(); + startY = rect.y()+ rect.height(); + gyro_z = new QGraphicsSvgItem(); + gyro_z->setSharedRenderer(renderer); + gyro_z->setElementId("gyro_z"); + m_ui->ahrsBargraph->scene()->addItem(gyro_z); + gyro_z->setPos(startX,startY); + gyro_z->setTransform(QTransform::fromScale(1,0),true); + + lineMatrix = renderer->matrixForElement("mag_x"); + rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_x")); + startX = rect.x(); + startY = rect.y()+ rect.height(); + mag_x = new QGraphicsSvgItem(); + mag_x->setSharedRenderer(renderer); + mag_x->setElementId("mag_x"); + m_ui->ahrsBargraph->scene()->addItem(mag_x); + mag_x->setPos(startX,startY); + mag_x->setTransform(QTransform::fromScale(1,0),true); + + lineMatrix = renderer->matrixForElement("mag_y"); + rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_y")); + startX = rect.x(); + startY = rect.y()+ rect.height(); + mag_y = new QGraphicsSvgItem(); + mag_y->setSharedRenderer(renderer); + mag_y->setElementId("mag_y"); + m_ui->ahrsBargraph->scene()->addItem(mag_y); + mag_y->setPos(startX,startY); + mag_y->setTransform(QTransform::fromScale(1,0),true); + + lineMatrix = renderer->matrixForElement("mag_z"); + rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_z")); + startX = rect.x(); + startY = rect.y()+ rect.height(); + mag_z = new QGraphicsSvgItem(); + mag_z->setSharedRenderer(renderer); + mag_z->setElementId("mag_z"); + m_ui->ahrsBargraph->scene()->addItem(mag_z); + mag_z->setPos(startX,startY); + mag_z->setTransform(QTransform::fromScale(1,0),true); + + // Connect the signals + connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration())); + + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + connect(revoCalibration, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues())); + + connect(m_ui->ahrsSettingsSaveRAM, SIGNAL(clicked()), this, SLOT(SettingsToRAM())); + connect(m_ui->ahrsSettingsSaveSD, SIGNAL(clicked()), this, SLOT(SettingsToFlash())); + connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(sixPointCalibrationMode())); + connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); + + // Leave this timer permanently connected. The timer itself is started and stopped. + connect(&progressBarTimer, SIGNAL(timeout()), this, SLOT(incrementProgress())); + + // Order is important: 1st request the settings (it will also enable the controls) + // then explicitely disable them. They will be re-enabled right afterwards by the + // configgadgetwidget if the autopilot is actually connected. + refreshValues(); + // when the AHRS Widget is instanciated, the autopilot is always connected // enableControls(false); + connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); + connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect())); + + // Connect the help button + connect(m_ui->ahrsHelp, SIGNAL(clicked()), this, SLOT(openHelp())); +} + +ConfigRevoWidget::~ConfigRevoWidget() +{ + // Do nothing +} + + +void ConfigRevoWidget::showEvent(QShowEvent *event) +{ + Q_UNUSED(event) + // Thit fitInView method should only be called now, once the + // widget is shown, otherwise it cannot compute its values and + // the result is usually a ahrsbargraph that is way too small. + m_ui->ahrsBargraph->fitInView(ahrsbargraph, Qt::KeepAspectRatio); + m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); +} + +void ConfigRevoWidget::resizeEvent(QResizeEvent *event) +{ + Q_UNUSED(event) + m_ui->ahrsBargraph->fitInView(ahrsbargraph, Qt::KeepAspectRatio); + m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); +} + + +void ConfigRevoWidget::enableControls(bool enable) +{ + //m_ui->ahrsSettingsSaveRAM->setEnabled(enable); + m_ui->ahrsSettingsSaveSD->setEnabled(enable); +} + +/** + Starts an accelerometer bias calibration. + */ +void ConfigRevoWidget::launchAccelBiasCalibration() +{ + m_ui->accelBiasStart->setEnabled(false); + m_ui->accelBiasProgress->setValue(0); + + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); + revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_FALSE; + revoCalibration->setData(revoCalibrationData); + revoCalibration->updated(); + + accel_accum_x.clear(); + accel_accum_y.clear(); + accel_accum_z.clear(); + + /* Need to get as many AttitudeRaw updates as possible */ + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + initialMdata = accels->getMetadata(); + UAVObject::Metadata mdata = initialMdata; + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = 100; + accels->setMetadata(mdata); + + // Now connect to the accels and mag updates, gather for 100 samples + collectingData = true; + connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(accelBiasattitudeRawUpdated(UAVObject*))); +} + +/** + Updates the accel bias raw values + */ +void ConfigRevoWidget::accelBiasattitudeRawUpdated(UAVObject *obj) +{ + Q_UNUSED(obj); + + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + Accels::DataFields accelsData = accels->getData(); + + // This is necessary to prevent a race condition on disconnect signal and another update + if (collectingData == true) { + accel_accum_x.append(accelsData.x); + accel_accum_y.append(accelsData.y); + accel_accum_z.append(accelsData.z); + } + + m_ui->accelBiasProgress->setValue(m_ui->accelBiasProgress->value()+1); + + if(accel_accum_x.size() >= 100 && collectingData == true) { + collectingData = false; + disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(accelBiasattitudeRawUpdated(UAVObject*))); + m_ui->accelBiasStart->setEnabled(true); + + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); + revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_TRUE; + + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] -= listMean(accel_accum_x); + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] -= listMean(accel_accum_y); + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] -= GRAVITY + listMean(accel_accum_z); + + revoCalibration->setData(revoCalibrationData); + revoCalibration->updated(); + + accels->setMetadata(initialMdata); + } +} + +/** + Increment progress bar for noise measurements (not really based on feedback) + */ +void ConfigRevoWidget::incrementProgress() +{ + m_ui->calibProgress->setValue(m_ui->calibProgress->value()+1); + if (m_ui->calibProgress->value() >= m_ui->calibProgress->maximum()) { + progressBarTimer.stop(); + + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + disconnect(revoCalibration, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(noiseMeasured())); + collectingData = false; + + QErrorMessage err(this); + err.showMessage("Noise measurement timed out. State undetermined. Please power cycle."); + err.exec(); + } +} + +void ConfigRevoWidget::sensorsUpdated(UAVObject * obj) +{ + QMutexLocker lock(&attitudeRawUpdateLock); + + qDebug() << "Data"; + // This is necessary to prevent a race condition on disconnect signal and another update + if (collectingData == true) { + qDebug() << "Collecting"; + if( obj->getObjID() == Accels::OBJID ) { + qDebug() << "Accels"; + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + Accels::DataFields accelsData = accels->getData(); + accel_accum_x.append(accelsData.x); + accel_accum_y.append(accelsData.y); + accel_accum_z.append(accelsData.z); + } else if( obj->getObjID() == Magnetometer::OBJID ) { + qDebug() << "Mag"; + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); + Magnetometer::DataFields magData = mag->getData(); + mag_accum_x.append(magData.x); + mag_accum_y.append(magData.y); + mag_accum_z.append(magData.z); + } else { + Q_ASSERT(0); + } + } + + if(accel_accum_x.size() >= 20 && mag_accum_x.size() >= 20 && collectingData == true) { + collectingData = false; + + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); + disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(sensorsUpdated(UAVObject*))); + disconnect(mag,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(sensorsUpdated(UAVObject*))); + + m_ui->sixPointsSave->setEnabled(true); + + accel_data_x[position] = listMean(accel_accum_x); + accel_data_y[position] = listMean(accel_accum_y); + accel_data_z[position] = listMean(accel_accum_z); + mag_data_x[position] = listMean(mag_accum_x); + mag_data_y[position] = listMean(mag_accum_y); + mag_data_z[position] = listMean(mag_accum_z); + + position = (position + 1) % 6; + if(position == 1) { + m_ui->sixPointCalibInstructions->append("Place with left side down and click save position..."); + displayPlane("plane-left"); + } + if(position == 2) { + m_ui->sixPointCalibInstructions->append("Place upside down and click save position..."); + displayPlane("plane-flip"); + } + if(position == 3) { + m_ui->sixPointCalibInstructions->append("Place with right side down and click save position..."); + displayPlane("plane-right"); + } + if(position == 4) { + m_ui->sixPointCalibInstructions->append("Place with nose up and click save position..."); + displayPlane("plane-up"); + } + if(position == 5) { + m_ui->sixPointCalibInstructions->append("Place with nose down and click save position..."); + displayPlane("plane-down"); + } + if(position == 0) { + computeScaleBias(); + m_ui->sixPointsStart->setEnabled(true); + m_ui->sixPointsSave->setEnabled(false); + + /* Cleanup original settings */ + accels->setMetadata(initialMdata); + mag->setMetadata(initialMdata); + } + } +} + +/** + * Saves the data from the aircraft in one of six positions + */ +void ConfigRevoWidget::savePositionData() +{ + QMutexLocker lock(&attitudeRawUpdateLock); + m_ui->sixPointsSave->setEnabled(false); + + accel_accum_x.clear(); + accel_accum_y.clear(); + accel_accum_z.clear(); + mag_accum_x.clear(); + mag_accum_y.clear(); + mag_accum_z.clear(); + gyro_accum_x.clear(); + gyro_accum_y.clear(); + gyro_accum_z.clear(); + + collectingData = true; + + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); + + connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(sensorsUpdated(UAVObject*))); + connect(mag, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(sensorsUpdated(UAVObject*))); + + m_ui->sixPointCalibInstructions->append("Hold..."); +} + +int LinearEquationsSolving(int nDim, double* pfMatr, double* pfVect, double* pfSolution) +{ + double fMaxElem; + double fAcc; + + int i , j, k, m; + + for(k=0; k<(nDim-1); k++) // base row of matrix + { + // search of line with max element + fMaxElem = fabs( pfMatr[k*nDim + k] ); + m = k; + for(i=k+1; i=0; k--) + { + pfSolution[k] = pfVect[k]; + for(i=(k+1); igetData(); + + // Calibration accel + SixPointInConstFieldCal( GRAVITY, accel_data_x, accel_data_y, accel_data_z, S, b); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = fabs(S[0]); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = fabs(S[1]); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = fabs(S[2]); + + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = -sign(S[0]) * b[0]; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = -sign(S[1]) * b[1]; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = -sign(S[2]) * b[2]; + + // Calibration mag + SixPointInConstFieldCal( 1000, mag_data_x, mag_data_y, mag_data_z, S, b); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = fabs(S[0]); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = fabs(S[1]); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = fabs(S[2]); + + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = -sign(S[0]) * b[0]; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = -sign(S[1]) * b[1]; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = -sign(S[2]) * b[2]; + + revoCalibration->setData(revoCalibrationData); + + position = -1; //set to run again + m_ui->sixPointCalibInstructions->append("Computed accel and mag scale and bias..."); + +} + +/** + Six point calibration mode + */ +void ConfigRevoWidget::sixPointCalibrationMode() +{ + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); + + // Calibration accel + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = 1; + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = 1; + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = 1; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = 0; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = 0; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = 0; + + // Calibration mag + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = 1; + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = 1; + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = 1; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = 0; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = 0; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = 0; + + revoCalibration->setData(revoCalibrationData); + + Thread::usleep(100000); + + gyro_accum_x.clear(); + gyro_accum_y.clear(); + gyro_accum_z.clear(); + accel_accum_x.clear(); + accel_accum_y.clear(); + accel_accum_z.clear(); + mag_accum_x.clear(); + mag_accum_y.clear(); + mag_accum_z.clear(); + + /* Need to get as many accel and mag updates as possible */ + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); + + initialMdata = accels->getMetadata(); + UAVObject::Metadata mdata = initialMdata; + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = 100; + accels->setMetadata(mdata); + + mdata = mag->getMetadata(); + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = 100; + mag->setMetadata(mdata); + + /* Show instructions and enable controls */ + m_ui->sixPointCalibInstructions->clear(); + m_ui->sixPointCalibInstructions->append("Place horizontally and click save position..."); + displayPlane("plane-horizontal"); + m_ui->sixPointsStart->setEnabled(false); + m_ui->sixPointsSave->setEnabled(true); + position = 0; + qDebug() << "Starting"; +} + + + +/** + Rotate the paper plane + */ +void ConfigRevoWidget::displayPlane(QString elementID) +{ + paperplane->setElementId(elementID); + m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect()); + m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); + +} + + +/** + Draws the sensor variances bargraph + */ +void ConfigRevoWidget::drawVariancesGraph() +{ + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); + + // The expected range is from 1E-6 to 1E-1 + double steps = 6; // 6 bars on the graph + float accel_x_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_X])); + accel_x->setTransform(QTransform::fromScale(1,accel_x_var),false); + float accel_y_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_Y])); + accel_y->setTransform(QTransform::fromScale(1,accel_y_var),false); + float accel_z_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_Z])); + accel_z->setTransform(QTransform::fromScale(1,accel_z_var),false); + + float gyro_x_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_X])); + gyro_x->setTransform(QTransform::fromScale(1,gyro_x_var),false); + float gyro_y_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_Y])); + gyro_y->setTransform(QTransform::fromScale(1,gyro_y_var),false); + float gyro_z_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_Z])); + gyro_z->setTransform(QTransform::fromScale(1,gyro_z_var),false); + + // Scale by 1e-3 because mag vars are much higher. + float mag_x_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_X])); + mag_x->setTransform(QTransform::fromScale(1,mag_x_var),false); + float mag_y_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_Y])); + mag_y->setTransform(QTransform::fromScale(1,mag_y_var),false); + float mag_z_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_Z])); + mag_z->setTransform(QTransform::fromScale(1,mag_z_var),false); +} + +/** + Request current settings from the AHRS + */ +void ConfigRevoWidget::refreshValues() +{ + drawVariancesGraph(); + + m_ui->ahrsCalibStart->setEnabled(true); + m_ui->sixPointsStart->setEnabled(true); + m_ui->accelBiasStart->setEnabled(true); + m_ui->startDriftCalib->setEnabled(true); + + m_ui->calibInstructions->setText(QString("Press \"Start\" above to calibrate.")); +} + + +/** + Save current settings to RAM + */ +void ConfigRevoWidget::SettingsToRAM() +{ + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + revoCalibration->updated(); +} + +/** +Save Revo calibration settings to flash + */ +void ConfigRevoWidget::SettingsToFlash() +{ + SettingsToRAM(); + + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + saveObjectToSD(revoCalibration); +} + +void ConfigRevoWidget::openHelp() +{ + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Revo+Configuration", QUrl::StrictMode) ); +} + +/** + @} + @} + */ diff --git a/ground/openpilotgcs/src/plugins/config/configahrswidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h similarity index 60% rename from ground/openpilotgcs/src/plugins/config/configahrswidget.h rename to ground/openpilotgcs/src/plugins/config/configrevowidget.h index 645c63198..82d7025fc 100644 --- a/ground/openpilotgcs/src/plugins/config/configahrswidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -24,12 +24,12 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef CONFIGAHRSWIDGET_H -#define CONFIGAHRSWIDGET_H +#ifndef CONFIGREVOWIDGET_H +#define CONFIGREVOWIDGET_H -#include +#include "ui_revosensors.h" +#include "configtaskwidget.h" -#include "ui_ahrs.h" #include "../uavobjectwidgetutils/configtaskwidget.h" #include "extensionsystem/pluginmanager.h" #include "uavobjectmanager.h" @@ -41,23 +41,22 @@ #include #include -#include +class Ui_Widget; -class ConfigAHRSWidget: public ConfigTaskWidget +class ConfigRevoWidget: public ConfigTaskWidget { Q_OBJECT public: - ConfigAHRSWidget(QWidget *parent = 0); - ~ConfigAHRSWidget(); - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + ConfigRevoWidget(QWidget *parent = 0); + ~ConfigRevoWidget(); private: void drawVariancesGraph(); void displayPlane(QString elementID); virtual void enableControls(bool enable); - Ui_AHRSWidget *m_ahrs; + Ui_RevoSensorsWidget *m_ui; QGraphicsSvgItem *paperplane; QGraphicsSvgItem *ahrsbargraph; QGraphicsSvgItem *accel_x; @@ -75,7 +74,7 @@ private: int progressBarIndex; QTimer progressBarTimer; const static double maxVarValue; - const static int calibrationDelay; + const static int calibrationDelay = 10; bool collectingData; @@ -89,63 +88,26 @@ private: QList mag_accum_y; QList mag_accum_z; - // TODO: Store these in std::vectors - Eigen::Vector3f gyro_data[60]; - Eigen::Vector3f accel_data[60]; - Eigen::Vector3f mag_data[60]; - int position; - int n_positions; + double accel_data_x[6], accel_data_y[6], accel_data_z[6]; + double mag_data_x[6], mag_data_y[6], mag_data_z[6]; UAVObject::Metadata initialMdata; - - void computeGyroDrift(); - - - // Saved parameters for calibration. In the event of a calibration failure, - // the old parameters will be restored. - Eigen::Vector3f saved_gyro_bias; - - Eigen::Vector3f saved_accel_bias; - Eigen::Vector3f saved_accel_scale; - Eigen::Vector3f saved_accel_ortho; - Eigen::Vector3f saved_accel_rotation; - - Eigen::Vector3f saved_mag_scale; - Eigen::Vector3f saved_mag_bias; - - bool - updateScaleFactors(UAVObjectField *scale, - UAVObjectField *bias , - UAVObjectField *ortho, - const Eigen::Matrix3f& updateScale, - const Eigen::Vector3f& updateBias, - const Eigen::Vector3f& oldScale, - const Eigen::Vector3f& oldBias, - const Eigen::Vector3f& oldOrtho = Eigen::Vector3f::Zero()); + int position; private slots: - void enableHomeLocSave(UAVObject *obj); - void launchAHRSCalibration(); - void saveAHRSCalibration(); void openHelp(); void launchAccelBiasCalibration(); - void calibPhase2(); void incrementProgress(); virtual void refreshValues(); //void ahrsSettingsRequest(); - void ahrsSettingsSaveRAM(); - void ahrsSettingsSaveSD(); + void SettingsToRAM(); + void SettingsToFlash(); void savePositionData(); void computeScaleBias(); - void multiPointCalibrationMode(); -// void sixPointCalibrationMode(); // this function no longer exists - void attitudeRawUpdated(UAVObject * obj); + void sixPointCalibrationMode(); + void sensorsUpdated(UAVObject * obj); void accelBiasattitudeRawUpdated(UAVObject*); - void driftCalibrationAttitudeRawUpdated(UAVObject*); - void launchGyroDriftCalibration(); - void resetCalibrationDefaults(); - void cacheCurrentCalibration(); protected: void showEvent(QShowEvent *event); @@ -153,4 +115,4 @@ protected: }; -#endif // ConfigAHRSWidget_H +#endif // ConfigRevoWidget_H diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index f34e40900..331c39e23 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -40,6 +40,11 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa { m_stabilization = new Ui_StabilizationWidget(); m_stabilization->setupUi(this); + + // To bring old style sheet back without adding it manually do this: + // Alternatively apply a global stylesheet to the QGroupBox + // setStyleSheet("QGroupBox {background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); border: 1px outset #999; border-radius: 3; }"); + autoLoadWidgets(); realtimeUpdates=new QTimer(this); connect(m_stabilization->realTimeUpdates_6,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int))); @@ -52,6 +57,26 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa connect(m_stabilization->checkBox_3,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); connect(this,SIGNAL(widgetContentsChanged(QWidget*)),this,SLOT(processLinkedWidgets(QWidget*))); + + disableMouseWheelEvents(); + + // This is needed because new style tries to compact things as much as possible in grid + // and on OSX the widget sizes of PushButtons is reported incorrectly: + // https://bugreports.qt-project.org/browse/QTBUG-14591 + m_stabilization->saveStabilizationToRAM_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->saveStabilizationToSD_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->stabilizationReloadBoardData_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->saveStabilizationToRAM_7->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->saveStabilizationToSD_7->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->pushButton_2->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->pushButton_3->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->pushButton_4->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->pushButton_19->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->pushButton_20->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->pushButton_21->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->pushButton_22->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->pushButton_23->setAttribute(Qt::WA_LayoutUsesWidgetRect); + m_stabilization->pushButton_24->setAttribute(Qt::WA_LayoutUsesWidgetRect); } diff --git a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp index 27df06ef9..30c87bd78 100644 --- a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp @@ -67,6 +67,8 @@ ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent) enableControls(false); populateWidgets(); refreshWidgetsValues(); + + disableMouseWheelEvents(); } ConfigTxPIDWidget::~ConfigTxPIDWidget() diff --git a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h index 9723e141f..14eb5925d 100644 --- a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h @@ -37,7 +37,6 @@ class ConfigTxPIDWidget : public ConfigTaskWidget public: ConfigTxPIDWidget(QWidget *parent = 0); ~ConfigTxPIDWidget(); - private: Ui_TxPIDWidget *m_txpid; diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 62489f54c..19047af55 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -36,10 +36,11 @@ #include #include #include +#include + #include "systemsettings.h" #include "mixersettings.h" #include "actuatorsettings.h" -#include /** Helper delegate for the custom mixer editor table. @@ -103,23 +104,24 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi addUAVObject("MixerSettings"); addUAVObject("ActuatorSettings"); - ffTuningInProgress = false; ffTuningPhase = false; - //Generate list of channels - QStringList channels; - channels << "None"; + //Generate lists of mixerTypeNames, mixerVectorNames, channelNames + channelNames << "None"; for (int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) { + mixerTypes << QString("Mixer%1Type").arg(i+1); mixerVectors << QString("Mixer%1Vector").arg(i+1); - channels << QString("Channel%1").arg(i+1); + channelNames << QString("Channel%1").arg(i+1); } QStringList airframeTypes; airframeTypes << "Fixed Wing" << "Multirotor" << "Helicopter" << "Ground" << "Custom"; m_aircraft->aircraftType->addItems(airframeTypes); - m_aircraft->aircraftType->setCurrentIndex(1); + + m_aircraft->aircraftType->setCurrentIndex(0); //Set default vehicle to Fixed Wing + m_aircraft->airframesWidget->setCurrentIndex(0); // Force the tab index to match QStringList fixedWingTypes; fixedWingTypes << "Elevator aileron rudder" << "Elevon" << "Vtail"; @@ -138,27 +140,13 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi m_aircraft->multirotorFrameType->addItems(multiRotorTypes); m_aircraft->multirotorFrameType->setCurrentIndex(1); //Set default model to "Quad +" - // Now load all the channel assignements - //OLD STYLE: DO IT MANUALLY -// m_aircraft->triYawChannelBox->addItems(channels); -// m_aircraft->gvMotor1ChannelBox->addItems(channels); -// m_aircraft->gvMotor2ChannelBox->addItems(channels); -// m_aircraft->gvSteering1ChannelBox->addItems(channels); -// m_aircraft->gvSteering2ChannelBox->addItems(channels); -// m_aircraft->fwElevator1ChannelBox->addItems(channels); -// m_aircraft->fwElevator2ChannelBox->addItems(channels); -// m_aircraft->fwEngineChannelBox->addItems(channels); -// m_aircraft->fwRudder1ChannelBox->addItems(channels); -// m_aircraft->fwRudder2ChannelBox->addItems(channels); -// m_aircraft->fwAileron1ChannelBox->addItems(channels); -// m_aircraft->fwAileron2ChannelBox->addItems(channels); //NEW STYLE: Loop through the widgets looking for all widgets that have "ChannelBox" in their name // The upshot of this is that ALL new ComboBox widgets for selecting the output channel must have "ChannelBox" in their name foreach(QComboBox *combobox, this->findChildren(QRegExp("\\S+ChannelBo\\S+")))//FOR WHATEVER REASON, THIS DOES NOT WORK WITH ChannelBox. ChannelBo is sufficiently accurate { - combobox->addItems(channels); - } + combobox->addItems(channelNames); + } // Setup the Multirotor picture in the Quad settings interface m_aircraft->quadShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); @@ -188,6 +176,27 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd); } + // create and setup a MultiRotor config widget + m_multirotor = new ConfigMultiRotorWidget(m_aircraft); + m_multirotor->quad = quad; + m_multirotor->uiowner = this; + m_multirotor->setupUI(m_aircraft->multirotorFrameType->currentText()); + + // create and setup a GroundVehicle config widget + m_groundvehicle = new ConfigGroundVehicleWidget(m_aircraft); + m_groundvehicle->setupUI(m_aircraft->groundVehicleType->currentText() ); + + // create and setup a FixedWing config widget + m_fixedwing = new ConfigFixedWingWidget(m_aircraft); + m_fixedwing->setupUI(m_aircraft->fixedWingType->currentText() ); + + // create and setup a Helicopter config widget + m_heli = m_aircraft->widget_3; + m_heli->setupUI(QString("HeliCP")); + + // initialize the ui to show the mixersettings tab + //mdl m_aircraft->tabWidget->setCurrentIndex(0); + //Connect aircraft type selection dropbox to callback function connect(m_aircraft->aircraftType, SIGNAL(currentIndexChanged(int)), this, SLOT(switchAirframeType(int))); @@ -195,6 +204,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString))); connect(m_aircraft->multirotorFrameType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString))); connect(m_aircraft->groundVehicleType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString))); + //mdl connect(m_heli->m_ccpm->ccpmType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString))); //Connect throttle curve reset pushbuttons to reset functions connect(m_aircraft->fwThrottleReset, SIGNAL(clicked()), this, SLOT(resetFwMixer())); @@ -220,19 +230,13 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi connect(m_aircraft->ffTestBox2, SIGNAL(clicked(bool)), this, SLOT(enableFFTest())); connect(m_aircraft->ffTestBox3, SIGNAL(clicked(bool)), this, SLOT(enableFFTest())); - //WHAT DOES THIS DO? - enableControls(false); - refreshWidgetsValues(); - // Connect the help pushbutton connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + enableControls(false); + refreshWidgetsValues(); addToDirtyMonitor(); - - //Initialize GUI tabs //MOVING THIS FROM THE END OF THIS FUNCTION CAN CAUSE RUNTIME ERRORS DUE TO setupMultiRotorUI. WHY? - setupMultiRotorUI( m_aircraft->multirotorFrameType->currentText() ); - setupGroundVehicleUI( m_aircraft->groundVehicleType->currentText() ); - setupFixedWingUI( m_aircraft->fixedWingType->currentText() ); - + + disableMouseWheelEvents(); } @@ -244,13 +248,95 @@ ConfigVehicleTypeWidget::~ConfigVehicleTypeWidget() // Do nothing } +/** + Static function to get currently assigned channelDescriptions + for all known vehicle types; instantiates the appropriate object + then asks it to supply channel descs + */ +QStringList ConfigVehicleTypeWidget::getChannelDescriptions() +{ + int i; + QStringList channelDesc; + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager * objMngr = pm->getObject(); + Q_ASSERT(objMngr); + + // get an instance of systemsettings + SystemSettings * systemSettings = SystemSettings::GetInstance(objMngr); + Q_ASSERT(systemSettings); + SystemSettings::DataFields systemSettingsData = systemSettings->getData(); + + switch (systemSettingsData.AirframeType) + { + // fixed wing + case SystemSettings::AIRFRAMETYPE_FIXEDWING: + case SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON: + case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL: + { + ConfigFixedWingWidget* fixedwing = new ConfigFixedWingWidget(); + channelDesc = fixedwing->getChannelDescriptions(); + } + break; + + // helicp + case SystemSettings::AIRFRAMETYPE_HELICP: + { + ConfigCcpmWidget* heli = new ConfigCcpmWidget(); + channelDesc = heli->getChannelDescriptions(); + } + break; + + //multirotor + case SystemSettings::AIRFRAMETYPE_VTOL: + case SystemSettings::AIRFRAMETYPE_TRI: + case SystemSettings::AIRFRAMETYPE_QUADX: + case SystemSettings::AIRFRAMETYPE_QUADP: + case SystemSettings::AIRFRAMETYPE_OCTOV: + case SystemSettings::AIRFRAMETYPE_OCTOCOAXX: + case SystemSettings::AIRFRAMETYPE_OCTOCOAXP: + case SystemSettings::AIRFRAMETYPE_OCTO: + case SystemSettings::AIRFRAMETYPE_HEXAX: + case SystemSettings::AIRFRAMETYPE_HEXACOAX: + case SystemSettings::AIRFRAMETYPE_HEXA: + { + ConfigMultiRotorWidget* multi = new ConfigMultiRotorWidget(); + channelDesc = multi->getChannelDescriptions(); + } + break; + + // ground + case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLECAR: + case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLEDIFFERENTIAL: + case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLEMOTORCYCLE: + { + ConfigGroundVehicleWidget* ground = new ConfigGroundVehicleWidget(); + channelDesc = ground->getChannelDescriptions(); + } + break; + + default: + { + for (i=0; i < (int)(VehicleConfig::CHANNEL_NUMELEM); i++) + channelDesc.append(QString("-")); + } + break; + } + +// for (i=0; i < channelDesc.count(); i++) +// qDebug() << QString("Channel %0 = %1").arg(i).arg(channelDesc[i]); + + return channelDesc; +} + /** Slot for switching the airframe type. We do it explicitely rather than a signal in the UI, because we want to force a fitInView of the quad shapes. This is because this method (fitinview) only works when the widget is shown. */ -void ConfigVehicleTypeWidget::switchAirframeType(int index){ +void ConfigVehicleTypeWidget::switchAirframeType(int index) +{ m_aircraft->airframesWidget->setCurrentIndex(index); m_aircraft->quadShape->setSceneRect(quad->boundingRect()); m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio); @@ -331,7 +417,6 @@ void ConfigVehicleTypeWidget::toggleRudder2(int index) } } - ///////////////////////////////////////////////////////// /// Feed Forward Testing ///////////////////////////////////////////////////////// @@ -353,7 +438,7 @@ void ConfigVehicleTypeWidget::enableFFTest() UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ManualControlCommand"))); UAVObject::Metadata mdata = obj->getMetadata(); accInitialData = mdata; - mdata.flightAccess = UAVObject::ACCESS_READONLY; + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY); obj->setMetadata(mdata); } // Depending on phase, either move actuator or send FF settings: @@ -525,8 +610,10 @@ void ConfigVehicleTypeWidget::updateCustomThrottle2CurveValue(QList list /** Refreshes the current value of the SystemSettings which holds the aircraft type */ -void ConfigVehicleTypeWidget::refreshWidgetsValues() +void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject * o) { + Q_UNUSED(o); + if(!allObjectsUpdated()) return; @@ -609,7 +696,7 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues() if (frameType.startsWith("FixedWing")) { // Retrieve fixed wing settings - refreshFixedWingWidgetsValues(frameType); + m_fixedwing->refreshWidgetsValues(frameType); } else if (frameType == "Tri" || frameType == "QuadX" || frameType == "QuadP" || @@ -617,17 +704,18 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues() frameType == "Octo" || frameType == "OctoV" || frameType == "OctoCoaxP" || frameType == "OctoCoaxX" ) { // Retrieve multirotor settings - refreshMultiRotorWidgetsValues(frameType); + m_multirotor->refreshWidgetsValues(frameType); } else if (frameType == "HeliCP") { - m_aircraft->widget_3->requestccpmUpdate(); - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Helicopter"));//"Helicopter" + setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Helicopter")); + m_heli->refreshWidgetsValues(frameType); + } else if (frameType.startsWith("GroundVehicle")) { - // Retrieve ground vehicle settings - refreshGroundVehicleWidgetsValues(frameType); + // Retrieve ground vehicle settings + m_groundvehicle->refreshWidgetsValues(frameType); } else if (frameType == "Custom") { - m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Custom")); + setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Custom")); } @@ -641,13 +729,13 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues() */ void ConfigVehicleTypeWidget::setupAirframeUI(QString frameType) { - bool dirty=isDirty(); if(frameType == "FixedWing" || frameType == "Elevator aileron rudder" || frameType == "FixedWingElevon" || frameType == "Elevon" || - frameType == "FixedWingVtail" || frameType == "Vtail"){ - setupFixedWingUI(frameType); - } else if (frameType == "Tri" || frameType == "Tricopter Y" || + frameType == "FixedWingVtail" || frameType == "Vtail"){ + m_fixedwing->setupUI(frameType); + } + else if (frameType == "Tri" || frameType == "Tricopter Y" || frameType == "QuadX" || frameType == "Quad X" || frameType == "QuadP" || frameType == "Quad +" || frameType == "Hexa" || frameType == "Hexacopter" || @@ -655,15 +743,19 @@ void ConfigVehicleTypeWidget::setupAirframeUI(QString frameType) frameType == "HexaCoax" || frameType == "Hexacopter Y6" || frameType == "Octo" || frameType == "Octocopter" || frameType == "OctoV" || frameType == "Octocopter V" || - frameType == "OctoCoaxP" || frameType == "Octo Coax +" ) { + frameType == "OctoCoaxP" || frameType == "Octo Coax +" || + frameType == "OctoCoaxX" || frameType == "Octo Coax X" ) { - //Call multi-rotor setup UI - setupMultiRotorUI(frameType); + //Call multi-rotor setup UI + m_multirotor->setupUI(frameType); } + else if (frameType == "HeliCP") { + m_heli->setupUI(frameType); + } else if (frameType == "GroundVehicleCar" || frameType == "Turnable (car)" || frameType == "GroundVehicleDifferential" || frameType == "Differential (tank)" || - frameType == "GroundVehicleMotorcyle" || frameType == "Motorcycle") { - setupGroundVehicleUI(frameType); + frameType == "GroundVehicleMotorcyle" || frameType == "Motorcycle") { + m_groundvehicle->setupUI(frameType); } //SHOULDN'T THIS BE DONE ONLY IN QUAD SETUP, AND NOT ALL THE REST??? @@ -684,85 +776,72 @@ void ConfigVehicleTypeWidget::resetField(UAVObjectField * field) } } - -/** - Reset actuator values - */ -void ConfigVehicleTypeWidget::resetActuators() -{ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - QList fieldList = obj->getFields(); - // Reset all assignements first: - foreach (UAVObjectField* field, fieldList) { - // NOTE: we assume that all options in ActuatorSettings are a channel assignement - // except for the options called "ChannelBoxXXX" - if (field->getUnits().contains("channel")) { - field->setValue(field->getOptions().last()); - } - } -} - - /** Updates the custom airframe settings based on the current airframe. Note: does NOT ask for an object refresh itself! */ void ConfigVehicleTypeWidget::updateCustomAirframeUI() -{ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - UAVObjectField* field = obj->getField(QString("ThrottleCurve1")); +{ + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + + VehicleConfig* vconfig = new VehicleConfig(); + QList curveValues; - // If the 1st element of the curve is <= -10, then the curve - // is a straight line (that's how the mixer works on the mainboard): - if (field->getValue(0).toInt() <= -10) { - m_aircraft->customThrottle1Curve->initLinearCurve(field->getNumElements(),(double)1); - } else { - double temp=0; - double value; - for (unsigned int i=0; i < field->getNumElements(); i++) { - value=field->getValue(i).toDouble(); - temp+=value; - curveValues.append(value); - } - if(temp==0) - m_aircraft->customThrottle1Curve->initLinearCurve(field->getNumElements(),(double)1); - else - m_aircraft->customThrottle1Curve->initCurve(curveValues); + + // setup throttlecurve 1 + vconfig->getThrottleCurve(mixer,VehicleConfig::MIXER_THROTTLECURVE1,&curveValues); + + int total = 0; + for (int i=0; icustomThrottle1Curve->initLinearCurve(curveValues.length(),(double)1); } - - field = obj->getField(QString("ThrottleCurve2")); - curveValues.clear(); - // If the 1st element of the curve is <= -10, then the curve - // is a straight line (that's how the mixer works on the mainboard): - if (field->getValue(0).toInt() <= -10) { - m_aircraft->customThrottle2Curve->initLinearCurve(field->getNumElements(),(double)1); - } else { - for (unsigned int i=0; i < field->getNumElements(); i++) { - curveValues.append(field->getValue(i).toDouble()); - } + else { + m_aircraft->customThrottle1Curve->initCurve(curveValues); + } + + // setup throttlecurve 2 + vconfig->getThrottleCurve(mixer,VehicleConfig::MIXER_THROTTLECURVE2,&curveValues); + + total = 0; + for (int i=0; icustomThrottle2Curve->initLinearCurve(curveValues.length(),(double)1); + } + else { m_aircraft->customThrottle2Curve->initCurve(curveValues); } - // Update the table: - for (int i=0; i<8; i++) { - field = obj->getField(mixerTypes.at(i)); - QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,i); - QString s = field->getValue().toString(); - q->setCurrentIndex(q->findText(s)); - //bool en = (s != "Disabled"); - field = obj->getField(mixerVectors.at(i)); - int ti = field->getElementNames().indexOf("ThrottleCurve1"); - m_aircraft->customMixerTable->item(1,i)->setText(field->getValue(ti).toString()); - ti = field->getElementNames().indexOf("ThrottleCurve2"); - m_aircraft->customMixerTable->item(2,i)->setText(field->getValue(ti).toString()); - ti = field->getElementNames().indexOf("Roll"); - m_aircraft->customMixerTable->item(3,i)->setText(field->getValue(ti).toString()); - ti = field->getElementNames().indexOf("Pitch"); - m_aircraft->customMixerTable->item(4,i)->setText(field->getValue(ti).toString()); - ti = field->getElementNames().indexOf("Yaw"); - m_aircraft->customMixerTable->item(5,i)->setText(field->getValue(ti).toString()); + + // Update the mixer table: + for (int channel=0; channel<8; channel++) { + UAVObjectField* field = mixer->getField(mixerTypes.at(channel)); + if (field) + { + QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,channel); + if (q) + { + QString s = field->getValue().toString(); + setComboCurrentIndex(q, q->findText(s)); + } + + m_aircraft->customMixerTable->item(1,channel)->setText( + QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1))); + m_aircraft->customMixerTable->item(2,channel)->setText( + QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE2))); + m_aircraft->customMixerTable->item(3,channel)->setText( + QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_ROLL))); + m_aircraft->customMixerTable->item(4,channel)->setText( + QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_PITCH))); + m_aircraft->customMixerTable->item(5,channel)->setText( + QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_YAW))); + } } } @@ -776,63 +855,58 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI() */ void ConfigVehicleTypeWidget::updateObjectsFromWidgets() { - qDebug()<<"updateObjectsFromWidgets"; QString airframeType = "Custom"; //Sets airframe type default to "Custom" if (m_aircraft->aircraftType->currentText() == "Fixed Wing") { - airframeType = updateFixedWingObjectsFromWidgets(); - } else if (m_aircraft->aircraftType->currentText() == "Multirotor") { - //update the mixer - airframeType = updateMultiRotorObjectsFromWidgets(); - } else if (m_aircraft->aircraftType->currentText() == "Helicopter") { - airframeType = "HeliCP"; - m_aircraft->widget_3->sendccpmUpdate(); - } else if (m_aircraft->aircraftType->currentText() == "Ground") { - airframeType = updateGroundVehicleObjectsFromWidgets(); - } else { - airframeType = "Custom"; + airframeType = m_fixedwing->updateConfigObjectsFromWidgets(); + } + else if (m_aircraft->aircraftType->currentText() == "Multirotor") { + airframeType = m_multirotor->updateConfigObjectsFromWidgets(); + } + else if (m_aircraft->aircraftType->currentText() == "Helicopter") { + airframeType = m_heli->updateConfigObjectsFromWidgets(); + } + else if (m_aircraft->aircraftType->currentText() == "Ground") { + airframeType = m_groundvehicle->updateConfigObjectsFromWidgets(); + } + else { - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - UAVObjectField* field = obj->getField(QString("FeedForward")); + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); - // Curve is also common to all quads: - field = obj->getField("ThrottleCurve1"); - QList curve = m_aircraft->customThrottle1Curve->getCurve(); - for (int i=0;isetValue(curve.at(i),i); - } + VehicleConfig* vconfig = new VehicleConfig(); - field = obj->getField("ThrottleCurve2"); - curve.clear(); - curve = m_aircraft->customThrottle2Curve->getCurve(); - for (int i=0;isetValue(curve.at(i),i); - } + vconfig->setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->customThrottle1Curve->getCurve()); + vconfig->setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, m_aircraft->customThrottle2Curve->getCurve()); // Update the table: - for (int i=0; i<8; i++) { - field = obj->getField(mixerTypes.at(i)); - QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,i); - field->setValue(q->currentText()); - field = obj->getField(mixerVectors.at(i)); - int ti = field->getElementNames().indexOf("ThrottleCurve1"); - field->setValue(m_aircraft->customMixerTable->item(1,i)->text(),ti); - ti = field->getElementNames().indexOf("ThrottleCurve2"); - field->setValue(m_aircraft->customMixerTable->item(2,i)->text(),ti); - ti = field->getElementNames().indexOf("Roll"); - field->setValue(m_aircraft->customMixerTable->item(3,i)->text(),ti); - ti = field->getElementNames().indexOf("Pitch"); - field->setValue(m_aircraft->customMixerTable->item(4,i)->text(),ti); - ti = field->getElementNames().indexOf("Yaw"); - field->setValue(m_aircraft->customMixerTable->item(5,i)->text(),ti); + for (int channel=0; channel<8; channel++) { + QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,channel); + + vconfig->setMixerType(mixer,channel, + q->currentText() == "Servo" ? VehicleConfig::MIXERTYPE_SERVO : VehicleConfig::MIXERTYPE_MOTOR); + + vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, + m_aircraft->customMixerTable->item(1,channel)->text().toDouble()); + vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE2, + m_aircraft->customMixerTable->item(2,channel)->text().toDouble()); + vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_ROLL, + m_aircraft->customMixerTable->item(3,channel)->text().toDouble()); + vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_PITCH, + m_aircraft->customMixerTable->item(4,channel)->text().toDouble()); + vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_YAW, + m_aircraft->customMixerTable->item(5,channel)->text().toDouble()); } - } - - //WHAT DOES THIS DO? - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("SystemSettings"))); - UAVObjectField* field = obj->getField(QString("AirframeType")); - field->setValue(airframeType); + // set the airframe type + UAVDataObject* system = dynamic_cast(getObjectManager()->getObject(QString("SystemSettings"))); + Q_ASSERT(system); + + QPointer field = system->getField(QString("AirframeType")); + if (field) + field->setValue(airframeType); + + updateCustomAirframeUI(); } /** @@ -844,6 +918,16 @@ void ConfigVehicleTypeWidget::openHelp() QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Airframe+configuration", QUrl::StrictMode) ); } +/** + Helper function: + Sets the current index on supplied combobox to index + if it is within bounds 0 <= index < combobox.count() + */ +void ConfigVehicleTypeWidget::setComboCurrentIndex(QComboBox* box, int index) +{ + if (index >= 0 && index < box->count()) + box->setCurrentIndex(index); +} /** WHAT DOES THIS DO??? @@ -872,6 +956,9 @@ void ConfigVehicleTypeWidget::addToDirtyMonitor() addWidget(m_aircraft->multiMotorChannelBox6); addWidget(m_aircraft->multiMotorChannelBox7); addWidget(m_aircraft->multiMotorChannelBox8); + addWidget(m_aircraft->mrPitchMixLevel); + addWidget(m_aircraft->mrRollMixLevel); + addWidget(m_aircraft->mrYawMixLevel); addWidget(m_aircraft->triYawChannelBox); addWidget(m_aircraft->aircraftType); addWidget(m_aircraft->fwEngineChannelBox); @@ -883,44 +970,44 @@ void ConfigVehicleTypeWidget::addToDirtyMonitor() addWidget(m_aircraft->fwRudder2ChannelBox); addWidget(m_aircraft->elevonSlider1); addWidget(m_aircraft->elevonSlider2); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmType); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmTailChannel); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmEngineChannel); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoWChannel); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoXChannel); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoYChannel); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmSingleServo); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoZChannel); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleW); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleX); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmCorrectionAngle); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleZ); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleY); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectivePassthrough); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmLinkRoll); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmLinkCyclic); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmRevoSlider); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmREVOspinBox); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveSlider); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectivespinBox); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveScale); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveScaleBox); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmCyclicScale); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmPitchScale); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmPitchScaleBox); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmRollScale); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmRollScaleBox); - addWidget(m_aircraft->widget_3->m_ccpm->SwashLvlPositionSlider); - addWidget(m_aircraft->widget_3->m_ccpm->SwashLvlPositionSpinBox); - addWidget(m_aircraft->widget_3->m_ccpm->CurveType); - addWidget(m_aircraft->widget_3->m_ccpm->NumCurvePoints); - addWidget(m_aircraft->widget_3->m_ccpm->CurveValue1); - addWidget(m_aircraft->widget_3->m_ccpm->CurveValue2); - addWidget(m_aircraft->widget_3->m_ccpm->CurveValue3); - addWidget(m_aircraft->widget_3->m_ccpm->CurveToGenerate); - addWidget(m_aircraft->widget_3->m_ccpm->CurveSettings); - addWidget(m_aircraft->widget_3->m_ccpm->ThrottleCurve); - addWidget(m_aircraft->widget_3->m_ccpm->PitchCurve); - addWidget(m_aircraft->widget_3->m_ccpm->ccpmAdvancedSettingsTable); + addWidget(m_heli->m_ccpm->ccpmType); + addWidget(m_heli->m_ccpm->ccpmTailChannel); + addWidget(m_heli->m_ccpm->ccpmEngineChannel); + addWidget(m_heli->m_ccpm->ccpmServoWChannel); + addWidget(m_heli->m_ccpm->ccpmServoXChannel); + addWidget(m_heli->m_ccpm->ccpmServoYChannel); + addWidget(m_heli->m_ccpm->ccpmSingleServo); + addWidget(m_heli->m_ccpm->ccpmServoZChannel); + addWidget(m_heli->m_ccpm->ccpmAngleW); + addWidget(m_heli->m_ccpm->ccpmAngleX); + addWidget(m_heli->m_ccpm->ccpmCorrectionAngle); + addWidget(m_heli->m_ccpm->ccpmAngleZ); + addWidget(m_heli->m_ccpm->ccpmAngleY); + addWidget(m_heli->m_ccpm->ccpmCollectivePassthrough); + addWidget(m_heli->m_ccpm->ccpmLinkRoll); + addWidget(m_heli->m_ccpm->ccpmLinkCyclic); + addWidget(m_heli->m_ccpm->ccpmRevoSlider); + addWidget(m_heli->m_ccpm->ccpmREVOspinBox); + addWidget(m_heli->m_ccpm->ccpmCollectiveSlider); + addWidget(m_heli->m_ccpm->ccpmCollectivespinBox); + addWidget(m_heli->m_ccpm->ccpmCollectiveScale); + addWidget(m_heli->m_ccpm->ccpmCollectiveScaleBox); + addWidget(m_heli->m_ccpm->ccpmCyclicScale); + addWidget(m_heli->m_ccpm->ccpmPitchScale); + addWidget(m_heli->m_ccpm->ccpmPitchScaleBox); + addWidget(m_heli->m_ccpm->ccpmRollScale); + addWidget(m_heli->m_ccpm->ccpmRollScaleBox); + addWidget(m_heli->m_ccpm->SwashLvlPositionSlider); + addWidget(m_heli->m_ccpm->SwashLvlPositionSpinBox); + addWidget(m_heli->m_ccpm->CurveType); + addWidget(m_heli->m_ccpm->NumCurvePoints); + addWidget(m_heli->m_ccpm->CurveValue1); + addWidget(m_heli->m_ccpm->CurveValue2); + addWidget(m_heli->m_ccpm->CurveValue3); + addWidget(m_heli->m_ccpm->CurveToGenerate); + addWidget(m_heli->m_ccpm->CurveSettings); + addWidget(m_heli->m_ccpm->ThrottleCurve); + addWidget(m_heli->m_ccpm->PitchCurve); + addWidget(m_heli->m_ccpm->ccpmAdvancedSettingsTable); } diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h index 9c6daf16e..3cca72ba1 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h @@ -33,6 +33,13 @@ #include "uavobjectmanager.h" #include "uavobject.h" #include "uavtalk/telemetrymanager.h" + +#include "cfg_vehicletypes/configccpmwidget.h" +#include "cfg_vehicletypes/configfixedwingwidget.h" +#include "cfg_vehicletypes/configmultirotorwidget.h" +#include "cfg_vehicletypes/configgroundvehiclewidget.h" +#include "cfg_vehicletypes/vehicleconfig.h" + #include #include #include @@ -47,54 +54,40 @@ public: ConfigVehicleTypeWidget(QWidget *parent = 0); ~ConfigVehicleTypeWidget(); + static QStringList getChannelDescriptions(); + private: Ui_AircraftWidget *m_aircraft; - bool setupFrameFixedWing(QString airframeType); - bool setupFrameElevon(QString airframeType); - bool setupFrameVtail(QString airframeType); - bool setupQuad(bool pLayout); - bool setupHexa(bool pLayout); - bool setupOcto(); - bool setupGroundVehicleCar(QString airframeType); - bool setupGroundVehicleDifferential(QString airframeType); - bool setupGroundVehicleMotorcycle(QString airframeType); + + ConfigCcpmWidget *m_heli; + ConfigFixedWingWidget *m_fixedwing; + ConfigMultiRotorWidget *m_multirotor; + ConfigGroundVehicleWidget *m_groundvehicle; + void updateCustomAirframeUI(); - bool setupMultiRotorMixer(double mixerFactors[8][3]); - void setupMotors(QList motorList); void addToDirtyMonitor(); void resetField(UAVObjectField * field); void resetMixer (MixerCurveWidget *mixer, int numElements, double maxvalue); - void resetActuators(); - //void setMixerChannel(int channelNumber, bool channelIsMotor, QList vector); - void setupQuadMotor(int channel, double roll, double pitch, double yaw); + //void setMixerChannel(int channelNumber, bool channelIsMotor, QList vector); + + QStringList channelNames; QStringList mixerTypes; QStringList mixerVectors; + QGraphicsSvgItem *quad; bool ffTuningInProgress; bool ffTuningPhase; UAVObject::Metadata accInitialData; private slots: - virtual void refreshWidgetsValues(); - void refreshFixedWingWidgetsValues(QString frameType); - void refreshMultiRotorWidgetsValues(QString frameType); - void refreshGroundVehicleWidgetsValues(QString frameType); - - void updateObjectsFromWidgets(); - QString updateFixedWingObjectsFromWidgets(); - QString updateMultiRotorObjectsFromWidgets(); - QString updateGroundVehicleObjectsFromWidgets(); - // void saveAircraftUpdate(); + + virtual void refreshWidgetsValues(UAVObject * o=NULL); + virtual void updateObjectsFromWidgets(); + + void setComboCurrentIndex(QComboBox* box, int index); void setupAirframeUI(QString type); - void setupFixedWingUI(QString frameType); - void setupMultiRotorUI(QString frameType); - void setupGroundVehicleUI(QString frameType); - - void throwMultiRotorChannelConfigError(int numMotors); - void throwFixedWingChannelConfigError(QString airframeType); - void throwGroundVehicleChannelConfigError(QString airframeType); void toggleAileron2(int index); void toggleElevator2(int index); diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index 915df3d4b..422904bb5 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -16,23 +16,6 @@ - - #groupBox_2,#groupBox{ -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); -border: 1px outset #999; -border-radius: 3; -font:bold; -} - -QGroupBox::title { - subcontrol-origin: margin; - subcontrol-position: top center; /* position at the top center */ - padding: 0 3px; - background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, - stop: 0 #FFOECE, stop: 1 #FFFFFF); - top: 5px; - } - 0 @@ -246,7 +229,7 @@ QGroupBox::title { 30 160 451 - 141 + 161
@@ -291,6 +274,9 @@ margin:1px; 0 + + Qt::StrongFocus +
@@ -301,6 +287,9 @@ margin:1px; 0
+ + Qt::StrongFocus +
@@ -311,6 +300,9 @@ margin:1px; 0
+ + Qt::StrongFocus +
@@ -324,13 +316,25 @@ margin:1px; - + + + Qt::StrongFocus + + - + + + Qt::StrongFocus + + - + + + Qt::StrongFocus + + @@ -343,13 +347,25 @@ margin:1px; - + + + Qt::StrongFocus + + - + + + Qt::StrongFocus + + - + + + Qt::StrongFocus + + @@ -409,9 +425,6 @@ margin:1px; 121
- - - FlightMode Switch Positions @@ -424,6 +437,9 @@ margin:1px; 26 + + Qt::StrongFocus + @@ -434,6 +450,9 @@ margin:1px; 26 + + Qt::StrongFocus + Select the stabilization mode on this position (manual/stabilized/auto) @@ -460,6 +479,9 @@ margin:1px; 26 + + Qt::StrongFocus + @@ -499,6 +521,9 @@ margin:1px; 81 + + Qt::StrongFocus + This slider moves when you move the flight mode switch on your remote. Setup the flightmode channel on the RC Input tab @@ -572,6 +597,9 @@ if you have not done so already. + + Qt::StrongFocus + Indicate the control used for arming the airframe, in addition to setting the throttle to its minimum position. In other terms "Throttle Off". @@ -603,6 +631,9 @@ if you have not done so already. + + Qt::StrongFocus + After the time indicated here, the frame go back to disarmed state. @@ -733,17 +764,30 @@ Applies and Saves all settings to SD fmsSlider fmsModePos3 - fmsSsPos3Roll - fmsSsPos3Pitch - fmsSsPos3Yaw fmsModePos2 - fmsSsPos2Roll - fmsSsPos2Pitch - fmsSsPos2Yaw fmsModePos1 fmsSsPos1Roll fmsSsPos1Pitch fmsSsPos1Yaw + fmsSsPos2Roll + fmsSsPos2Pitch + fmsSsPos2Yaw + fmsSsPos3Roll + fmsSsPos3Pitch + fmsSsPos3Yaw + tabWidget + deadband + configurationWizard + runCalibration + graphicsView + wzBack + wzNext + wzCancel + armControl + armTimeout + inputHelp + saveRCInputToRAM + saveRCInputToSD diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp index 7561e111f..e80986399 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp @@ -2,9 +2,10 @@ #include "ui_inputchannelform.h" #include "manualcontrolsettings.h" +#include "gcsreceiver.h" inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) : - QWidget(parent), + ConfigTaskWidget(parent), ui(new Ui::inputChannelForm) { ui->setupUi(this); @@ -36,12 +37,16 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) : // a spin box fixes this connect(ui->channelNumberDropdown,SIGNAL(currentIndexChanged(int)),this,SLOT(channelDropdownUpdated(int))); connect(ui->channelNumber,SIGNAL(valueChanged(int)),this,SLOT(channelNumberUpdated(int))); + + disableMouseWheelEvents(); } + inputChannelForm::~inputChannelForm() { delete ui; } + void inputChannelForm::setName(QString &name) { ui->channelName->setText(name); @@ -111,7 +116,7 @@ void inputChannelForm::groupUpdated() count = 18; break; case ManualControlSettings::CHANNELGROUPS_GCS: - count = 5; + count = GCSReceiver::CHANNEL_NUMELEM; break; case ManualControlSettings::CHANNELGROUPS_NONE: count = 0; diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.h b/ground/openpilotgcs/src/plugins/config/inputchannelform.h index c6534dc48..606ef2d78 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.h +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.h @@ -7,7 +7,7 @@ namespace Ui { class inputChannelForm; } -class inputChannelForm : public QWidget +class inputChannelForm : public ConfigTaskWidget { Q_OBJECT diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.ui b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui index b53bbb6bf..a32599c30 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.ui +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui @@ -65,6 +65,9 @@ 16777215 + + Qt::StrongFocus + @@ -75,6 +78,9 @@ 25 + + Qt::StrongFocus + QAbstractSpinBox::NoButtons @@ -94,6 +100,9 @@ 25 + + Qt::StrongFocus + QAbstractSpinBox::NoButtons @@ -275,6 +284,9 @@ font:bold; 22 + + Qt::StrongFocus + Qt::Horizontal @@ -300,6 +312,9 @@ font:bold; 16777215 + + Qt::StrongFocus + 7 @@ -471,6 +486,15 @@ font:bold; + + channelNumber + channelGroup + channelNumberDropdown + channelMin + channelNeutral + channelMax + channelRev + diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp index 64e7df893..f2d039edb 100644 --- a/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp @@ -29,7 +29,7 @@ #include "configoutputwidget.h" OutputChannelForm::OutputChannelForm(const int index, QWidget *parent, const bool showLegend) : - QWidget(parent), + ConfigTaskWidget(parent), ui(), m_index(index), m_inChannelTest(false) @@ -70,6 +70,8 @@ OutputChannelForm::OutputChannelForm(const int index, QWidget *parent, const boo ui.actuatorLink->setChecked(false); connect(ui.actuatorLink, SIGNAL(toggled(bool)), this, SLOT(linkToggled(bool))); + + disableMouseWheelEvents(); } OutputChannelForm::~OutputChannelForm() diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.h b/ground/openpilotgcs/src/plugins/config/outputchannelform.h index 7d492dc1a..873a5ea50 100644 --- a/ground/openpilotgcs/src/plugins/config/outputchannelform.h +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.h @@ -29,10 +29,9 @@ #include #include "ui_outputchannelform.h" +#include "configtaskwidget.h" -class ConfigOnputWidget; - -class OutputChannelForm : public QWidget +class OutputChannelForm : public ConfigTaskWidget { Q_OBJECT diff --git a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui new file mode 100644 index 000000000..8a5c2dec4 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui @@ -0,0 +1,1423 @@ + + + PipXtremeWidget + + + + 0 + 0 + 840 + 834 + + + + Form + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + true + + + + + + + + + + + + + + + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Send settings to the board but do not save to the non-volatile memory + + + Apply + + + + + + + Send settings to the board and save to the non-volatile memory + + + Save + + + false + + + + + + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + 75 + true + + + + Pairing + + + + + + + + + + + + + + + + -127 + + + 0 + + + -127 + + + false + + + %v dBm + + + + + + + + + + + + + + + + + -127 + + + 0 + + + 0 + + + false + + + %v dBm + + + + + + + + + + + + + + + + + -127 + + + 0 + + + 0 + + + false + + + %v dBm + + + + + + + + + + + + + + + + + -127 + + + 0 + + + 0 + + + false + + + %v dBm + + + + + + + -100dB + + + + + + + -100dB + + + + + + + -100dB + + + + + + + -100dB + + + + + + + + + + + 400 + 0 + + + + + 75 + true + + + + Status + + + + + + Firmware Version + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 75 + true + + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + false + + + true + + + + + + + Serial Number + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + 75 + false + true + + + + false + + + The modems serial number + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + true + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + true + + + + + + + Min Frequency + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + 75 + true + + + + The modems minimum allowed frequency + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + true + + + + + + + Max Frequency + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + 75 + true + + + + The modems maximum allowed frequency + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + true + + + + + + + Freq. Step Size + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + 75 + true + + + + The modems minimum frequency step size + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + true + + + + + + + Link State + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + 75 + true + + + + The modems current state + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + true + + + + + + + Rx AFC + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 75 + true + + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + true + + + + + + + Retries + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 75 + true + + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + false + + + true + + + + + + + + 75 + true + + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + false + + + true + + + + + + + Errors + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + UAVTalk Errors + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 75 + true + + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + false + + + true + + + + + + + Resets + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 75 + true + + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + false + + + true + + + + + + + Dropped + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 75 + true + + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + false + + + true + + + + + + + TX Rate (B/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 75 + true + + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + false + + + true + + + + + + + RX Rate (B/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 75 + true + + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + false + + + true + + + + + + + + 75 + true + + + + QLineEdit { + border: none; + border-radius: 1px; + padding: 0 8px; + background: rgba(0, 0, 0, 16); +/* background: transparent; */ +/* selection-background-color: darkgray;*/ +} + + + false + + + true + + + + + + + Device ID + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + + + + 75 + true + + + + Configuration + + + + + + Telemetry Port Config. + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Set the telemetry port configuration + + + + + + + Telemetry Port Speed + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Set the telemetry port speed + + + + + + + Flexi Port Configuration + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Set the flexi port configuration + + + + + + + Flexi Port Speed + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Set the flexi port speed + + + + + + + VCP Configuration + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Set the virtual serial port configuration + + + + + + + VCP Speed + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Set the virtual serial port speed + + + + + + + Max RF Datarate (bits/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Set the maximum RF datarate/channel bandwidth the modem will use + + + + + + + Max RF Tx Power(mW) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Set the maximum TX output power the modem will use + + + Qt::LeftToRight + + + 0 + + + + + + + Send Timeout (ms) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Calibrate the modems RF carrier frequency + + + true + + + 255 + + + + + + + Min Packet Size + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Calibrate the modems RF carrier frequency + + + true + + + 255 + + + + + + + Frequency Calibration + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Calibrate the modems RF carrier frequency + + + true + + + 255 + + + + + + + Frequency (Hz) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Set the modems RF carrier frequency + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + true + + + 0 + + + 1000000000 + + + 100000 + + + + + + + AES Encription + + + + + + + Courier New + 9 + + + + The AES encryption key - has to be the same key on the remote modem. + + + + + + 32 + + + true + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Radomise the AES encryption key + + + Rand + + + + + + + + 75 + true + + + + Enable/Disable AES encryption + + + Qt::RightToLeft + + + Enable + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + Scan whole band to see where their is interference and/or used channels + + + Scan Spectrum + + + + + + + + + + + + + PairSelect1 + PairID1 + PairSelect2 + PairID2 + PairSelect3 + PairID3 + PairSelect4 + PairID4 + FirmwareVersion + SerialNumber + DeviceID + MinFrequency + MaxFrequency + FrequencyStepSize + LinkState + RxAFC + Retries + Errors + UAVTalkErrors + Resets + TXRate + RXRate + TelemPortConfig + TelemPortSpeed + FlexiPortConfig + FlexiPortSpeed + VCPConfig + VCPSpeed + MaxRFDatarate + MaxRFTxPower + SendTimeout + MinPacketSize + FrequencyCalibration + Frequency + ScanSpectrum + AESKey + AESKeyRandom + AESEnable + graphicsView_Spectrum + Apply + Save + + + + diff --git a/ground/openpilotgcs/src/plugins/config/ahrs.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui similarity index 89% rename from ground/openpilotgcs/src/plugins/config/ahrs.ui rename to ground/openpilotgcs/src/plugins/config/revosensors.ui index a9ad4ca32..e92d09d7b 100644 --- a/ground/openpilotgcs/src/plugins/config/ahrs.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -1,13 +1,13 @@ - AHRSWidget - + RevoSensorsWidget + 0 0 720 - 537 + 567 @@ -469,24 +469,24 @@ TODO: is this necessary? Measurement could be auto updated every second or so, o <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> +</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;"> <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Help</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Step #1 and #2 are really necessary. Steps #3 and #4 will help you achieve the best possible results.</span></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-weight:600;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">#1: Multi-Point calibration:</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">This calibration will compute the scale for all sensors on the INS. Press &quot;Start&quot; to begin calibration, and follow the instructions which will be displayed here. Note that your HomeLocation must be set first, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">#2: Sensor noise calibration:</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">This calibration will compute sensor variance under standard conditions. You can leave your engines running at low to mid throttle to take their vibration into account before pressing &quot;Start&quot;.</p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">#3: Accelerometer bias calibration:</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">This step will ensure that accelerometer bias is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.</p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">#4 Gyro temp drift calibration:</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-weight:600;"></p></td></tr></table></body></html> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">Help</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">Step #1 and #2 are really necessary. Steps #3 and #4 will help you achieve the best possible results.</span></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt; font-weight:600;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#1: Multi-Point calibration:</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This calibration will compute the scale for all sensors on the INS. Press &quot;Start&quot; to begin calibration, and follow the instructions which will be displayed here. Note that your HomeLocation must be set first, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#2: Sensor noise calibration:</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This calibration will compute sensor variance under standard conditions. You can leave your engines running at low to mid throttle to take their vibration into account before pressing &quot;Start&quot;.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#3: Accelerometer bias calibration:</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step will ensure that accelerometer bias is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#4 Gyro temp drift calibration:</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt; font-weight:600;"></p></td></tr></table></body></html> @@ -508,7 +508,7 @@ p, li { white-space: pre-wrap; } - INS Algorithm: + Attitude Algorithm: diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 5c79c104f..3f985a66e 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -497,27 +497,11 @@ 0 0 673 - 880 + 790 - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - + Qt::Horizontal @@ -533,7 +517,7 @@ - + @@ -541,19 +525,12 @@ 16 - - - 9 - 75 - true - - Rate Stabilization (Inner Loop) - + @@ -573,530 +550,6 @@ 181 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - #RateStabilizationGroup_15{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); - -border: 1px outset #999; -border-radius: 3; -} - @@ -3383,6 +2836,10 @@ border-radius: 5; Qt::StrongFocus + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + @@ -3433,6 +2890,10 @@ border-radius: 5; Qt::StrongFocus + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + 200 @@ -3484,6 +2945,10 @@ border-radius: 5; Qt::StrongFocus + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + @@ -3531,6 +2996,10 @@ border-radius: 5; Qt::StrongFocus + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + 200 @@ -3582,6 +3051,10 @@ border-radius: 5; Qt::StrongFocus + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + @@ -3629,6 +3102,10 @@ border-radius: 5; Qt::StrongFocus + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + 200 @@ -3683,6 +3160,10 @@ border-radius: 5; Qt::StrongFocus + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + @@ -3730,6 +3211,10 @@ border-radius: 5; Qt::StrongFocus + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + 200 @@ -3765,6 +3250,10 @@ border-radius: 5; Qt::StrongFocus + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + @@ -3812,6 +3301,10 @@ border-radius: 5; Qt::StrongFocus + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + 200 @@ -3847,6 +3340,10 @@ border-radius: 5; Qt::StrongFocus + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + @@ -3894,6 +3391,10 @@ border-radius: 5; Qt::StrongFocus + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + 200 @@ -3918,23 +3419,7 @@ border-radius: 5; - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 15 - - - - - + Qt::Horizontal @@ -3950,7 +3435,7 @@ border-radius: 5; - + @@ -3958,19 +3443,12 @@ border-radius: 5; 16 - - - 9 - 75 - true - - Attitude Stabilization (Outer Loop) - + @@ -4507,13 +3985,6 @@ border-radius: 5; false - - #RateStabilizationGroup_17{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); - -border: 1px outset #999; -border-radius: 3; -} - @@ -4556,26 +4027,14 @@ border-radius: 3; - + - - - 0 - 0 - - 81 28 - - - 81 - 28 - - QPushButton { border: 1px outset #999; @@ -4608,7 +4067,7 @@ border-radius: 4; - + @@ -7287,26 +6746,14 @@ border-radius: 5; - + - - - 0 - 0 - - 51 28 - - - 51 - 28 - - QPushButton { border: 1px outset #999; @@ -7339,42 +6786,23 @@ border-radius: 4; + + + + Qt::Horizontal + + + + 40 + 20 + + + + - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 2 - 10 - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 15 - - - - - + Qt::Horizontal @@ -7390,7 +6818,7 @@ border-radius: 4; - + @@ -7398,19 +6826,12 @@ border-radius: 4; 16 - - - 9 - 75 - true - - Stick Range and Limits - + @@ -7944,16 +7365,6 @@ border-radius: 4; - - false - - - #RateStabilizationGroup_19{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); - -border: 1px outset #999; -border-radius: 3; -} - @@ -7971,7 +7382,7 @@ border-radius: 3; - 10 + 1000 10 @@ -7979,24 +7390,12 @@ border-radius: 3; - - - 0 - 0 - - 51 28 - - - 51 - 28 - - QPushButton { border: 1px outset #999; @@ -8043,12 +7442,6 @@ border-radius: 4; 28 - - - 81 - 28 - - QPushButton { border: 1px outset #999; @@ -10198,7 +9591,7 @@ border-radius: 5; Full Stick -Angle +Angle (deg) Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -10226,7 +9619,7 @@ Angle - 100 + 180 50 @@ -10245,7 +9638,7 @@ Angle objname:StabilizationSettings fieldname:RollMax haslimits:yes - scale:1.8 + scale:1.0 buttongroup:3,10 @@ -10269,17 +9662,17 @@ Angle Qt::StrongFocus - 200 + 180 - 200 + 180 objname:StabilizationSettings fieldname:RollMax haslimits:yes - scale:1.8 + scale:1.0 buttongroup:3,10 @@ -10322,7 +9715,7 @@ Angle - 100 + 180 50 @@ -10341,7 +9734,7 @@ Angle objname:StabilizationSettings fieldname:PitchMax haslimits:yes - scale:1.8 + scale:1.0 buttongroup:3,10 @@ -10365,17 +9758,17 @@ Angle Qt::StrongFocus - 200 + 180 - 200 + 180 objname:StabilizationSettings fieldname:PitchMax haslimits:yes - scale:1.8 + scale:1.0 buttongroup:3,10 @@ -10418,7 +9811,7 @@ Angle - 100 + 180 50 @@ -10437,7 +9830,7 @@ Angle objname:StabilizationSettings fieldname:YawMax haslimits:yes - scale:1.8 + scale:1.0 buttongroup:3,10 @@ -10461,17 +9854,17 @@ Angle Qt::StrongFocus - 200 + 180 - 200 + 180 objname:StabilizationSettings fieldname:YawMax haslimits:yes - scale:1.8 + scale:1.0 buttongroup:3,10 @@ -10490,7 +9883,7 @@ Angle Full Stick -Rate +Rate (deg/s) Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -10518,7 +9911,7 @@ Rate - 100 + 500 50 @@ -10538,7 +9931,7 @@ Rate fieldname:ManualRate element:Roll haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10562,10 +9955,10 @@ Rate Qt::StrongFocus - 200 + 500 - 200 + 180 @@ -10573,7 +9966,7 @@ Rate fieldname:ManualRate element:Roll haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10600,7 +9993,7 @@ Rate - 100 + 500 50 @@ -10620,7 +10013,7 @@ Rate fieldname:ManualRate element:Pitch haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10644,10 +10037,10 @@ Rate Qt::StrongFocus - 200 + 500 - 200 + 180 @@ -10655,7 +10048,7 @@ Rate fieldname:ManualRate element:Pitch haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10682,7 +10075,7 @@ Rate - 100 + 500 50 @@ -10702,7 +10095,7 @@ Rate fieldname:ManualRate element:Yaw haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10726,10 +10119,10 @@ Rate Qt::StrongFocus - 200 + 500 - 200 + 180 @@ -10737,7 +10130,7 @@ Rate fieldname:ManualRate element:Yaw haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10784,7 +10177,7 @@ Attitude - 100 + 500 50 @@ -10804,7 +10197,7 @@ Attitude fieldname:MaximumRate element:Roll haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10828,7 +10221,7 @@ Attitude Qt::StrongFocus - 200 + 500 200 @@ -10839,7 +10232,7 @@ Attitude fieldname:MaximumRate element:Roll haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10866,7 +10259,7 @@ Attitude - 100 + 500 50 @@ -10886,7 +10279,7 @@ Attitude fieldname:MaximumRate element:Pitch haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10910,7 +10303,7 @@ Attitude Qt::StrongFocus - 200 + 500 200 @@ -10921,7 +10314,7 @@ Attitude fieldname:MaximumRate element:Pitch haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10948,7 +10341,7 @@ Attitude - 100 + 500 50 @@ -10968,7 +10361,7 @@ Attitude fieldname:MaximumRate element:Yaw haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -10992,7 +10385,7 @@ Attitude Qt::StrongFocus - 200 + 500 200 @@ -11003,7 +10396,7 @@ Attitude fieldname:MaximumRate element:Yaw haslimits:yes - scale:5 + scale:1 buttongroup:3,10 @@ -11015,23 +10408,7 @@ Attitude - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - + Qt::Vertical @@ -11047,23 +10424,7 @@ Attitude - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 2 - 10 - - - - - + @@ -11600,13 +10961,6 @@ Attitude false - - #RateStabilizationGroup_21{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); - -border: 1px outset #999; -border-radius: 3; -} - @@ -11686,28 +11040,15 @@ automatically every 300ms, which will help for fast tuning. - - - 0 - 0 - - 120 28 - - - 120 - 28 - - - - - 8 - + + Reloads the saved settings into GCS. +Useful if you have accidentally changed some settings. QPushButton { @@ -11743,29 +11084,12 @@ border-radius: 4; - - - 0 - 0 - - 60 28 - - - 60 - 28 - - - - - 8 - - Send settings to the board but do not save to the non-volatile memory @@ -11802,29 +11126,12 @@ border-radius: 4; - - - 0 - 0 - - 60 28 - - - 60 - 28 - - - - - 8 - - Send settings to the board and save to the non-volatile memory @@ -11885,29 +11192,13 @@ border-radius: 4; 0 - -403 + 0 673 - 1079 + 981 - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 25 - 10 - - - - - + Qt::Horizontal @@ -11923,7 +11214,7 @@ border-radius: 4; - + @@ -11931,19 +11222,12 @@ border-radius: 4; 16 - - - 9 - 75 - true - - Rate Stabization Coefficients (Inner Loop) - + @@ -12477,16 +11761,6 @@ border-radius: 4; - - false - - - #RateStabilizationGroup_8{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); - -border: 1px outset #999; -border-radius: 3; -} - @@ -12523,7 +11797,7 @@ border-radius: 3; - + @@ -12576,7 +11850,7 @@ border-radius: 4; - + @@ -14743,7 +14017,7 @@ Then lower the value by 20% or so. - 6 + 5 0.000100000000000 @@ -14791,7 +14065,7 @@ Then lower the value by 20% or so. - 6 + 5 0.000100000000000 @@ -14841,7 +14115,7 @@ You can usually go for higher values for Yaw factors. - 6 + 5 0.000100000000000 @@ -14924,7 +14198,7 @@ value as the Kp. - 6 + 5 0.000100000000000 @@ -14988,7 +14262,7 @@ value as the Kp. - 6 + 5 0.000100000000000 @@ -15052,7 +14326,7 @@ value as the Kp. - 6 + 5 0.000100000000000 @@ -15262,7 +14536,7 @@ value as the Kp. - K_i*ILimit + ILimit Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -15299,7 +14573,7 @@ value as the Kp. - 6 + 4 1.000000000000000 @@ -15346,7 +14620,7 @@ value as the Kp. - 6 + 4 1.000000000000000 @@ -15396,7 +14670,7 @@ value as the Kp. - 6 + 4 1.000000000000000 @@ -15419,58 +14693,23 @@ value as the Kp. + + + + Qt::Horizontal + + + + 40 + 20 + + + + - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 2 - 10 - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 2 - 10 - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 15 - - - - - Qt::Horizontal @@ -15486,7 +14725,7 @@ value as the Kp. - + @@ -15494,19 +14733,12 @@ value as the Kp. 16 - - - 9 - 75 - true - - Attitude Stabization Coefficients (Outer Loop) - + @@ -16043,13 +15275,6 @@ value as the Kp. false - - #RateStabilizationGroup_4{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); - -border: 1px outset #999; -border-radius: 3; -} - @@ -16060,86 +15285,7 @@ border-radius: 3; false - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - - - Link Roll and Pitch - - - - - - - - 0 - 0 - - - - - 81 - 28 - - - - - 81 - 28 - - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:5 - - - - - + @@ -18302,7 +17448,7 @@ border-radius: 5; - 6 + 3 0.100000000000000 @@ -18346,7 +17492,7 @@ border-radius: 5; - 6 + 3 0.100000000000000 @@ -18393,7 +17539,7 @@ border-radius: 5; - 6 + 3 0.100000000000000 @@ -18475,7 +17621,7 @@ border-radius: 5; - 6 + 3 0.100000000000000 @@ -18535,7 +17681,7 @@ border-radius: 5; - 6 + 3 0.100000000000000 @@ -18598,7 +17744,7 @@ border-radius: 5; - 6 + 3 0.100000000000000 @@ -18639,7 +17785,7 @@ border-radius: 5; - K_i*ILimit + ILimit Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -18676,7 +17822,7 @@ border-radius: 5; - 6 + 2 0.100000000000000 @@ -18720,7 +17866,7 @@ border-radius: 5; - 6 + 2 0.100000000000000 @@ -18767,7 +17913,7 @@ border-radius: 5; - 6 + 2 0.100000000000000 @@ -18787,26 +17933,102 @@ border-radius: 5; + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 81 + 28 + + + + + 81 + 28 + + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:5 + + + + + + + + + + + Link Roll and Pitch + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 15 - - - - - + Qt::Horizontal @@ -18822,7 +18044,7 @@ border-radius: 5; - + @@ -18830,19 +18052,12 @@ border-radius: 5; 16 - - - 9 - 75 - true - - Stick Range and Limits - + @@ -19376,16 +18591,6 @@ border-radius: 5; - - false - - - #RateStabilizationGroup_6{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); - -border: 1px outset #999; -border-radius: 3; -} - @@ -19403,7 +18608,7 @@ border-radius: 3; - 10 + 10000 10 @@ -19411,24 +18616,12 @@ border-radius: 3; - - - 0 - 0 - - 81 28 - - - 81 - 28 - - QPushButton { border: 1px outset #999; @@ -22140,23 +21333,7 @@ rate(deg/s) - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - + Qt::Horizontal @@ -22172,7 +21349,7 @@ rate(deg/s) - + @@ -22180,26 +21357,13 @@ rate(deg/s) 16 - - - 9 - 75 - true - - Sensor Tunning - + - - - 0 - 0 - - 0 @@ -22729,13 +21893,6 @@ rate(deg/s) false - - #RateStabilizationGroup_23{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); - -border: 1px outset #999; -border-radius: 3; -} - @@ -25066,23 +24223,7 @@ border-radius: 5; - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - + @@ -25619,13 +24760,6 @@ border-radius: 5; false - - #RateStabilizationGroup_22{background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); - -border: 1px outset #999; -border-radius: 3; -} - @@ -25672,13 +24806,6 @@ border-radius: 3; 0 - - - 9 - 50 - false - - If you check this, the GCS will udpate the stabilization factors automatically every 300ms, which will help for fast tuning. @@ -25724,11 +24851,6 @@ automatically every 300ms, which will help for fast tuning. 28 - - - 8 - - Send settings to the board but do not save to the non-volatile memory @@ -25783,11 +24905,6 @@ border-radius: 4; 28 - - - 8 - - Send settings to the board and save to the non-volatile memory diff --git a/ground/openpilotgcs/src/plugins/config/txpid.ui b/ground/openpilotgcs/src/plugins/config/txpid.ui index 3bfce4cd7..6ffa2e62d 100644 --- a/ground/openpilotgcs/src/plugins/config/txpid.ui +++ b/ground/openpilotgcs/src/plugins/config/txpid.ui @@ -1,584 +1,620 @@ - - - TxPIDWidget - - - - 0 - 0 - 720 - 567 - - - - Form - - - - - - QFrame::NoFrame - - - true - - - - - 0 - 0 - 702 - 489 - - - - - - - This module will periodically update values of stabilization PID settings -depending on configured input control channels. New values of stabilization -settings are not saved to flash, but updated in RAM. It is expected that the -module will be enabled only for tuning. When desired values are found, they -can be read via GCS and saved permanently. Then this module should be -disabled again. - -Up to 3 separate PID options (or option pairs) can be selected and updated. - - - Enable TxPID module - - - - - - - After enabling the module, you must power cycle before using and configuring. - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 100 - - - - #groupBox_6{ -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); -border: 1px outset #999; -border-radius: 3; -font:bold; -} - -QGroupBox::title { - subcontrol-origin: margin; - subcontrol-position: top center; /* position at the top center */ - padding: 0 3px; - background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, - stop: 0 #FFOECE, stop: 1 #FFFFFF); - top: 5px; - } - - - Module Settings - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - PID option - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Control Source - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Min - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Max - - - Qt::AlignCenter - - - - - - - Instance 1 - - - - - - - Select PID option or option pair to update. -Set to Disabled if not used. - - - - - - - Select input used as a control source for this instance. -It can be one of Accessory channels or Throttle channel. - -If Accessory channel is chosen then its range [0..1] will be mapped -to PID range [Min..Max] defined for this instance. - -If Throttle channel is chosen then Throttle range [Min..Max] will -be mapped to PID range [Min..Max] defined for this instance. If -Throttle is out of bounds then PID Min and Max values will be used -accordingly. - -Note that it is possible to set PID Min > Max. In that case increasing -control input value will decrease the PID option value. This can be -used, for instance, to decrease PID value when increasing Throttle. - - - - - - - Minimum PID value mapped to Accessory channel = 0 or -Throttle channel lesser or equal to Throttle Min value. - - - 6 - - - 0.000100000000000 - - - - - - - Maximum PID value mapped to Accessory channel = 1 or -Throttle channel greater or equal to Throttle Max value. - - - 6 - - - 0.000100000000000 - - - - - - - Instance 2 - - - - - - - Select PID option or option pair to update. -Set to Disabled if not used. - - - - - - - Select input used as a control source for this instance. -It can be one of Accessory channels or Throttle channel. - -If Accessory channel is chosen then its range [0..1] will be mapped -to PID range [Min..Max] defined for this instance. - -If Throttle channel is chosen then Throttle range [Min..Max] will -be mapped to PID range [Min..Max] defined for this instance. If -Throttle is out of bounds then PID Min and Max values will be used -accordingly. - -Note that it is possible to set PID Min > Max. In that case increasing -control input value will decrease the PID option value. This can be -used, for instance, to decrease PID value when increasing Throttle. - - - - - - - Minimum PID value mapped to Accessory channel = 0 or -Throttle channel lesser or equal to Throttle Min value. - - - 6 - - - 0.000100000000000 - - - - - - - Maximum PID value mapped to Accessory channel = 1 or -Throttle channel greater or equal to Throttle Max value. - - - 6 - - - 0.000100000000000 - - - - - - - Instance 3 - - - - - - - Select PID option or option pair to update. -Set to Disabled if not used. - - - - - - - Select input used as a control source for this instance. -It can be one of Accessory channels or Throttle channel. - -If Accessory channel is chosen then its range [0..1] will be mapped -to PID range [Min..Max] defined for this instance. - -If Throttle channel is chosen then Throttle range [Min..Max] will -be mapped to PID range [Min..Max] defined for this instance. If -Throttle is out of bounds then PID Min and Max values will be used -accordingly. - -Note that it is possible to set PID Min > Max. In that case increasing -control input value will decrease the PID option value. This can be -used, for instance, to decrease PID value when increasing Throttle. - - - - - - - Minimum PID value mapped to Accessory channel = 0 or -Throttle channel lesser or equal to Throttle Min value. - - - 6 - - - 0.000100000000000 - - - - - - - Maximum PID value mapped to Accessory channel = 1 or -Throttle channel greater or equal to Throttle Max value. - - - 6 - - - 0.000100000000000 - - - - - - - Update Mode - - - - - - - PID values update mode which can be set to: -- Never: this disables PID updates (but module still will be run if enabled), -- When Armed: PID updated only when system is armed, -- Always: PID updated always regardless of arm state. - -Since the GCS updates GUI PID values in real time on change, could be -tricky to change other PID values from the GUI if the module is enabled -and constantly updates stabilization settings object. As a workaround, -this option can be used to temporarily disable updates or enable them -only when system is armed without disabling the module. - - - - - - - Throttle Range - - - - - - - Throttle channel lower bound mapped to PID Min value - - - 1.000000000000000 - - - 0.010000000000000 - - - - - - - Throttle channel upper bound mapped to PID Max value - - - 1.000000000000000 - - - 0.010000000000000 - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Min - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Max - - - Qt::AlignCenter - - - - - - - Qt::Vertical - - - - 20 - 20 - - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 20 - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - - - - - - - - - - - QFrame::StyledPanel - - - QFrame::Raised - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Send settings to the board but do not save to the non-volatile memory - - - Apply - - - - - - - Send settings to the board and save to the non-volatile memory - - - Save - - - false - - - - - - - - - - - TxPIDEnable - Apply - Save - scrollArea - - - - + + + TxPIDWidget + + + + 0 + 0 + 720 + 567 + + + + Form + + + + + + QFrame::NoFrame + + + true + + + + + 0 + 0 + 696 + 475 + + + + + + + Qt::StrongFocus + + + This module will periodically update values of stabilization PID settings +depending on configured input control channels. New values of stabilization +settings are not saved to flash, but updated in RAM. It is expected that the +module will be enabled only for tuning. When desired values are found, they +can be read via GCS and saved permanently. Then this module should be +disabled again. + +Up to 3 separate PID options (or option pairs) can be selected and updated. + + + Enable TxPID module + + + + + + + After enabling the module, you must power cycle before using and configuring. + + + + + + + Qt::Horizontal + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 10 + + + + + + + + true + + + + 0 + 0 + + + + + 0 + 100 + + + + Module Settings + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + PID option + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Control Source + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Min + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Max + + + Qt::AlignCenter + + + + + + + Instance 1 + + + + + + + Qt::StrongFocus + + + Select PID option or option pair to update. +Set to Disabled if not used. + + + + + + + Qt::StrongFocus + + + Select input used as a control source for this instance. +It can be one of Accessory channels or Throttle channel. + +If Accessory channel is chosen then its range [0..1] will be mapped +to PID range [Min..Max] defined for this instance. + +If Throttle channel is chosen then Throttle range [Min..Max] will +be mapped to PID range [Min..Max] defined for this instance. If +Throttle is out of bounds then PID Min and Max values will be used +accordingly. + +Note that it is possible to set PID Min > Max. In that case increasing +control input value will decrease the PID option value. This can be +used, for instance, to decrease PID value when increasing Throttle. + + + + + + + Qt::StrongFocus + + + Minimum PID value mapped to Accessory channel = 0 or +Throttle channel lesser or equal to Throttle Min value. + + + 6 + + + 0.000100000000000 + + + + + + + Qt::StrongFocus + + + Maximum PID value mapped to Accessory channel = 1 or +Throttle channel greater or equal to Throttle Max value. + + + 6 + + + 0.000100000000000 + + + + + + + Instance 2 + + + + + + + Qt::StrongFocus + + + Select PID option or option pair to update. +Set to Disabled if not used. + + + + + + + Qt::StrongFocus + + + Select input used as a control source for this instance. +It can be one of Accessory channels or Throttle channel. + +If Accessory channel is chosen then its range [0..1] will be mapped +to PID range [Min..Max] defined for this instance. + +If Throttle channel is chosen then Throttle range [Min..Max] will +be mapped to PID range [Min..Max] defined for this instance. If +Throttle is out of bounds then PID Min and Max values will be used +accordingly. + +Note that it is possible to set PID Min > Max. In that case increasing +control input value will decrease the PID option value. This can be +used, for instance, to decrease PID value when increasing Throttle. + + + + + + + Qt::StrongFocus + + + Minimum PID value mapped to Accessory channel = 0 or +Throttle channel lesser or equal to Throttle Min value. + + + 6 + + + 0.000100000000000 + + + + + + + Qt::StrongFocus + + + Maximum PID value mapped to Accessory channel = 1 or +Throttle channel greater or equal to Throttle Max value. + + + 6 + + + 0.000100000000000 + + + + + + + Instance 3 + + + + + + + Qt::StrongFocus + + + Select PID option or option pair to update. +Set to Disabled if not used. + + + + + + + Qt::StrongFocus + + + Select input used as a control source for this instance. +It can be one of Accessory channels or Throttle channel. + +If Accessory channel is chosen then its range [0..1] will be mapped +to PID range [Min..Max] defined for this instance. + +If Throttle channel is chosen then Throttle range [Min..Max] will +be mapped to PID range [Min..Max] defined for this instance. If +Throttle is out of bounds then PID Min and Max values will be used +accordingly. + +Note that it is possible to set PID Min > Max. In that case increasing +control input value will decrease the PID option value. This can be +used, for instance, to decrease PID value when increasing Throttle. + + + + + + + Qt::StrongFocus + + + Minimum PID value mapped to Accessory channel = 0 or +Throttle channel lesser or equal to Throttle Min value. + + + 6 + + + 0.000100000000000 + + + + + + + Qt::StrongFocus + + + Maximum PID value mapped to Accessory channel = 1 or +Throttle channel greater or equal to Throttle Max value. + + + 6 + + + 0.000100000000000 + + + + + + + Update Mode + + + + + + + Qt::StrongFocus + + + PID values update mode which can be set to: +- Never: this disables PID updates (but module still will be run if enabled), +- When Armed: PID updated only when system is armed, +- Always: PID updated always regardless of arm state. + +Since the GCS updates GUI PID values in real time on change, could be +tricky to change other PID values from the GUI if the module is enabled +and constantly updates stabilization settings object. As a workaround, +this option can be used to temporarily disable updates or enable them +only when system is armed without disabling the module. + + + + + + + Throttle Range + + + + + + + Qt::StrongFocus + + + Throttle channel lower bound mapped to PID Min value + + + 1.000000000000000 + + + 0.010000000000000 + + + + + + + Qt::StrongFocus + + + Throttle channel upper bound mapped to PID Max value + + + 1.000000000000000 + + + 0.010000000000000 + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Min + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Max + + + Qt::AlignCenter + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 20 + + + + + + + + + + + Qt::Vertical + + + + 20 + 20 + + + + + + + + + + + + + + + + + + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Send settings to the board but do not save to the non-volatile memory + + + Apply + + + + + + + Send settings to the board and save to the non-volatile memory + + + Save + + + false + + + + + + + + + + + TxPIDEnable + Apply + Save + scrollArea + PID1 + Input1 + MinPID1 + MaxPID1 + PID2 + Input2 + MinPID2 + MaxPID2 + PID3 + Input3 + MinPID3 + MaxPID3 + ThrottleMin + ThrottleMax + UpdateMode + + + + diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml index 7394a661f..64c653f23 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml @@ -492,18 +492,18 @@ 0 Rotate Roll - AttitudeRaw + Accels 1 20 -20 Horizontal - accels-X - AttitudeRaw + x + Accels -1 360 0 Rotate - accels-X + x false @@ -989,29 +989,6 @@ - - - false - 0.0.0 - - - %%DATAPATH%%dials/deluxe/lineardial-vertical.svg - 0 - 1 - Andale Mono,12,-1,5,75,0,0,0,0,0 - 50 - 0 - 100 - 0 - 100 - 80 - AhrsStatus - CPULoad - false - 80 - 50 - - false @@ -1028,8 +1005,8 @@ -11 11 -11 - AttitudeRaw - accels-X + Accels + x false -5 -11 @@ -1051,8 +1028,8 @@ -11 11 -11 - AttitudeRaw - accels-Y + Accels + y false -5 -11 @@ -1074,8 +1051,8 @@ -11 11 -11 - AttitudeRaw - accels-Z + Accels + z false -5 -11 @@ -1757,24 +1734,27 @@ 60 4294901760 - accels-X - AttitudeRaw + None + x + Accels 0 0 0 4283782655 - accels-Y - AttitudeRaw + None + y + Accels 0 0 0 4283804160 - accels-Z - AttitudeRaw + None + z + Accels 0 0 0 @@ -1797,6 +1777,7 @@ 20 4294901760 + None Channel-4 ActuatorCommand 0 @@ -1805,6 +1786,7 @@ 4294901760 + None Channel-5 ActuatorCommand 0 @@ -1813,6 +1795,7 @@ 4289374847 + None Channel-6 ActuatorCommand 0 @@ -1821,6 +1804,7 @@ 4289374847 + None Channel-7 ActuatorCommand 0 @@ -1845,6 +1829,7 @@ 60 4283760895 + None Roll AttitudeActual 0 @@ -1853,6 +1838,7 @@ 4278233600 + None Yaw AttitudeActual 0 @@ -1861,6 +1847,7 @@ 4294901760 + None Pitch AttitudeActual 0 @@ -1885,6 +1872,7 @@ 60 4278190080 + None Pressure BaroAltitude 0 @@ -1909,6 +1897,7 @@ 40 4278190207 + None Channel-1 ManualControlCommand 0 @@ -1917,6 +1906,7 @@ 4294901760 + None Channel-4 ManualControlCommand 0 @@ -1925,6 +1915,7 @@ 4294901760 + None Channel-5 ManualControlCommand 0 @@ -1933,6 +1924,7 @@ 4294901760 + None Channel-6 ManualControlCommand 0 @@ -1941,6 +1933,7 @@ 4294901760 + None Channel-7 ManualControlCommand 0 @@ -1949,6 +1942,7 @@ 4283825920 + None Channel-2 ManualControlCommand 0 @@ -1957,6 +1951,7 @@ 4294923520 + None Channel-3 ManualControlCommand 0 @@ -1965,6 +1960,7 @@ 4294967040 + None Channel-0 ManualControlCommand 0 @@ -1989,24 +1985,27 @@ 60 4294901760 - accels-X - AttitudeRaw + None + x + Accels 0 0 0 4283782655 - accels-Y - AttitudeRaw + None + y + Accels 0 0 0 4283804160 - accels-Z - AttitudeRaw + None + z + Accels 0 0 0 @@ -2029,24 +2028,27 @@ 60 4283804160 - gyros-Z - AttitudeRaw + None + z + Gyros 0 0 0 4283782655 - gyros-Y - AttitudeRaw + None + y + Gyros 0 0 0 4294901760 - gyros-X - AttitudeRaw + None + x + Gyros 0 0 0 @@ -2069,24 +2071,27 @@ 60 4294901760 - magnetometers-X - AttitudeRaw + None + X + Magnetometer 0 0 0 4283782655 - magnetometers-Y - AttitudeRaw + None + Y + Magnetometer 0 0 0 4283804160 - magnetometers-Z - AttitudeRaw + None + Z + Magnetometer 0 0 0 @@ -2109,6 +2114,7 @@ 240 4294945280 + None StackRemaining-System TaskInfo 0 @@ -2117,6 +2123,7 @@ 4294945280 + None StackRemaining-Actuator TaskInfo 0 @@ -2125,6 +2132,7 @@ 4294945280 + None StackRemaining-Guidance TaskInfo 0 @@ -2133,6 +2141,7 @@ 4294945280 + None StackRemaining-Watchdog TaskInfo 0 @@ -2141,6 +2150,7 @@ 4294945280 + None StackRemaining-TelemetryTx TaskInfo 0 @@ -2149,6 +2159,7 @@ 4294945280 + None StackRemaining-TelemetryTxPri TaskInfo 0 @@ -2157,6 +2168,7 @@ 4294945280 + None StackRemaining-TelemetryRx TaskInfo 0 @@ -2165,6 +2177,7 @@ 4294945280 + None StackRemaining-GPS TaskInfo 0 @@ -2173,6 +2186,7 @@ 4294945280 + None StackRemaining-ManualControl TaskInfo 0 @@ -2181,6 +2195,7 @@ 4294945280 + None StackRemaining-Altitude TaskInfo 0 @@ -2189,6 +2204,7 @@ 4294945280 + None StackRemaining-AHRSComms TaskInfo 0 @@ -2197,6 +2213,7 @@ 4294945280 + None StackRemaining-Stabilization TaskInfo 0 @@ -2221,6 +2238,7 @@ 20 4289374847 + None TxFailures GCSTelemetryStats 0 @@ -2229,6 +2247,7 @@ 4283782655 + None RxFailures GCSTelemetryStats 0 @@ -2237,6 +2256,7 @@ 4294901760 + None TxRetries GCSTelemetryStats 0 @@ -2260,21 +2280,14 @@ 1000 240 - 4289374847 - RunningTime - AhrsStatus - 0 - 0 - 0 - - 4294945407 + None FlightTime SystemStats 0 0 0 - + 2 1 800 diff --git a/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h b/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h index f02315d2f..3398a3c89 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h @@ -49,6 +49,7 @@ const char * const GCS_VERSION_LONG = GCS_VERSION; const char * const GCS_AUTHOR = "OpenPilot Project"; const char * const GCS_YEAR = "2011"; +const char * const GCS_HELP = "http://wiki.openpilot.org"; #ifdef GCS_REVISION const char * const GCS_REVISION_STR = STRINGIFY(GCS_REVISION); #else diff --git a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp index 1849b4e8b..b35f21cc3 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp @@ -83,6 +83,7 @@ #include #include #include +#include /* #ifdef Q_OS_UNIX @@ -731,10 +732,7 @@ void MainWindow::registerDefaultActions() cmd = am->registerAction(tmpaction, Constants::G_HELP_HELP, m_globalContext); mhelp->addAction(cmd, Constants::G_HELP_HELP); tmpaction->setEnabled(true); -#ifdef Q_WS_MAC - cmd->action()->setMenuRole(QAction::ApplicationSpecificRole); -#endif - connect(tmpaction, SIGNAL(triggered()), this, SLOT(aboutPlugins())); + connect(tmpaction, SIGNAL(triggered()), this, SLOT(showHelp())); // About sep #ifndef Q_WS_MAC // doesn't have the "About" actions in the Help menu @@ -870,6 +868,11 @@ void MainWindow::applyTabBarSettings(QTabWidget::TabPosition pos, bool movable) m_modeStack->setMovable(movable); } +void MainWindow::showHelp() +{ + QDesktopServices::openUrl( QUrl(Constants::GCS_HELP, QUrl::StrictMode) ); +} + ActionManager *MainWindow::actionManager() const { return m_actionManager; diff --git a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.h b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.h index 7d1c61ebc..7ae640fef 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.h @@ -163,6 +163,7 @@ private slots: void modeChanged(Core::IMode *mode); void showUavGadgetMenus(bool show, bool hasSplitter); void applyTabBarSettings(QTabWidget::TabPosition pos, bool movable); + void showHelp(); private: void updateContextObject(IContext *context); diff --git a/ground/openpilotgcs/src/plugins/coreplugin/modemanager.cpp b/ground/openpilotgcs/src/plugins/coreplugin/modemanager.cpp index ac3c4c224..a4479bae2 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/modemanager.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/modemanager.cpp @@ -124,6 +124,17 @@ void ModeManager::activateMode(const QString &id) m_modeStack->setCurrentIndex(index); } +void ModeManager::activateModeByWorkspaceName(const QString &id) +{ + for (int i = 0; i < m_modes.count(); ++i) { + if (m_modes.at(i)->name() == id) + { + m_modeStack->setCurrentIndex(i); + return; + } + } +} + void ModeManager::objectAdded(QObject *obj) { IMode *mode = Aggregation::query(obj); diff --git a/ground/openpilotgcs/src/plugins/coreplugin/modemanager.h b/ground/openpilotgcs/src/plugins/coreplugin/modemanager.h index 687ec0a51..ccaf50607 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/modemanager.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/modemanager.h @@ -80,6 +80,7 @@ signals: public slots: void activateMode(const QString &id); + void activateModeByWorkspaceName(const QString &id); void setFocusToCurrentMode(); private slots: diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp index 68f0162f5..6ee123ff6 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp @@ -49,7 +49,7 @@ GCSControlGadgetWidget::GCSControlGadgetWidget(QWidget *parent) : QLabel(parent) UAVObjectManager *objManager = pm->getObject(); UAVDataObject* obj = dynamic_cast( objManager->getObject(QString("ManualControlCommand")) ); UAVObject::Metadata mdata = obj->getMetadata(); - m_gcscontrol->checkBoxGcsControl->setChecked(mdata.flightAccess == UAVObject::ACCESS_READONLY); + m_gcscontrol->checkBoxGcsControl->setChecked(UAVObject::GetFlightAccess(mdata) == UAVObject::ACCESS_READONLY); // Set up the drop down box for the flightmode UAVDataObject* flightStatus = dynamic_cast( objManager->getObject(QString("FlightStatus")) ); @@ -117,10 +117,10 @@ void GCSControlGadgetWidget::toggleControl(int state) if (state) { mccInitialData = mdata; - mdata.flightAccess = UAVObject::ACCESS_READONLY; - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; - mdata.gcsTelemetryAcked = false; - mdata.gcsTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY); + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE); + UAVObject::SetGcsTelemetryAcked(mdata, false); + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE); mdata.gcsTelemetryUpdatePeriod = 100; } diff --git a/ground/openpilotgcs/src/plugins/hitlnew/fgsimulator.cpp b/ground/openpilotgcs/src/plugins/hitlnew/fgsimulator.cpp index abfb9f75f..fec61c88d 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/fgsimulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitlnew/fgsimulator.cpp @@ -308,13 +308,7 @@ void FGSimulator::processUpdate(const QByteArray& inp) double ECEF[3]; double RNE[9]; Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE); - for (int t=0;t<9;t++) { - homeData.RNE[t]=RNE[t]; - } Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF); - homeData.ECEF[0]=ECEF[0]*100; - homeData.ECEF[1]=ECEF[1]*100; - homeData.ECEF[2]=ECEF[2]*100; homeData.Be[0]=0; homeData.Be[1]=0; homeData.Be[2]=0; @@ -335,7 +329,7 @@ void FGSimulator::processUpdate(const QByteArray& inp) memset(&positionActualData, 0, sizeof(PositionActual::DataFields)); positionActualData.North = 0; //Currently hardcoded as there is no way of setting up a reference point to calculate distance positionActualData.East = 0; //Currently hardcoded as there is no way of setting up a reference point to calculate distance - positionActualData.Down = (altitude * 100); //Multiply by 100 because positionActual expects input in Centimeters. + positionActualData.Down = altitude ; //Multiply by 1 because positionActual expects input in meters. posActual->setData(positionActualData); // Update AltitudeActual object @@ -371,26 +365,39 @@ void FGSimulator::processUpdate(const QByteArray& inp) gpsPos->setData(gpsData); float NED[3]; - double LLA[3] = {(double) gpsData.Latitude / 1e7, (double) gpsData.Longitude / 1e7, (double) (gpsData.GeoidSeparation + gpsData.Altitude)}; // convert from cm back to meters - double ECEF[3] = {(double) (homeData.ECEF[0] / 100), (double) (homeData.ECEF[1] / 100), (double) (homeData.ECEF[2] / 100)}; - Utils::CoordinateConversions().LLA2Base(LLA, ECEF, (float (*)[3]) homeData.RNE, NED); - positionActualData.North = NED[0]*100; //Currently hardcoded as there is no way of setting up a reference point to calculate distance - positionActualData.East = NED[1]*100; //Currently hardcoded as there is no way of setting up a reference point to calculate distance - positionActualData.Down = NED[2]*100; //Multiply by 100 because positionActual expects input in Centimeters. + double hLLA[3] = {(double) homeData.Latitude / 1e7, (double) homeData.Longitude / 1e7, (double) (homeData.Altitude)}; + double ECEF[3]; + double RNE[9]; + Utils::CoordinateConversions().RneFromLLA(hLLA,(double (*)[3])RNE); + Utils::CoordinateConversions().LLA2ECEF(hLLA,ECEF); + Utils::CoordinateConversions().LLA2Base(hLLA, ECEF, (float (*)[3]) RNE, NED); + + positionActualData.North = NED[0]; //Currently hardcoded as there is no way of setting up a reference point to calculate distance + positionActualData.East = NED[1]; //Currently hardcoded as there is no way of setting up a reference point to calculate distance + positionActualData.Down = NED[2]; //Multiply by 1 because positionActual expects input in meters. posActual->setData(positionActualData); // Update AttitudeRaw object (filtered gyros only for now) - AttitudeRaw::DataFields rawData; - memset(&rawData, 0, sizeof(AttitudeRaw::DataFields)); - rawData = attRaw->getData(); - rawData.gyros[0] = rollRate; + //AttitudeRaw::DataFields rawData; + //AttitudeRaw::DataFields rawData; + Gyros::DataFields gyroData; + Accels::DataFields accelData; + memset(&gyroData, 0, sizeof(Gyros::DataFields)); + memset(&accelData, 0, sizeof(Accels::DataFields)); + gyroData = gyros->getData(); + accelData = accels->getData(); + //rawData.gyros[0] = rollRate; //rawData.gyros[1] = cos(DEG2RAD * roll) * pitchRate + sin(DEG2RAD * roll) * yawRate; //rawData.gyros[2] = cos(DEG2RAD * roll) * yawRate - sin(DEG2RAD * roll) * pitchRate; - rawData.gyros[1] = pitchRate; - rawData.gyros[2] = yawRate; - attRaw->setData(rawData); + //rawData.gyros[1] = pitchRate; + //rawData.gyros[2] = yawRate; + gyroData.x = rollRate; + gyroData.y = pitchRate; + gyroData.z = yawRate; + // TODO: Accels are still missing!!!! + gyros->setData(gyroData); // attRaw->updated(); } diff --git a/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp b/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp index 0d957afe4..78f78ffac 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp @@ -263,35 +263,45 @@ void IL2Simulator::processUpdate(const QByteArray& inp) // Update positionActual objects PositionActual::DataFields posData; memset(&posData, 0, sizeof(PositionActual::DataFields)); - posData.North = current.Y*100; - posData.East = current.X*100; - posData.Down = current.Z*-100; + posData.North = current.Y; + posData.East = current.X; + posData.Down = current.Z*-1.; // Update velocityActual objects VelocityActual::DataFields velData; memset(&velData, 0, sizeof(VelocityActual::DataFields)); - velData.North = current.dY*100; - velData.East = current.dX*100; - velData.Down = current.dZ*-100; + velData.North = current.dY; + velData.East = current.dX; + velData.Down = current.dZ*-1.; // Update AttitudeRaw object (filtered gyros and accels only for now) - AttitudeRaw::DataFields rawData; - memset(&rawData, 0, sizeof(AttitudeRaw::DataFields)); - rawData = attRaw->getData(); + //AttitudeRaw::DataFields rawData; + //memset(&rawData, 0, sizeof(AttitudeRaw::DataFields)); + //rawData = attRaw->getData(); + Gyros::DataFields gyroData; + Accels::DataFields accelData; + memset(&gyroData, 0, sizeof(Gyros::DataFields)); + memset(&accelData, 0, sizeof(Accels::DataFields)); + gyroData = gyros->getData(); + accelData = accels->getData(); + // rotate turn rates and accelerations into body frame // (note: rotation deltas are NOT in NED frame but in RPY - manual conversion!) - rawData.gyros[0] = current.dRoll; - rawData.gyros[1] = cos(DEG2RAD * current.roll) * current.dPitch + sin(DEG2RAD * current.roll) * current.dAzimuth; - rawData.gyros[2] = cos(DEG2RAD * current.roll) * current.dAzimuth - sin(DEG2RAD * current.roll) * current.dPitch; + gyroData.x = current.dRoll; + gyroData.y = cos(DEG2RAD * current.roll) * current.dPitch + sin(DEG2RAD * current.roll) * current.dAzimuth; + gyroData.z = cos(DEG2RAD * current.roll) * current.dAzimuth - sin(DEG2RAD * current.roll) * current.dPitch; // accels are in NED and can be converted using standard ned->local rotation matrix float Rbe[3][3]; Utils::CoordinateConversions().Quaternion2R(quat,Rbe); - for (int t=0;t<3;t++) { - rawData.accels[t]=current.ddX*Rbe[t][0] - +current.ddY*Rbe[t][1] - +(current.ddZ+GEE)*Rbe[t][2]; - } - rawData.accels[2]=-rawData.accels[2]; + accelData.x = current.ddX*Rbe[0][0] + +current.ddY*Rbe[0][1] + +(current.ddZ+GEE)*Rbe[0][2]; + accelData.y = current.ddX*Rbe[1][0] + +current.ddY*Rbe[1][1] + +(current.ddZ+GEE)*Rbe[1][2]; + accelData.z = - (current.ddX*Rbe[2][0] + +current.ddY*Rbe[2][1] + +(current.ddZ+GEE)*Rbe[2][2]); // Update homelocation HomeLocation::DataFields homeData; @@ -307,13 +317,7 @@ void IL2Simulator::processUpdate(const QByteArray& inp) double ECEF[3]; double RNE[9]; Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE); - for (int t=0;t<9;t++) { - homeData.RNE[t]=RNE[t]; - } Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF); - homeData.ECEF[0]=ECEF[0]*100; - homeData.ECEF[1]=ECEF[1]*100; - homeData.ECEF[2]=ECEF[2]*100; homeData.Be[0]=0; homeData.Be[1]=0; homeData.Be[2]=0; @@ -339,7 +343,9 @@ void IL2Simulator::processUpdate(const QByteArray& inp) // update every time (50ms) attActual->setData(attActualData); //attActual->updated(); - attRaw->setData(rawData); + //attRaw->setData(rawData); + gyros->setData(gyroData); + accels->setData(accelData); //attRaw->updated(); velActual->setData(velData); //velActual->updated(); diff --git a/ground/openpilotgcs/src/plugins/hitlnew/simulator.cpp b/ground/openpilotgcs/src/plugins/hitlnew/simulator.cpp index c6e2a27e1..2cb7f9ae8 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/simulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitlnew/simulator.cpp @@ -49,7 +49,7 @@ Simulator::Simulator(const SimulatorSettings& params) : outSocket(NULL), settings(params), updatePeriod(50), - simTimeout(2000), + simTimeout(8000), autopilotConnectionStatus(false), simConnectionStatus(false), txTimer(NULL), @@ -131,7 +131,8 @@ void Simulator::onStart() posActual = PositionActual::GetInstance(objManager); altActual = BaroAltitude::GetInstance(objManager); attActual = AttitudeActual::GetInstance(objManager); - attRaw = AttitudeRaw::GetInstance(objManager); + accels = Accels::GetInstance(objManager); + gyros = Gyros::GetInstance(objManager); gpsPos = GPSPosition::GetInstance(objManager); telStats = GCSTelemetryStats::GetInstance(objManager); @@ -225,7 +226,8 @@ void Simulator::setupObjects() setupOutputObject(posActual, 250); setupOutputObject(velActual, 250); setupOutputObject(posHome, 1000); - setupOutputObject(attRaw, 10); + setupOutputObject(accels, 10); + setupOutputObject(gyros, 10); //setupOutputObject(attRaw, 100); @@ -236,12 +238,12 @@ void Simulator::setupInputObject(UAVObject* obj, int updatePeriod) { UAVObject::Metadata mdata; mdata = obj->getDefaultMetadata(); - mdata.flightAccess = UAVObject::ACCESS_READWRITE; - mdata.gcsAccess = UAVObject::ACCESS_READWRITE; - mdata.flightTelemetryAcked = false; - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE); + UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READWRITE); + UAVObject::SetFlightTelemetryAcked(mdata, false); + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); mdata.flightTelemetryUpdatePeriod = updatePeriod; - mdata.gcsTelemetryUpdateMode = UAVObject::UPDATEMODE_MANUAL; + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL); obj->setMetadata(mdata); } @@ -249,11 +251,11 @@ void Simulator::setupOutputObject(UAVObject* obj, int updatePeriod) { UAVObject::Metadata mdata; mdata = obj->getDefaultMetadata(); - mdata.flightAccess = UAVObject::ACCESS_READONLY; - mdata.gcsAccess = UAVObject::ACCESS_READWRITE; - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_NEVER; - mdata.gcsTelemetryAcked = false; - mdata.gcsTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY); + UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READWRITE); + UAVObject::SetFlightTelemetryUpdateMode(mdata,UAVObject::UPDATEMODE_MANUAL); + UAVObject::SetGcsTelemetryAcked(mdata, false); + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); mdata.gcsTelemetryUpdatePeriod = updatePeriod; obj->setMetadata(mdata); } diff --git a/ground/openpilotgcs/src/plugins/hitlnew/simulator.h b/ground/openpilotgcs/src/plugins/hitlnew/simulator.h index 3f5f65355..b345f0a5e 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/simulator.h +++ b/ground/openpilotgcs/src/plugins/hitlnew/simulator.h @@ -44,7 +44,8 @@ #include "attitudeactual.h" #include "gpsposition.h" #include "homelocation.h" -#include "attituderaw.h" +#include "accels.h" +#include "gyros.h" #include "gcstelemetrystats.h" #include "flightstatus.h" @@ -177,7 +178,8 @@ protected: VelocityActual* velActual; PositionActual* posActual; HomeLocation* posHome; - AttitudeRaw* attRaw; + Accels* accels; + Gyros* gyros; GPSPosition* gpsPos; GCSTelemetryStats* telStats; diff --git a/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp b/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp index ab8e485f4..66dbfd1d6 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp @@ -306,13 +306,7 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) double ECEF[3]; double RNE[9]; Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE); - for (int t=0;t<9;t++) { - homeData.RNE[t]=RNE[t]; - } Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF); - homeData.ECEF[0]=ECEF[0]*100; - homeData.ECEF[1]=ECEF[1]*100; - homeData.ECEF[2]=ECEF[2]*100; homeData.Be[0]=0; homeData.Be[1]=0; homeData.Be[2]=0; @@ -368,33 +362,45 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) // Update VelocityActual.{Nort,East,Down} VelocityActual::DataFields velocityActualData; memset(&velocityActualData, 0, sizeof(VelocityActual::DataFields)); - velocityActualData.North = velY*100; - velocityActualData.East = velX*100; - velocityActualData.Down = -velZ*100; + velocityActualData.North = velY; + velocityActualData.East = velX; + velocityActualData.Down = -velZ; velActual->setData(velocityActualData); // Update PositionActual.{Nort,East,Down} PositionActual::DataFields positionActualData; memset(&positionActualData, 0, sizeof(PositionActual::DataFields)); - positionActualData.North = (dstY-initY)*100; - positionActualData.East = (dstX-initX)*100; - positionActualData.Down = -(dstZ-initZ)*100; + positionActualData.North = (dstY-initY); + positionActualData.East = (dstX-initX); + positionActualData.Down = -(dstZ-initZ); posActual->setData(positionActualData); // Update AttitudeRaw object (filtered gyros only for now) - AttitudeRaw::DataFields rawData; - memset(&rawData, 0, sizeof(AttitudeRaw::DataFields)); - rawData = attRaw->getData(); - rawData.gyros[0] = rollRate; + //AttitudeRaw::DataFields rawData; + //memset(&rawData, 0, sizeof(AttitudeRaw::DataFields)); + //rawData = attRaw->getData(); + //rawData.gyros[0] = rollRate; //rawData.gyros_filtered[1] = cos(DEG2RAD * roll) * pitchRate + sin(DEG2RAD * roll) * yawRate; //rawData.gyros_filtered[2] = cos(DEG2RAD * roll) * yawRate - sin(DEG2RAD * roll) * pitchRate; - rawData.gyros[1] = pitchRate; - rawData.gyros[2] = yawRate; - rawData.accels[0] = accX; - rawData.accels[1] = accY; - rawData.accels[2] = -accZ; - attRaw->setData(rawData); + //rawData.gyros[1] = pitchRate; + //rawData.gyros[2] = yawRate; + //rawData.accels[0] = accX; + //rawData.accels[1] = accY; + //rawData.accels[2] = -accZ; + //attRaw->setData(rawData); + Gyros::DataFields gyroData; + memset(&gyroData, 0, sizeof(Gyros::DataFields)); + gyroData.x = rollRate; + gyroData.y = pitchRate; + gyroData.z = yawRate; + gyros->setData(gyroData); + Accels::DataFields accelData; + memset(&accelData, 0, sizeof(Accels::DataFields)); + accelData.x = accX; + accelData.y = accY; + accelData.z = -accZ; + accels->setData(accelData); } // issue manual update diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.cpp new file mode 100644 index 000000000..51daf2460 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.cpp @@ -0,0 +1,468 @@ +#include "aerosimrc.h" +#include +#include +#include + +AeroSimRCSimulator::AeroSimRCSimulator(const SimulatorSettings ¶ms) + : Simulator(params) +{ + udpCounterASrecv = 0; +} + +AeroSimRCSimulator::~AeroSimRCSimulator() +{ +} + +bool AeroSimRCSimulator::setupProcess() +{ + QMutexLocker locker(&lock); + return true; +} + +void AeroSimRCSimulator::setupUdpPorts(const QString &host, int inPort, int outPort) +{ + Q_UNUSED(outPort) + if (inSocket->bind(QHostAddress(host), inPort)) + emit processOutput("Successfully bound to address " + host + ", port " + QString::number(inPort) + "\n"); + else + emit processOutput("Cannot bind to address " + host + ", port " + QString::number(inPort) + "\n"); +} + +void AeroSimRCSimulator::transmitUpdate() +{ + // read actuator output + ActuatorCommand::DataFields actCmdData; + actCmdData = actCommand->getData(); + float channels[10]; + for (int i = 0; i < 10; ++i) { + qint16 ch = actCmdData.Channel[i]; + float out = -1.0; + if (ch >= 1000 && ch <= 2000) { + ch -= 1000; + out = ((float)ch / 500.0) - 1.0; + } + channels[i] = out; + } + + // read flight status + FlightStatus::DataFields flightData; + flightData = flightStatus->getData(); + quint8 armed; + quint8 mode; + armed = flightData.Armed; + mode = flightData.FlightMode; + + QByteArray data; + // 50 - current size of values, 4(quint32) + 10*4(float) + 2(quint8) + 4(quint32) + data.resize(50); + QDataStream stream(&data, QIODevice::WriteOnly); + stream.setFloatingPointPrecision(QDataStream::SinglePrecision); + stream << quint32(0x52434D44); // magic header, "RCMD" + for (int i = 0; i < 10; ++i) + stream << channels[i]; // channels + stream << armed << mode; // flight status + stream << udpCounterASrecv; // packet counter + + if (outSocket->writeDatagram(data, QHostAddress(settings.remoteAddress), settings.outPort) == -1) { + qDebug() << "write failed: " << outSocket->errorString(); + } + +#ifdef DBG_TIMERS + static int cntTX = 0; + if (cntTX >= 100) { + qDebug() << "TX=" << 1000.0 * 100 / timeTX.restart(); + cntTX = 0; + } else { + ++cntTX; + } +#endif +} + +void AeroSimRCSimulator::processUpdate(const QByteArray &data) +{ + // check size + if (data.size() > 188) { + qDebug() << "!!! big datagram: " << data.size(); + return; + } + + QByteArray buf = data; + QDataStream stream(&buf, QIODevice::ReadOnly); + stream.setFloatingPointPrecision(QDataStream::SinglePrecision); + + // check magic header + quint32 magic; + stream >> magic; + if (magic != 0x4153494D) { // "AERO" + qDebug() << "wrong magic: " << magic << ", correct: " << quint32(0x4153494D); + return; + } + + float timeStep, + homeX, homeY, homeZ, + WpHX, WpHY, WpLat, WpLon, + posX, posY, posZ, // world + velX, velY, velZ, // world + angX, angY, angZ, // model + accX, accY, accZ, // model + lat, lon, agl, // world + yaw, pitch, roll, // model + volt, curr, + rx, ry, rz, fx, fy, fz, ux, uy, uz, // matrix + ch[8]; + + stream >> timeStep; + stream >> homeX >> homeY >> homeZ; + stream >> WpHX >> WpHY >> WpLat >> WpLon; + stream >> posX >> posY >> posZ; + stream >> velX >> velY >> velZ; + stream >> angX >> angY >> angZ; + stream >> accX >> accY >> accZ; + stream >> lat >> lon >> agl; + stream >> yaw >> pitch >> roll; + stream >> volt >> curr; + stream >> rx >> ry >> rz >> fx >> fy >> fz >> ux >> uy >> uz; + stream >> ch[0] >> ch[1] >> ch[2] >> ch[3] >> ch[4] >> ch[5] >> ch[6] >> ch[7]; + stream >> udpCounterASrecv; + + /**********************************************************************************************/ + QTime currentTime = QTime::currentTime(); + /**********************************************************************************************/ + static bool firstRun = true; + if (settings.homeLocation) { + if (firstRun) { + HomeLocation::DataFields homeData; + homeData = posHome->getData(); + + homeData.Latitude = WpLat * 10e6; + homeData.Longitude = WpLon * 10e6; + homeData.Altitude = homeZ; + homeData.Set = HomeLocation::SET_TRUE; + + posHome->setData(homeData); + + firstRun = false; + } + if (settings.homeLocRate > 0) { + static QTime homeLocTime = currentTime; + if (homeLocTime.secsTo(currentTime) >= settings.homeLocRate) { + firstRun = true; + homeLocTime = currentTime; + } + } + } + /**********************************************************************************************/ + if (settings.attRaw || settings.attActual) { + QMatrix4x4 mat; + mat = QMatrix4x4( fy, fx, -fz, 0.0, // model matrix + ry, rx, -rz, 0.0, // (X,Y,Z) -> (+Y,+X,-Z) + -uy, -ux, uz, 0.0, + 0.0, 0.0, 0.0, 1.0); + mat.optimize(); + + QQuaternion quat; // model quat + asMatrix2Quat(mat, quat); + + // rotate gravity + QVector3D acc = QVector3D(accY, accX, -accZ); // accel (X,Y,Z) -> (+Y,+X,-Z) + QVector3D gee = QVector3D(0.0, 0.0, -GEE); + QQuaternion qWorld = quat.conjugate(); + gee = qWorld.rotatedVector(gee); + acc += gee; + + /*************************************************************************************/ + if (settings.attRaw) { + Accels::DataFields accelsData; + accelsData = accels->getData(); + Gyros::DataFields gyrosData; + gyrosData = gyros->getData(); + + gyrosData.x = angY * RAD2DEG; // gyros (X,Y,Z) -> (+Y,+X,-Z) + gyrosData.y = angX * RAD2DEG; + gyrosData.z = angZ * -RAD2DEG; + accelsData.x = acc.x(); + accelsData.y = acc.y(); + accelsData.z = acc.z(); + + accels->setData(accelsData); + gyros->setData(gyrosData); + } + /*************************************************************************************/ + if (settings.attActHW) { + // do nothing + /*****************************************/ + } else if (settings.attActSim) { + // take all data from simulator + AttitudeActual::DataFields attActData; + attActData = attActual->getData(); + + QVector3D rpy; // model roll, pitch, yaw + asMatrix2RPY(mat, rpy); + + attActData.Roll = rpy.x(); + attActData.Pitch = rpy.y(); + attActData.Yaw = rpy.z(); + attActData.q1 = quat.scalar(); + attActData.q2 = quat.x(); + attActData.q3 = quat.y(); + attActData.q4 = quat.z(); + + attActual->setData(attActData); + /*****************************************/ + } else if (settings.attActCalc) { + // calculate RPY with code from Attitude module + AttitudeActual::DataFields attActData; + attActData = attActual->getData(); + + static float q[4] = {1, 0, 0, 0}; + static float gyro_correct_int2 = 0; + + float dT = timeStep; + + AttitudeSettings::DataFields attSettData = attSettings->getData(); + float accelKp = attSettData.AccelKp * 0.1666666666666667; + float accelKi = attSettData.AccelKp * 0.1666666666666667; + float yawBiasRate = attSettData.YawBiasRate; + + // calibrate sensors on arming + if (flightStatus->getData().Armed == FlightStatus::ARMED_ARMING) { + accelKp = 2.0; + accelKi = 0.9; + } + + float gyro[3] = {angY * RAD2DEG, angX * RAD2DEG, angZ * -RAD2DEG}; + float attRawAcc[3] = {acc.x(), acc.y(), acc.z()}; + + // code from Attitude module begin /////////////////////////////// + float *accels = attRawAcc; + float grot[3]; + float accel_err[3]; + + // Rotate gravity to body frame and cross with accels + grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2])); + grot[1] = -(2 * (q[2] * q[3] + q[0] * q[1])); + grot[2] = -(q[0] * q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]); + + // CrossProduct + { + accel_err[0] = accels[1]*grot[2] - grot[1]*accels[2]; + accel_err[1] = grot[0]*accels[2] - accels[0]*grot[2]; + accel_err[2] = accels[0]*grot[1] - grot[0]*accels[1]; + } + + // Account for accel magnitude + float accel_mag = sqrt(accels[0] * accels[0] + accels[1] * accels[1] + accels[2] * accels[2]); + accel_err[0] /= accel_mag; + accel_err[1] /= accel_mag; + accel_err[2] /= accel_mag; + + // Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s + gyro_correct_int2 += -gyro[2] * yawBiasRate; + + // Correct rates based on error, integral component dealt with in updateSensors + gyro[0] += accel_err[0] * accelKp / dT; + gyro[1] += accel_err[1] * accelKp / dT; + gyro[2] += accel_err[2] * accelKp / dT + gyro_correct_int2; + + // Work out time derivative from INSAlgo writeup + // Also accounts for the fact that gyros are in deg/s + float qdot[4]; + qdot[0] = (-q[1] * gyro[0] - q[2] * gyro[1] - q[3] * gyro[2]) * dT * M_PI / 180 / 2; + qdot[1] = (+q[0] * gyro[0] - q[3] * gyro[1] + q[2] * gyro[2]) * dT * M_PI / 180 / 2; + qdot[2] = (+q[3] * gyro[0] + q[0] * gyro[1] - q[1] * gyro[2]) * dT * M_PI / 180 / 2; + qdot[3] = (-q[2] * gyro[0] + q[1] * gyro[1] + q[0] * gyro[2]) * dT * M_PI / 180 / 2; + + // Take a time step + q[0] += qdot[0]; + q[1] += qdot[1]; + q[2] += qdot[2]; + q[3] += qdot[3]; + + if(q[0] < 0) { + q[0] = -q[0]; + q[1] = -q[1]; + q[2] = -q[2]; + q[3] = -q[3]; + } + + // Renomalize + float qmag = sqrt((q[0] * q[0]) + (q[1] * q[1]) + (q[2] * q[2]) + (q[3] * q[3])); + q[0] /= qmag; + q[1] /= qmag; + q[2] /= qmag; + q[3] /= qmag; + + // If quaternion has become inappropriately short or is nan reinit. + // THIS SHOULD NEVER ACTUALLY HAPPEN + if((fabs(qmag) < 1e-3) || (qmag != qmag)) { + q[0] = 1; + q[1] = 0; + q[2] = 0; + q[3] = 0; + } + + float rpy2[3]; + // Quaternion2RPY + { + float q0s, q1s, q2s, q3s; + q0s = q[0] * q[0]; + q1s = q[1] * q[1]; + q2s = q[2] * q[2]; + q3s = q[3] * q[3]; + + float R13, R11, R12, R23, R33; + R13 = 2 * (q[1] * q[3] - q[0] * q[2]); + R11 = q0s + q1s - q2s - q3s; + R12 = 2 * (q[1] * q[2] + q[0] * q[3]); + R23 = 2 * (q[2] * q[3] + q[0] * q[1]); + R33 = q0s - q1s - q2s + q3s; + + rpy2[1] = RAD2DEG * asinf(-R13); // pitch always between -pi/2 to pi/2 + rpy2[2] = RAD2DEG * atan2f(R12, R11); + rpy2[0] = RAD2DEG * atan2f(R23, R33); + } + + attActData.Roll = rpy2[0]; + attActData.Pitch = rpy2[1]; + attActData.Yaw = rpy2[2]; + attActData.q1 = q[0]; + attActData.q2 = q[1]; + attActData.q3 = q[2]; + attActData.q4 = q[3]; + attActual->setData(attActData); + /*****************************************/ + } + } + /**********************************************************************************************/ + if (settings.gcsReciever) { + static QTime gcsRcvrTime = currentTime; + if (!settings.manualOutput || gcsRcvrTime.msecsTo(currentTime) >= settings.outputRate) { + GCSReceiver::DataFields gcsRcvrData; + gcsRcvrData = gcsReceiver->getData(); + + for (int i = 0; i < 8; ++i) + gcsRcvrData.Channel[i] = 1500 + (ch[i] * 500); + + gcsReceiver->setData(gcsRcvrData); + if (settings.manualOutput) + gcsRcvrTime = currentTime; + } + } else if (settings.manualControl) { + // not implemented yet + } + /**********************************************************************************************/ + if (settings.gpsPosition) { + static QTime gpsPosTime = currentTime; + if (gpsPosTime.msecsTo(currentTime) >= settings.gpsPosRate) { + GPSPosition::DataFields gpsPosData; + gpsPosData = gpsPosition->getData(); + + gpsPosData.Altitude = posZ; + gpsPosData.Heading = yaw * RAD2DEG; + gpsPosData.Latitude = lat * 10e6; + gpsPosData.Longitude = lon * 10e6; + gpsPosData.Groundspeed = qSqrt(velX * velX + velY * velY); + gpsPosData.GeoidSeparation = 0.0; + gpsPosData.Satellites = 8; + gpsPosData.PDOP = 3.0; + gpsPosData.Status = GPSPosition::STATUS_FIX3D; + + gpsPosition->setData(gpsPosData); + gpsPosTime = currentTime; + } + } + /**********************************************************************************************/ + if (settings.sonarAltitude) { + static QTime sonarAltTime = currentTime; + if (sonarAltTime.msecsTo(currentTime) >= settings.sonarAltRate) { + SonarAltitude::DataFields sonarAltData; + sonarAltData = sonarAlt->getData(); + + float sAlt = settings.sonarMaxAlt; + // 0.35 rad ~= 20 degree + if ((agl < (sAlt * 2.0)) && (roll < 0.35) && (pitch < 0.35)) { + float x = agl * qTan(roll); + float y = agl * qTan(pitch); + float h = qSqrt(x*x + y*y + agl*agl); + sAlt = qMin(h, sAlt); + } + + sonarAltData.Altitude = sAlt; + sonarAlt->setData(sonarAltData); + sonarAltTime = currentTime; + } + } + /**********************************************************************************************/ +/* + BaroAltitude::DataFields altActData; + altActData = altActual->getData(); + altActData.Altitude = posZ; + altActual->setData(altActData); + + PositionActual::DataFields posActData; + posActData = posActual->getData(); + posActData.North = posY * 100; + posActData.East = posX * 100; + posActData.Down = posZ * -100; + posActual->setData(posActData); + + VelocityActual::DataFields velActData; + velActData = velActual->getData(); + velActData.North = velY * 100; + velActData.East = velX * 100; + velActData.Down = velZ * 100; + velActual->setData(velActData); +*/ + +#ifdef DBG_TIMERS + static int cntRX = 0; + if (cntRX >= 100) { + qDebug() << "RX=" << 1000.0 * 100 / timeRX.restart(); + cntRX = 0; + } else { + ++cntRX; + } +#endif +} + +// transfomations + +void AeroSimRCSimulator::asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q) +{ + qreal w, x, y, z; + + // w always >= 0 + w = qSqrt(qMax(0.0, 1.0 + m(0, 0) + m(1, 1) + m(2, 2))) / 2.0; + x = qSqrt(qMax(0.0, 1.0 + m(0, 0) - m(1, 1) - m(2, 2))) / 2.0; + y = qSqrt(qMax(0.0, 1.0 - m(0, 0) + m(1, 1) - m(2, 2))) / 2.0; + z = qSqrt(qMax(0.0, 1.0 - m(0, 0) - m(1, 1) + m(2, 2))) / 2.0; + + x = copysign(x, (m(1, 2) - m(2, 1))); + y = copysign(y, (m(2, 0) - m(0, 2))); + z = copysign(z, (m(0, 1) - m(1, 0))); + + q.setScalar(w); + q.setX(x); + q.setY(y); + q.setZ(z); +} + +void AeroSimRCSimulator::asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy) +{ + qreal roll, pitch, yaw; + + if (qFabs(m(0, 2)) > 0.998) { + // ~86.3°, gimbal lock + roll = 0.0; + pitch = copysign(M_PI_2, -m(0, 2)); + yaw = qAtan2(-m(1, 0), m(1, 1)); + } else { + roll = qAtan2(m(1, 2), m(2, 2)); + pitch = qAsin(-m(0, 2)); + yaw = qAtan2(m(0, 1), m(0, 0)); + } + + rpy.setX(roll * RAD2DEG); + rpy.setY(pitch * RAD2DEG); + rpy.setZ(yaw * RAD2DEG); +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.h new file mode 100644 index 000000000..19dae3bce --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.h @@ -0,0 +1,46 @@ +#ifndef AEROSIMRC_H +#define AEROSIMRC_H + +#include +#include +#include +#include +#include "simulatorv2.h" + +class AeroSimRCSimulator: public Simulator +{ + Q_OBJECT + +public: + AeroSimRCSimulator(const SimulatorSettings ¶ms); + ~AeroSimRCSimulator(); + + bool setupProcess(); + void setupUdpPorts(const QString& host, int inPort, int outPort); + +private slots: + void transmitUpdate(); + +private: + quint32 udpCounterASrecv; //keeps track of udp packets received by ASim + + void processUpdate(const QByteArray &data); + + void asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q); + void asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy); +}; + +class AeroSimRCSimulatorCreator : public SimulatorCreator +{ +public: + AeroSimRCSimulatorCreator(const QString &classId, const QString &description) + : SimulatorCreator (classId, description) + {} + + Simulator* createSimulator(const SimulatorSettings ¶ms) + { + return new AeroSimRCSimulator(params); + } +}; + +#endif // AEROSIMRC_H diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.pluginspec b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pluginspec similarity index 55% rename from ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.pluginspec rename to ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pluginspec index f67f414af..26fede385 100644 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.pluginspec +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pluginspec @@ -1,13 +1,12 @@ - - The OpenPilot Project - (C) 2011 Cathy Moss A.K.A. Pip - The GNU Public License (GPL) Version 3 - A plugin to configure the PipXtreme OP modem via USB HID or Serial Port - http://www.openpilot.org - - - - - - - + + The OpenPilot Project + (C) 2011 OpenPilot Project + The GNU Public License (GPL) Version 3 + Hardware In The Loop Simulation (v2) + http://www.openpilot.org + + + + + + diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pro b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pro new file mode 100644 index 000000000..58475b05f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pro @@ -0,0 +1,27 @@ +TEMPLATE = lib +TARGET = HITLv2 +QT += network +include(../../openpilotgcsplugin.pri) +include(hitlv2_dependencies.pri) +HEADERS += \ + aerosimrc.h \ + hitlv2configuration.h \ + hitlv2factory.h \ + hitlv2gadget.h \ + hitlv2optionspage.h \ + hitlv2plugin.h \ + hitlv2widget.h \ + simulatorv2.h +SOURCES += \ + aerosimrc.cpp \ + hitlv2configuration.cpp \ + hitlv2factory.cpp \ + hitlv2gadget.cpp \ + hitlv2optionspage.cpp \ + hitlv2plugin.cpp \ + hitlv2widget.cpp \ + simulatorv2.cpp +OTHER_FILES += hitlv2.pluginspec +FORMS += \ + hitlv2optionspage.ui \ + hitlv2widget.ui diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2_dependencies.pri b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2_dependencies.pri new file mode 100644 index 000000000..50268face --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2_dependencies.pri @@ -0,0 +1,4 @@ +include(../../plugins/uavobjects/uavobjects.pri) +include(../../plugins/uavtalk/uavtalk.pri) +#include(../../plugins/coreplugin/coreplugin.pri) +#include(../../libs/utils/utils.pri) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.cpp new file mode 100644 index 000000000..890742e41 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.cpp @@ -0,0 +1,178 @@ +/** + ****************************************************************************** + * + * @file hitlconfiguration.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITL Plugin + * @{ + * @brief The Hardware In The Loop plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "hitlv2configuration.h" + +HITLConfiguration::HITLConfiguration(QString classId, + QSettings* qSettings, + QObject *parent) + : IUAVGadgetConfiguration(classId, parent) +{ +// qDebug() << "HITLV2Configuration"; + // default values + QString simulatorId = "ASimRC"; + QString hostAddress = "127.0.0.1"; + int inPort = 40100; + QString remoteAddress = "127.0.0.1"; + int outPort = 40200; + QString binPath = ""; + QString dataPath = ""; + + bool homeLocation = true; + quint16 homeLocRate = 0; + + bool attRaw = true; + quint8 attRawRate = 20; + + bool attActual = true; + bool attActHW = false; + bool attActSim = true; + bool attActCalc = false; + + bool sonarAltitude = false; + float sonarMaxAlt = 5.0; + quint16 sonarAltRate = 50; + + bool gpsPosition = true; + quint16 gpsPosRate = 200; + + bool inputCommand = true; + bool gcsReciever = true; + bool manualControl = false; + + bool manualOutput = false; + quint8 outputRate = 20; + + // if a saved configuration exists load it + if (qSettings != 0) { + settings.simulatorId = qSettings->value("simulatorId", simulatorId).toString(); + settings.hostAddress = qSettings->value("hostAddress", hostAddress).toString(); + settings.inPort = qSettings->value("inPort", inPort).toInt(); + settings.remoteAddress = qSettings->value("remoteAddress", remoteAddress).toString(); + settings.outPort = qSettings->value("outPort", outPort).toInt(); + settings.binPath = qSettings->value("binPath", binPath).toString(); + settings.dataPath = qSettings->value("dataPath", dataPath).toString(); + + settings.homeLocation = qSettings->value("homeLocation", homeLocation).toBool(); + settings.homeLocRate = qSettings->value("homeLocRate", homeLocRate).toInt(); + + settings.attRaw = qSettings->value("attRaw", attRaw).toBool(); + settings.attRawRate = qSettings->value("attRawRate", attRawRate).toInt(); + + settings.attActual = qSettings->value("attActual", attActual).toBool(); + settings.attActHW = qSettings->value("attActHW", attActHW).toBool(); + settings.attActSim = qSettings->value("attActSim", attActSim).toBool(); + settings.attActCalc = qSettings->value("attActCalc", attActCalc).toBool(); + + settings.sonarAltitude = qSettings->value("sonarAltitude", sonarAltitude).toBool(); + settings.sonarMaxAlt = qSettings->value("sonarMaxAlt", sonarMaxAlt).toFloat(); + settings.sonarAltRate = qSettings->value("sonarAltRate", sonarAltRate).toInt(); + + settings.gpsPosition = qSettings->value("gpsPosition", gpsPosition).toBool(); + settings.gpsPosRate = qSettings->value("gpsPosRate", gpsPosRate).toInt(); + + settings.inputCommand = qSettings->value("inputCommand", inputCommand).toBool(); + settings.gcsReciever = qSettings->value("gcsReciever", gcsReciever).toBool(); + settings.manualControl = qSettings->value("manualControl", manualControl).toBool(); + settings.manualOutput = qSettings->value("manualOutput", manualOutput).toBool(); + settings.outputRate = qSettings->value("outputRate", outputRate).toInt(); + } else { + settings.simulatorId = simulatorId; + settings.hostAddress = hostAddress; + settings.inPort = inPort; + settings.remoteAddress = remoteAddress; + settings.outPort = outPort; + settings.binPath = binPath; + settings.dataPath = dataPath; + + settings.homeLocation = homeLocation; + settings.homeLocRate = homeLocRate; + + settings.attRaw = attRaw; + settings.attRawRate = attRawRate; + + settings.attActual = attActual; + settings.attActHW = attActHW; + settings.attActSim = attActSim; + settings.attActCalc = attActCalc; + + settings.sonarAltitude = sonarAltitude; + settings.sonarMaxAlt = sonarMaxAlt; + settings.sonarAltRate = sonarAltRate; + + settings.gpsPosition = gpsPosition; + settings.gpsPosRate = gpsPosRate; + + settings.inputCommand = inputCommand; + settings.gcsReciever = gcsReciever; + settings.manualControl = manualControl; + settings.manualOutput = manualOutput; + settings.outputRate = outputRate; + } +} + +IUAVGadgetConfiguration *HITLConfiguration::clone() +{ + HITLConfiguration *m = new HITLConfiguration(this->classId()); + m->settings = settings; + return m; +} + +void HITLConfiguration::saveConfig(QSettings* qSettings) const +{ + qSettings->setValue("simulatorId", settings.simulatorId); + qSettings->setValue("hostAddress", settings.hostAddress); + qSettings->setValue("inPort", settings.inPort); + qSettings->setValue("remoteAddress", settings.remoteAddress); + qSettings->setValue("outPort", settings.outPort); + qSettings->setValue("binPath", settings.binPath); + qSettings->setValue("dataPath", settings.dataPath); + + qSettings->setValue("homeLocation", settings.homeLocation); + qSettings->setValue("homeLocRate", settings.homeLocRate); + + qSettings->setValue("attRaw", settings.attRaw); + qSettings->setValue("attRawRate", settings.attRawRate); + + qSettings->setValue("attActual", settings.attActual); + qSettings->setValue("attActHW", settings.attActHW); + qSettings->setValue("attActSim", settings.attActSim); + qSettings->setValue("attActCalc", settings.attActCalc); + + qSettings->setValue("sonarAltitude", settings.sonarAltitude); + qSettings->setValue("sonarMaxAlt", settings.sonarMaxAlt); + qSettings->setValue("sonarAltRate", settings.sonarAltRate); + + qSettings->setValue("gpsPosition", settings.gpsPosition); + qSettings->setValue("gpsPosRate", settings.gpsPosRate); + + qSettings->setValue("inputCommand", settings.inputCommand); + qSettings->setValue("gcsReciever", settings.gcsReciever); + qSettings->setValue("manualControl", settings.manualControl); + qSettings->setValue("manualOutput", settings.manualOutput); + qSettings->setValue("outputRate", settings.outputRate); +} diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetconfiguration.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.h similarity index 59% rename from ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetconfiguration.h rename to ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.h index e65a5368c..dfac80ddf 100644 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.h @@ -1,12 +1,13 @@ /** ****************************************************************************** * - * @file pipxtremegadgetconfiguration.h + * @file hitlconfiguration.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ + * @addtogroup HITLPlugin HITL Plugin * @{ - * @brief The YModem protocol serial uploader plugin + * @brief The Hardware In The Loop plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -24,25 +25,37 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef PIPXTREMEGADGETCONFIGURATION_H -#define PIPXTREMEGADGETCONFIGURATION_H +#ifndef HITLV2CONFIGURATION_H +#define HITLV2CONFIGURATION_H #include -#include +#include +#include +#include using namespace Core; -class PipXtremeGadgetConfiguration : public IUAVGadgetConfiguration +class HITLConfiguration : public IUAVGadgetConfiguration { -Q_OBJECT -public: - explicit PipXtremeGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); - ~PipXtremeGadgetConfiguration(); - void saveConfig(QSettings *settings) const; + Q_OBJECT + + Q_PROPERTY(SimulatorSettings settings READ Settings WRITE setSimulatorSettings) + +public: + explicit HITLConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); + + void saveConfig(QSettings* settings) const; IUAVGadgetConfiguration *clone(); + SimulatorSettings Settings() const { return settings; } + +public slots: + void setSimulatorSettings (const SimulatorSettings& params ) { settings = params; } + + private: + SimulatorSettings settings; }; -#endif +#endif // HITLV2CONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetfactory.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.cpp similarity index 54% rename from ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetfactory.cpp rename to ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.cpp index 4574913d5..6e6f1a42e 100644 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetfactory.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.cpp @@ -1,11 +1,13 @@ /** ****************************************************************************** * - * @file pipxtremegadgetfactory.cpp + * @file hitlfactory.cpp * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ + * @addtogroup HITLPlugin HITL Plugin * @{ + * @brief The Hardware In The Loop plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -22,30 +24,35 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ - -#include "pipxtremegadgetfactory.h" -#include "pipxtremegadgetwidget.h" -#include "pipxtremegadget.h" -#include "pipxtremegadgetconfiguration.h" -#include "pipxtremegadgetoptionspage.h" +#include "hitlv2factory.h" +#include "hitlv2widget.h" +#include "hitlv2gadget.h" +#include "hitlv2configuration.h" +#include "hitlv2optionspage.h" #include -PipXtremeGadgetFactory::PipXtremeGadgetFactory(QObject *parent) : - IUAVGadgetFactory(QString("PipXtreme"), tr("PipXtreme"), parent) +HITLFactory::HITLFactory(QObject *parent) + : IUAVGadgetFactory(QString("HITLv2"), tr("HITL Simulation (v2)"), parent) { } -PipXtremeGadgetFactory::~PipXtremeGadgetFactory() +HITLFactory::~HITLFactory() { } -Core::IUAVGadget* PipXtremeGadgetFactory::createGadget(QWidget *parent) +Core::IUAVGadget* HITLFactory::createGadget(QWidget *parent) { - PipXtremeGadgetWidget *gadgetWidget = new PipXtremeGadgetWidget(parent); - return new PipXtremeGadget(QString("PipXtreme"), gadgetWidget, parent); + HITLWidget* gadgetWidget = new HITLWidget(parent); + return new HITLGadget(QString("HITLv2"), gadgetWidget, parent); } -IUAVGadgetConfiguration * PipXtremeGadgetFactory::createConfiguration(QSettings *qSettings) +IUAVGadgetConfiguration *HITLFactory::createConfiguration(QSettings* qSettings) { - return new PipXtremeGadgetConfiguration(QString("PipXtreme"), qSettings); + return new HITLConfiguration(QString("HITLv2"), qSettings); } + +IOptionsPage *HITLFactory::createOptionsPage(IUAVGadgetConfiguration *config) +{ + return new HITLOptionsPage(qobject_cast(config)); +} + diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetfactory.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.h similarity index 68% rename from ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetfactory.h rename to ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.h index 8bd48f46b..b4142eeed 100644 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetfactory.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.h @@ -1,11 +1,13 @@ /** ****************************************************************************** * - * @file pipxtremegadgetfactory.h + * @file hitlfactory.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ + * @addtogroup HITLPlugin HITL Plugin * @{ + * @brief The Hardware In The Loop plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -23,28 +25,28 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef PIPXTREMEGADGETFACTORY_H -#define PIPXTREMEGADGETFACTORY_H +#ifndef HITLV2FACTORY_H +#define HITLV2FACTORY_H #include namespace Core { - class IUAVGadget; - class IUAVGadgetFactory; +class IUAVGadget; +class IUAVGadgetFactory; } using namespace Core; -class PipXtremeGadgetFactory : public Core::IUAVGadgetFactory +class HITLFactory : public Core::IUAVGadgetFactory { Q_OBJECT - public: - PipXtremeGadgetFactory(QObject *parent = 0); - ~PipXtremeGadgetFactory(); + HITLFactory(QObject *parent = 0); + ~HITLFactory(); - Core::IUAVGadget * createGadget(QWidget *parent); - IUAVGadgetConfiguration * createConfiguration(QSettings *qSettings); + IUAVGadget *createGadget(QWidget *parent); + IUAVGadgetConfiguration *createConfiguration(QSettings* qSettings); + IOptionsPage *createOptionsPage(IUAVGadgetConfiguration *config); }; -#endif +#endif // HITLV2FACTORY_H diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadget.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.cpp similarity index 59% rename from ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadget.cpp rename to ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.cpp index d38e36b67..de22d121b 100644 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadget.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.cpp @@ -1,11 +1,13 @@ /** ****************************************************************************** * - * @file pipxtremegadget.cpp + * @file hitl.cpp * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ + * @addtogroup HITLPlugin HITL Plugin * @{ + * @brief The Hardware In The Loop plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -22,27 +24,26 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "pipxtremegadget.h" -#include "pipxtremegadgetwidget.h" -#include "pipxtremegadgetconfiguration.h" +#include "hitlv2gadget.h" +#include "hitlv2widget.h" +#include "hitlv2configuration.h" +#include "simulatorv2.h" -PipXtremeGadget::PipXtremeGadget(QString classId, PipXtremeGadgetWidget *widget, QWidget *parent) : - IUAVGadget(classId, parent), - m_widget(widget) +HITLGadget::HITLGadget(QString classId, HITLWidget *widget, QWidget *parent) : + IUAVGadget(classId, parent), + m_widget(widget) { + connect(this, SIGNAL(changeConfiguration(void)), m_widget, SLOT(stopButtonClicked(void))); } -PipXtremeGadget::~PipXtremeGadget() +HITLGadget::~HITLGadget() { - delete m_widget; - m_widget = NULL; + delete m_widget; } -// Loads a configuration. -void PipXtremeGadget::loadConfiguration(IUAVGadgetConfiguration* config) +void HITLGadget::loadConfiguration(IUAVGadgetConfiguration* config) { - Q_UNUSED(config); -/* PipXtremeGadgetConfiguration *m = qobject_cast< PipXtremeGadgetConfiguration*>(config); - */ + HITLConfiguration *m = qobject_cast(config); + emit changeConfiguration(); + m_widget->setSettingParameters(m->Settings()); } - diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadget.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.h similarity index 73% rename from ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadget.h rename to ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.h index 547cb81a4..0e4fd1a80 100644 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadget.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.h @@ -1,55 +1,60 @@ -/** - ****************************************************************************** - * - * @file pipxtremegadget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @{ - * @brief The YModem protocol serial uploader plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIPXTREMEGADGET_H -#define PIPXTREMEGADGET_H - -#include -#include "pipxtremegadgetwidget.h" - -class IUAVGadget; -class QWidget; -class QString; -class PipXtremeGadgetWidget; - -using namespace Core; - -class PipXtremeGadget : public Core::IUAVGadget -{ - Q_OBJECT -public: - PipXtremeGadget(QString classId, PipXtremeGadgetWidget *widget, QWidget *parent = 0); - ~PipXtremeGadget(); - - QWidget *widget() { return m_widget; } - void loadConfiguration(IUAVGadgetConfiguration* config); - -private: - PipXtremeGadgetWidget *m_widget; -}; - -#endif - +/** + ****************************************************************************** + * + * @file hitl.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITL Plugin + * @{ + * @brief The Hardware In The Loop plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef HITLV2_H +#define HITLV2_H + +#include +#include "hitlv2widget.h" + +class IUAVGadget; +class QWidget; +class QString; +class Simulator; + +using namespace Core; + +class HITLGadget : public Core::IUAVGadget +{ + Q_OBJECT +public: + HITLGadget(QString classId, HITLWidget *widget, QWidget *parent = 0); + ~HITLGadget(); + + QWidget *widget() { return m_widget; } + void loadConfiguration(IUAVGadgetConfiguration* config); + +signals: + void changeConfiguration(); + +private: + HITLWidget* m_widget; + Simulator* simulator; +}; + + +#endif // HITLV2_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.cpp new file mode 100644 index 000000000..5b88785ad --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.cpp @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file hitloptionspage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITL Plugin + * @{ + * @brief The Hardware In The Loop plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "hitlv2optionspage.h" +#include "hitlv2configuration.h" +#include "ui_hitlv2optionspage.h" +#include "hitlv2plugin.h" + +#include +#include +#include +#include "simulatorv2.h" + +HITLOptionsPage::HITLOptionsPage(HITLConfiguration *conf, QObject *parent) : + IOptionsPage(parent), + config(conf) +{ +} + +QWidget *HITLOptionsPage::createPage(QWidget *parent) +{ +// qDebug() << "HITLOptionsPage::createPage"; + // Create page + m_optionsPage = new Ui::HITLOptionsPage(); + QWidget* optionsPageWidget = new QWidget; + m_optionsPage->setupUi(optionsPageWidget); + int index = 0; + foreach (SimulatorCreator* creator, HITLPlugin::typeSimulators) + m_optionsPage->chooseFlightSimulator->insertItem(index++, creator->Description(), creator->ClassId()); + + m_optionsPage->executablePath->setExpectedKind(Utils::PathChooser::File); + m_optionsPage->executablePath->setPromptDialogTitle(tr("Choose flight simulator executable")); + m_optionsPage->dataPath->setExpectedKind(Utils::PathChooser::Directory); + m_optionsPage->dataPath->setPromptDialogTitle(tr("Choose flight simulator data directory")); + + // Restore the contents from the settings: + foreach (SimulatorCreator* creator, HITLPlugin::typeSimulators) { + QString id = config->Settings().simulatorId; + if (creator->ClassId() == id) + m_optionsPage->chooseFlightSimulator->setCurrentIndex(HITLPlugin::typeSimulators.indexOf(creator)); + } + + m_optionsPage->hostAddress->setText(config->Settings().hostAddress); + m_optionsPage->inputPort->setText(QString::number(config->Settings().inPort)); + m_optionsPage->remoteAddress->setText(config->Settings().remoteAddress); + m_optionsPage->outputPort->setText(QString::number(config->Settings().outPort)); + m_optionsPage->executablePath->setPath(config->Settings().binPath); + m_optionsPage->dataPath->setPath(config->Settings().dataPath); + + m_optionsPage->homeLocation->setChecked(config->Settings().homeLocation); + m_optionsPage->homeLocRate->setValue(config->Settings().homeLocRate); + + m_optionsPage->attRaw->setChecked(config->Settings().attRaw); + m_optionsPage->attRawRate->setValue(config->Settings().attRawRate); + + m_optionsPage->attActual->setChecked(config->Settings().attActual); + m_optionsPage->attActHW->setChecked(config->Settings().attActHW); + m_optionsPage->attActSim->setChecked(config->Settings().attActSim); + m_optionsPage->attActCalc->setChecked(config->Settings().attActCalc); + + m_optionsPage->sonarAltitude->setChecked(config->Settings().sonarAltitude); + m_optionsPage->sonarMaxAlt->setValue(config->Settings().sonarMaxAlt); + m_optionsPage->sonarAltRate->setValue(config->Settings().sonarAltRate); + + m_optionsPage->gpsPosition->setChecked(config->Settings().gpsPosition); + m_optionsPage->gpsPosRate->setValue(config->Settings().gpsPosRate); + + m_optionsPage->inputCommand->setChecked(config->Settings().inputCommand); + m_optionsPage->gcsReciever->setChecked(config->Settings().gcsReciever); + m_optionsPage->manualControl->setChecked(config->Settings().manualControl); + + m_optionsPage->manualOutput->setChecked(config->Settings().manualOutput); + m_optionsPage->outputRate->setValue(config->Settings().outputRate); + + return optionsPageWidget; +} + +void HITLOptionsPage::apply() +{ + SimulatorSettings settings; + int i = m_optionsPage->chooseFlightSimulator->currentIndex(); + + settings.simulatorId = m_optionsPage->chooseFlightSimulator->itemData(i).toString(); + settings.hostAddress = m_optionsPage->hostAddress->text(); + settings.inPort = m_optionsPage->inputPort->text().toInt(); + settings.remoteAddress = m_optionsPage->remoteAddress->text(); + settings.outPort = m_optionsPage->outputPort->text().toInt(); + settings.binPath = m_optionsPage->executablePath->path(); + settings.dataPath = m_optionsPage->dataPath->path(); + + settings.homeLocation = m_optionsPage->homeLocation->isChecked(); + settings.homeLocRate = m_optionsPage->homeLocRate->value(); + + settings.attRaw = m_optionsPage->attRaw->isChecked(); + settings.attRawRate = m_optionsPage->attRawRate->value(); + + settings.attActual = m_optionsPage->attActual->isChecked(); + settings.attActHW = m_optionsPage->attActHW->isChecked(); + settings.attActSim = m_optionsPage->attActSim->isChecked(); + settings.attActCalc = m_optionsPage->attActCalc->isChecked(); + + settings.sonarAltitude = m_optionsPage->sonarAltitude->isChecked(); + settings.sonarMaxAlt = m_optionsPage->sonarMaxAlt->value(); + settings.sonarAltRate = m_optionsPage->sonarAltRate->value(); + + settings.gpsPosition = m_optionsPage->gpsPosition->isChecked(); + settings.gpsPosRate = m_optionsPage->gpsPosRate->value(); + + settings.inputCommand = m_optionsPage->inputCommand->isChecked(); + settings.gcsReciever = m_optionsPage->gcsReciever->isChecked(); + settings.manualControl = m_optionsPage->manualControl->isChecked(); + + settings.manualOutput = m_optionsPage->manualOutput->isChecked(); + settings.outputRate = m_optionsPage->outputRate->value(); + + config->setSimulatorSettings(settings); +} + +void HITLOptionsPage::finish() +{ + delete m_optionsPage; +} diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetoptionspage.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.h similarity index 64% rename from ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetoptionspage.h rename to ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.h index 97aa0006e..5c8d33f59 100644 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetoptionspage.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.h @@ -1,11 +1,13 @@ /** ****************************************************************************** * - * @file pipxtremegadgetoptionspage.h + * @file hitloptionspage.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ + * @addtogroup HITLPlugin HITL Plugin * @{ + * @brief The Hardware In The Loop plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -23,40 +25,37 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef PIPXTREMEGADGETOPTIONSPAGE_H -#define PIPXTREMEGADGETOPTIONSPAGE_H +#ifndef HITLV2OPTIONSPAGE_H +#define HITLV2OPTIONSPAGE_H -#include -#include "coreplugin/dialogs/ioptionspage.h" -#include "QString" -#include -#include +#include namespace Core { - class IUAVGadgetConfiguration; +class IUAVGadgetConfiguration; } -class PipXtremeGadgetConfiguration; - -namespace Ui { - class PipXtremeGadgetOptionsPage; -} +class HITLConfiguration; using namespace Core; -class PipXtremeGadgetOptionsPage : public IOptionsPage +namespace Ui { +class HITLOptionsPage; +} + +class HITLOptionsPage : public IOptionsPage { -Q_OBJECT + Q_OBJECT public: - explicit PipXtremeGadgetOptionsPage(PipXtremeGadgetConfiguration *config, QObject *parent = 0); + explicit HITLOptionsPage(HITLConfiguration *conf, QObject *parent = 0); QWidget *createPage(QWidget *parent); void apply(); void finish(); + bool isDecorated() const { return true; } private: - Ui::PipXtremeGadgetOptionsPage *options_page; - PipXtremeGadgetConfiguration *m_config; + HITLConfiguration* config; + Ui::HITLOptionsPage* m_optionsPage; }; -#endif +#endif // HITLV2OPTIONSPAGE_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.ui b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.ui new file mode 100644 index 000000000..00a2f60aa --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.ui @@ -0,0 +1,639 @@ + + + HITLOptionsPage + + + + 0 + 0 + 403 + 400 + + + + Form + + + + 3 + + + 0 + + + 0 + + + 0 + + + 3 + + + + + + + Choose flight simulator: + + + + + + + + + + + + + + Local interface (IP): + + + + + + + For communication with sim computer via network. Should be the IP address of one of the interfaces of the GCS computer. + + + + + + + Remote interface (IP): + + + + + + + Only required if running simulator on remote machine. Should be the IP of the machine on which the simulator is running. + + + + + + + Input Port: + + + + + + + For receiving data from sim + + + + + + + Output Port: + + + + + + + For sending data to sim + + + + + + + + + QFormLayout::AllNonFixedFieldsGrow + + + + + + 0 + 0 + + + + Path executable: + + + + + + + + + + + 0 + 0 + + + + Data directory: + + + + + + + + + + + + + + Attitude data + + + + 3 + + + 3 + + + 3 + + + 3 + + + 0 + + + + + AttitudeRaw (gyro, accels) + + + true + + + true + + + false + + + + 3 + + + 3 + + + 0 + + + 0 + + + + + Refresh rate + + + + + + + ms + + + 10 + + + 100 + + + 20 + + + + + + + + + + AttitudeActual + + + true + + + true + + + false + + + + 3 + + + 3 + + + 0 + + + 0 + + + + + send raw data to board + + + + + + + + 75 + true + + + + + + + use values from simulator + + + true + + + + + + + + + + calculate from AttitudeRaw + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + Other data + + + + 3 + + + 3 + + + 3 + + + 3 + + + 0 + + + + + HomeLocation + + + true + + + true + + + false + + + + 3 + + + 3 + + + 0 + + + 0 + + + + + Refresh rate + + + + + + + 0 - update once, or every N seconds + + + sec + + + 10 + + + + + + + + + + GPSPosition + + + true + + + true + + + false + + + + 3 + + + 3 + + + 0 + + + 0 + + + + + Refresh rate + + + + + + + ms + + + 100 + + + 2000 + + + 500 + + + + + + + + + + SonarAltitude + + + true + + + true + + + false + + + + 3 + + + 6 + + + 3 + + + 0 + + + 0 + + + + + + + Range detectioon + + + + + + + m + + + 1 + + + 10 + + + 5 + + + + + + + Refresh rate + + + + + + + ms + + + 20 + + + 2000 + + + 10 + + + 50 + + + + + + + + + + + + Map command from simulator + + + true + + + true + + + false + + + + 3 + + + 3 + + + 0 + + + 0 + + + + + + 75 + true + + + + to GCSReciver + + + true + + + + + + + false + + + to ManualCtrll (not implemented) + + + + + + + + + + 6 + + + + + Maximum output rate + + + + + + + ms + + + 10 + + + 100 + + + 5 + + + 15 + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + Utils::PathChooser + QWidget +
utils/pathchooser.h
+ 1 +
+
+ + chooseFlightSimulator + hostAddress + inputPort + remoteAddress + outputPort + + + +
diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremeplugin.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.cpp similarity index 60% rename from ground/openpilotgcs/src/plugins/pipxtreme/pipxtremeplugin.cpp rename to ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.cpp index 3f8422a7e..f0ee2d07a 100644 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremeplugin.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.cpp @@ -1,12 +1,13 @@ - /** ****************************************************************************** * - * @file pipxtremeplugin.cpp + * @file mapplugin.cpp * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ + * @addtogroup HITLPlugin HITL Plugin * @{ + * @brief The Hardware In The Loop plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -23,39 +24,47 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ - -#include "pipxtremeplugin.h" -#include "pipxtremegadgetfactory.h" +#include "hitlv2plugin.h" +#include "hitlv2factory.h" #include #include #include -PipXtremePlugin::PipXtremePlugin() +#include "aerosimrc.h" + +QList HITLPlugin::typeSimulators; + +HITLPlugin::HITLPlugin() { - mf = NULL; + // Do nothing } -PipXtremePlugin::~PipXtremePlugin() +HITLPlugin::~HITLPlugin() { + // Do nothing } -bool PipXtremePlugin::initialize(const QStringList &args, QString *errMsg) +bool HITLPlugin::initialize(const QStringList& args, QString *errMsg) { - Q_UNUSED(args); - Q_UNUSED(errMsg); + Q_UNUSED(args); + Q_UNUSED(errMsg); + mf = new HITLFactory(this); - mf = new PipXtremeGadgetFactory(this); - addAutoReleasedObject(mf); + addAutoReleasedObject(mf); - return true; + addSimulator(new AeroSimRCSimulatorCreator("ASimRC", "AeroSimRC")); + + return true; } -void PipXtremePlugin::extensionsInitialized() +void HITLPlugin::extensionsInitialized() { + // Do nothing } -void PipXtremePlugin::shutdown() +void HITLPlugin::shutdown() { + // Do nothing } +Q_EXPORT_PLUGIN(HITLPlugin) -Q_EXPORT_PLUGIN(PipXtremePlugin) diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremeplugin.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.h similarity index 53% rename from ground/openpilotgcs/src/plugins/pipxtreme/pipxtremeplugin.h rename to ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.h index f81ef1933..e68129bd4 100644 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremeplugin.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.h @@ -1,11 +1,13 @@ /** ****************************************************************************** * - * @file pipxtremeplugin.h + * @file browserplugin.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ + * @addtogroup HITLPlugin HITL Plugin * @{ + * @brief The Hardware In The Loop plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -23,26 +25,43 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef PIPXTREMEPLUGIN_H -#define PIPXTREMEPLUGIN_H +#ifndef HITLV2PLUGIN_H +#define HITLV2PLUGIN_H #include +#include -class PipXtremeGadgetFactory; +#include -class PipXtremePlugin : public ExtensionSystem::IPlugin +class HITLFactory; + +class HITLPlugin : public ExtensionSystem::IPlugin { public: - PipXtremePlugin(); - ~PipXtremePlugin(); + HITLPlugin(); + ~HITLPlugin(); - void extensionsInitialized(); - bool initialize(const QStringList & arguments, QString * errorString); - void shutdown(); + void extensionsInitialized(); + bool initialize(const QStringList & arguments, QString * errorString); + void shutdown(); + + static void addSimulator(SimulatorCreator* creator) + { + HITLPlugin::typeSimulators.append(creator); + } + + static SimulatorCreator* getSimulatorCreator(const QString classId) + { + foreach(SimulatorCreator* creator, HITLPlugin::typeSimulators) { + if(classId == creator->ClassId()) + return creator; + } + return 0; + } + + static QList typeSimulators; private: - PipXtremeGadgetFactory *mf; - + HITLFactory *mf; }; - -#endif +#endif /* HITLV2PLUGIN_H */ diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.cpp new file mode 100644 index 000000000..55d14f735 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.cpp @@ -0,0 +1,187 @@ +/** + ****************************************************************************** + * + * @file hitlwidget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITL Plugin + * @{ + * @brief The Hardware In The Loop plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "hitlv2widget.h" +#include "ui_hitlv2widget.h" +#include +#include +#include +#include +#include + +#include "hitlv2plugin.h" +#include "simulatorv2.h" +#include "uavobjectmanager.h" +#include +#include + +QStringList Simulator::instances; + +HITLWidget::HITLWidget(QWidget *parent) + : QWidget(parent), + simulator(0) +{ + widget = new Ui_HITLWidget(); + widget->setupUi(this); + widget->startButton->setEnabled(true); + widget->stopButton->setEnabled(false); + + strAutopilotDisconnected = " AP OFF "; + strSimulatorDisconnected = " Sim OFF "; + strAutopilotConnected = " AP ON "; +// strSimulatorConnected = " Sim ON "; + strStyleEnable = "QFrame{background-color: green; color: white}"; + strStyleDisable = "QFrame{background-color: red; color: grey}"; + + widget->apLabel->setText(strAutopilotDisconnected); + widget->simLabel->setText(strSimulatorDisconnected); + + connect(widget->startButton, SIGNAL(clicked()), this, SLOT(startButtonClicked())); + connect(widget->stopButton, SIGNAL(clicked()), this, SLOT(stopButtonClicked())); + connect(widget->buttonClearLog, SIGNAL(clicked()), this, SLOT(buttonClearLogClicked())); +} + +HITLWidget::~HITLWidget() +{ + delete widget; +} + +void HITLWidget::startButtonClicked() +{ + // allow only one instance per simulator + if (Simulator::Instances().indexOf(settings.simulatorId) != -1) { + widget->textBrowser->append(settings.simulatorId + " alreary started!"); + return; + } + + if (!HITLPlugin::typeSimulators.size()) { + widget->textBrowser->append("There is no registered simulators, add through HITLPlugin::addSimulator"); + return; + } + + // Stop running process if one is active + if (simulator) { + QMetaObject::invokeMethod(simulator, "onDeleteSimulator", Qt::QueuedConnection); + simulator = NULL; + } + + if (settings.hostAddress == "" || settings.inPort == 0) { + widget->textBrowser->append("Before start, set UDP parameters in options page!"); + return; + } + + SimulatorCreator* creator = HITLPlugin::getSimulatorCreator(settings.simulatorId); + simulator = creator->createSimulator(settings); + simulator->setName(creator->Description()); + simulator->setSimulatorId(creator->ClassId()); + + connect(simulator, SIGNAL(processOutput(QString)), this, SLOT(onProcessOutput(QString))); + + // Setup process + onProcessOutput(QString("[%1] Starting %2... ") + .arg(QTime::currentTime().toString("hh:mm:ss")) + .arg(creator->Description())); + + // Start bridge + bool ret = QMetaObject::invokeMethod(simulator, "setupProcess", Qt::QueuedConnection); + if (ret) { + Simulator::setInstance(settings.simulatorId); + + connect(this, SIGNAL(deleteSimulator()), simulator, SLOT(onDeleteSimulator()), Qt::QueuedConnection); + + widget->startButton->setEnabled(false); + widget->stopButton->setEnabled(true); + + connect(simulator, SIGNAL(autopilotConnected()), this, SLOT(onAutopilotConnect()), Qt::QueuedConnection); + connect(simulator, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect()), Qt::QueuedConnection); + connect(simulator, SIGNAL(simulatorConnected()), this, SLOT(onSimulatorConnect()), Qt::QueuedConnection); + connect(simulator, SIGNAL(simulatorDisconnected()), this, SLOT(onSimulatorDisconnect()), Qt::QueuedConnection); + + // Initialize connection status + if (simulator->isAutopilotConnected()) + onAutopilotConnect(); + else + onAutopilotDisconnect(); + + if (simulator->isSimulatorConnected()) + onSimulatorConnect(); + else + onSimulatorDisconnect(); + } +} + +void HITLWidget::stopButtonClicked() +{ + if (simulator) + widget->textBrowser->append(QString("[%1] Terminate %2 ") + .arg(QTime::currentTime().toString("hh:mm:ss")) + .arg(simulator->Name())); + + widget->startButton->setEnabled(true); + widget->stopButton->setEnabled(false); + widget->apLabel->setStyleSheet(QString::fromUtf8("QFrame{background-color: transparent; color: white}")); + widget->simLabel->setStyleSheet(QString::fromUtf8("QFrame{background-color: transparent; color: white}")); + widget->apLabel->setText(strAutopilotDisconnected); + widget->simLabel->setText(strSimulatorDisconnected); + if (simulator) { + QMetaObject::invokeMethod(simulator, "onDeleteSimulator", Qt::QueuedConnection); + simulator = NULL; + } +} + +void HITLWidget::buttonClearLogClicked() +{ + widget->textBrowser->clear(); +} + +void HITLWidget::onProcessOutput(QString text) +{ + widget->textBrowser->append(text); +} + +void HITLWidget::onAutopilotConnect() +{ + widget->apLabel->setStyleSheet(strStyleEnable); + widget->apLabel->setText(strAutopilotConnected); +} + +void HITLWidget::onAutopilotDisconnect() +{ + widget->apLabel->setStyleSheet(strStyleDisable); + widget->apLabel->setText(strAutopilotDisconnected); +} + +void HITLWidget::onSimulatorConnect() +{ + widget->simLabel->setStyleSheet(strStyleEnable); + widget->simLabel->setText(" " + simulator->Name() + " ON "); +} + +void HITLWidget::onSimulatorDisconnect() +{ + widget->simLabel->setStyleSheet(strStyleDisable); + widget->simLabel->setText(" " + simulator->Name() + " OFF "); +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.h new file mode 100644 index 000000000..78f3e9405 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.h @@ -0,0 +1,72 @@ +/** + ****************************************************************************** + * + * @file hitlwidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITL Plugin + * @{ + * @brief The Hardware In The Loop plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef HITLV2WIDGET_H +#define HITLV2WIDGET_H + +#include +#include +#include "simulatorv2.h" + +class Ui_HITLWidget; + +class HITLWidget : public QWidget +{ + Q_OBJECT + +public: + HITLWidget(QWidget *parent = 0); + ~HITLWidget(); + + void setSettingParameters(const SimulatorSettings& params) { settings = params; } + +signals: + void deleteSimulator(); + +private slots: + void startButtonClicked(); + void stopButtonClicked(); + void buttonClearLogClicked(); + void onProcessOutput(QString text); + void onAutopilotConnect(); + void onAutopilotDisconnect(); + void onSimulatorConnect(); + void onSimulatorDisconnect(); + +private: + Ui_HITLWidget* widget; + Simulator* simulator; + SimulatorSettings settings; + + QString strAutopilotDisconnected; + QString strSimulatorDisconnected; + QString strAutopilotConnected; +// QString strSimulatorConnected; + QString strStyleEnable; + QString strStyleDisable; +}; +#endif /* HITLV2WIDGET_H */ diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.ui b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.ui new file mode 100644 index 000000000..48d2c2db2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.ui @@ -0,0 +1,314 @@ + + + HITLWidget + + + + 0 + 0 + 477 + 300 + + + + + 0 + 0 + + + + Form + + + + +QScrollBar:vertical { + border: 1px solid grey; + background: grey; + margin: 22px 0 22px 0; + } + +QScrollBar:vertical:disabled { + border: 1px solid grey; + + background-color: grey; + margin: 22px 0 22px 0; + } + + QScrollBar::handle:vertical { +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(120, 120, 255, 255), stop:1 rgba(80, 80, 160, 255)); + min-height: 20px; + } + +QScrollBar::handle:vertical:disabled{ +background-color: grey; + min-height: 20px; + } + + + QScrollBar::handle:vertical:pressed { + + background-color: rgb(85, 85, 255); +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(170, 170, 255, 255), stop:1 rgba(80, 80, 160, 255)); + + min-height: 20px; + } + + QScrollBar::add-line:vertical { + border: 1px solid black; +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255)); + height: 20px; + subcontrol-position: bottom; + subcontrol-origin: margin; + } + + QScrollBar::add-line:vertical:disabled { +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(100, 100, 100, 255)); + border: 1px solid grey; + + } + + QScrollBar::sub-line:vertical:disabled { +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(100, 100, 100, 255)); + border: 1px solid grey; + + } + + QScrollBar::add-line:vertical:pressed { +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200)); + } + + QScrollBar::sub-line:vertical:pressed { +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200)); + } + + QScrollBar::sub-line:vertical { + border: 1px solid black; +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255)); + height: 20px; + subcontrol-position: top; + subcontrol-origin: margin; + } + QScrollBar::down-arrow:vertical { + + image: url(:/hitlnew/images/arrow-down2.png); + } + + QScrollBar::up-arrow:vertical { + image: url(:/hitlnew/images/arrow-up2.png); + } + + QScrollBar::add-page:vertical, QScrollBar::sub-page:vertical { + background: none; + } + + +QPushButton { +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(110, 110, 110, 255), stop:1 rgba(71, 71, 71, 255)); + + color: rgb(255, 255, 255); +border: 1px solid black; +width: 66px; +height: 20px; +} + +QPushButton:disabled { +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(120, 120, 120, 255)); + color: rgb(194, 194, 194); +border: 1px solid gray; +width: 66px; +height: 20px; +} + +QPushButton:hover { +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200)); +color: rgb(255, 255, 255); +border: 0px; +} +QPushButton:pressed { +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255)); +color: rgb(255, 255, 255); +border: 0px; +} + +QPushButton:checked { +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255)); +color: rgb(255, 255, 255); +border: 0px; +} + + + + 0 + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + +QFrame{ +background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(110, 110, 110, 255), stop:1 rgba(71, 71, 71, 255)); +color: rgba(0, 0, 0, 128); +} + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + QLayout::SetMaximumSize + + + + + QLayout::SetDefaultConstraint + + + + + Request update + + + + + + Start + + + + + + + false + + + Send update + + + Stop + + + + + + + + 0 + 22 + + + + + 50 + false + + + + Qt::LeftToRight + + + false + + + color: rgb(255, 255, 255); + + + AP OFF + + + Qt::AlignCenter + + + + + + + + 0 + 22 + + + + color: rgb(255, 255, 255); + + + Sim OFF + + + Qt::AlignCenter + + + + + + + Clear Log + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + false + + + QTextEdit { + background-color: white; + color: rgb(0, 0, 0); +} + + + QFrame::NoFrame + + + QFrame::Plain + + + Qt::ScrollBarAlwaysOn + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.cpp b/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.cpp new file mode 100644 index 000000000..c4c698689 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.cpp @@ -0,0 +1,341 @@ +/** + ****************************************************************************** + * + * @file simulator.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITL Plugin + * @{ + * @brief The Hardware In The Loop plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "simulatorv2.h" +#include +#include +#include + +volatile bool Simulator::isStarted = false; + +const float Simulator::GEE = 9.81; +const float Simulator::FT2M = 0.3048; +const float Simulator::KT2MPS = 0.514444444; +const float Simulator::INHG2KPA = 3.386; +const float Simulator::FPS2CMPS = 30.48; +const float Simulator::DEG2RAD = (M_PI/180.0); +const float Simulator::RAD2DEG = (180.0/M_PI); + + +Simulator::Simulator(const SimulatorSettings& params) : + inSocket(NULL), + outSocket(NULL), + settings(params), + updatePeriod(50), + simTimeout(2000), + autopilotConnectionStatus(false), + simConnectionStatus(false), + txTimer(NULL), + simTimer(NULL), + name("") +{ + // move to thread + moveToThread(Core::ICore::instance()->threadManager()->getRealTimeThread()); + connect(this, SIGNAL(myStart()), this, SLOT(onStart()), Qt::QueuedConnection); + emit myStart(); +} + +Simulator::~Simulator() +{ +// qDebug() << "Simulator::~Simulator"; + if (inSocket) { + delete inSocket; + inSocket = NULL; + } + if (outSocket) { + delete outSocket; + outSocket = NULL; + } + if (txTimer) { + delete txTimer; + txTimer = NULL; + } + if (simTimer) { + delete simTimer; + simTimer = NULL; + } +} + +void Simulator::onDeleteSimulator(void) +{ +// qDebug() << "Simulator::onDeleteSimulator"; + resetAllObjects(); + + Simulator::setStarted(false); + Simulator::Instances().removeOne(simulatorId); + + disconnect(this); + delete this; +} + +void Simulator::onStart() +{ +// qDebug() << "Simulator::onStart"; + QMutexLocker locker(&lock); + + // Get required UAVObjects + ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager* objManager = pm->getObject(); + +// actDesired = ActuatorDesired::GetInstance(objManager); +// manCtrlCommand = ManualControlCommand::GetInstance(objManager); +// velActual = VelocityActual::GetInstance(objManager); +// posActual = PositionActual::GetInstance(objManager); +// altActual = BaroAltitude::GetInstance(objManager); +// camDesired = CameraDesired::GetInstance(objManager); +// acsDesired = AccessoryDesired::GetInstance(objManager); + posHome = HomeLocation::GetInstance(objManager); + accels = Accels::GetInstance(objManager); + gyros = Gyros::GetInstance(objManager); + attActual = AttitudeActual::GetInstance(objManager); + gpsPosition = GPSPosition::GetInstance(objManager); + flightStatus = FlightStatus::GetInstance(objManager); + gcsReceiver = GCSReceiver::GetInstance(objManager); + actCommand = ActuatorCommand::GetInstance(objManager); + attSettings = AttitudeSettings::GetInstance(objManager); + sonarAlt = SonarAltitude::GetInstance(objManager); + + telStats = GCSTelemetryStats::GetInstance(objManager); + + // Listen to autopilot connection events + TelemetryManager* telMngr = pm->getObject(); + connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect())); + connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); + + // If already connect setup autopilot + GCSTelemetryStats::DataFields stats = telStats->getData(); + if (stats.Status == GCSTelemetryStats::STATUS_CONNECTED) + onAutopilotConnect(); + + emit processOutput("Local interface: " + settings.hostAddress + ":" + \ + QString::number(settings.inPort) + "\n" + \ + "Remote interface: " + settings.remoteAddress + ":" + \ + QString::number(settings.outPort) + "\n"); + + inSocket = new QUdpSocket(); + outSocket = new QUdpSocket(); + setupUdpPorts(settings.hostAddress, settings.inPort, settings.outPort); + + connect(inSocket, SIGNAL(readyRead()), this, SLOT(receiveUpdate())/*, Qt::DirectConnection*/); + + // Setup transmit timer + if (settings.manualOutput) { + txTimer = new QTimer(); + connect(txTimer, SIGNAL(timeout()), this, SLOT(transmitUpdate())/*, Qt::DirectConnection*/); + txTimer->setInterval(settings.outputRate); + txTimer->start(); + } + + // Setup simulator connection timer + simTimer = new QTimer(); + connect(simTimer, SIGNAL(timeout()), this, SLOT(onSimulatorConnectionTimeout())/*, Qt::DirectConnection*/); + simTimer->setInterval(simTimeout); + simTimer->start(); + +#ifdef DBG_TIMERS + timeRX = QTime(); + timeRX.start(); + timeTX = QTime(); + timeTX.start(); +#endif + + setupObjects(); +} + +void Simulator::receiveUpdate() +{ + // Update connection timer and status + simTimer->start(); + if (!simConnectionStatus) { + simConnectionStatus = true; + emit simulatorConnected(); + } + + // Process data + while (inSocket->hasPendingDatagrams()) { + // Receive datagram + QByteArray datagram; + datagram.resize(inSocket->pendingDatagramSize()); + QHostAddress sender; + quint16 senderPort; + inSocket->readDatagram(datagram.data(), datagram.size(), &sender, &senderPort); + // Process incomming data + processUpdate(datagram); + } + if (!settings.manualOutput) + transmitUpdate(); +} + +void Simulator::setupObjects() +{ + if (settings.gcsReciever) { + setupInputObject(actCommand, settings.outputRate); + setupOutputObject(gcsReceiver); + } else if (settings.manualControl) { +// setupInputObject(actDesired); +// setupInputObject(camDesired); +// setupInputObject(acsDesired); +// setupOutputObject(manCtrlCommand); + qDebug() << "ManualControlCommand not implemented yet"; + } + + if (settings.homeLocation) + setupOutputObject(posHome); + + if (settings.sonarAltitude) + setupOutputObject(sonarAlt); + + if (settings.gpsPosition) + setupOutputObject(gpsPosition); + + if (settings.attRaw || settings.attActual) { + setupOutputObject(accels); + setupOutputObject(gyros); + } + + if (settings.attActual && !settings.attActHW) + setupOutputObject(attActual); + else + setupWatchedObject(attActual); +} + +void Simulator::resetAllObjects() +{ + setupDefaultObject(posHome); + setupDefaultObject(accels); + setupDefaultObject(gyros); + setupDefaultObject(attActual); + setupDefaultObject(gpsPosition); + setupDefaultObject(gcsReceiver); + setupDefaultObject(actCommand); + setupDefaultObject(sonarAlt); +// setupDefaultObject(manCtrlCommand); +// setupDefaultObject(actDesired); +// setupDefaultObject(camDesired); +// setupDefaultObject(acsDesired); +// setupDefaultObject(altActual); +// setupDefaultObject(posActual); +// setupDefaultObject(velActual); +} + +void Simulator::setupInputObject(UAVObject* obj, quint32 updateRate) +{ + UAVObject::Metadata mdata; + mdata = obj->getDefaultMetadata(); + + UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READONLY); + UAVObject::SetGcsTelemetryAcked(mdata, false); + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL); + mdata.gcsTelemetryUpdatePeriod = 0; + + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE); + UAVObject::SetFlightTelemetryAcked(mdata, false); + + if (settings.manualOutput) { + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = updateRate; + } else { + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE); + mdata.flightTelemetryUpdatePeriod = 0; + } + + obj->setMetadata(mdata); +} + +void Simulator::setupWatchedObject(UAVObject *obj) +{ + UAVObject::Metadata mdata; + mdata = obj->getDefaultMetadata(); + + UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READONLY); + UAVObject::SetGcsTelemetryAcked(mdata, false); + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL); + mdata.gcsTelemetryUpdatePeriod = 0; + + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE); + UAVObject::SetFlightTelemetryAcked(mdata, false); + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = 100; + + obj->setMetadata(mdata); +} + +void Simulator::setupOutputObject(UAVObject* obj) +{ + UAVObject::Metadata mdata; + mdata = obj->getDefaultMetadata(); + + UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READWRITE); + UAVObject::SetGcsTelemetryAcked(mdata, false); + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE); + mdata.gcsTelemetryUpdatePeriod = 0; + + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY); + UAVObject::SetFlightTelemetryAcked(mdata, false); + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL); + mdata.flightTelemetryUpdatePeriod = 0; + + obj->setMetadata(mdata); +} + +void Simulator::setupDefaultObject(UAVObject *obj) +{ + UAVObject::Metadata mdata; + mdata = obj->getDefaultMetadata(); + + obj->setMetadata(mdata); +} + +void Simulator::onAutopilotConnect() +{ + autopilotConnectionStatus = true; + emit autopilotConnected(); +} + +void Simulator::onAutopilotDisconnect() +{ + autopilotConnectionStatus = false; + emit autopilotDisconnected(); +} + +void Simulator::onSimulatorConnectionTimeout() +{ + if (simConnectionStatus) { + simConnectionStatus = false; + emit simulatorDisconnected(); + } +} + +void Simulator::telStatsUpdated(UAVObject* obj) +{ + GCSTelemetryStats::DataFields stats = telStats->getData(); + if (!autopilotConnectionStatus && stats.Status == GCSTelemetryStats::STATUS_CONNECTED) + onAutopilotConnect(); + else if (autopilotConnectionStatus && stats.Status != GCSTelemetryStats::STATUS_CONNECTED) + onAutopilotDisconnect(); +} + diff --git a/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.h b/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.h new file mode 100644 index 000000000..6a0a9f008 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.h @@ -0,0 +1,222 @@ +/** + ****************************************************************************** + * + * @file simulator.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITL Plugin + * @{ + * @brief The Hardware In The Loop plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef ISIMULATORV2_H +#define ISIMULATORV2_H + +#include +#include +#include +#include +#include +#include +#include "uavtalk/telemetrymanager.h" +#include "uavobjectmanager.h" +#include "homelocation.h" +#include "accels.h" +#include "gyros.h" +#include "attitudeactual.h" +#include "gpsposition.h" +#include "flightstatus.h" +#include "gcsreceiver.h" +#include "actuatorcommand.h" +#include "gcstelemetrystats.h" +#include "attitudesettings.h" +#include "sonaraltitude.h" + +//#define DBG_TIMERS +#undef DBG_TIMERS + +/** + * just imagine this was a class without methods and all public properties + */ + +typedef struct _CONNECTION +{ + QString simulatorId; + QString hostAddress; + int inPort; + QString remoteAddress; + int outPort; + QString binPath; + QString dataPath; + + bool homeLocation; + quint16 homeLocRate; + + bool attRaw; + quint8 attRawRate; + + bool attActual; + bool attActHW; + bool attActSim; + bool attActCalc; + + bool sonarAltitude; + float sonarMaxAlt; + quint16 sonarAltRate; + + bool gpsPosition; + quint16 gpsPosRate; + + bool inputCommand; + bool gcsReciever; + bool manualControl; + bool manualOutput; + quint8 outputRate; + +} SimulatorSettings; + +class Simulator : public QObject +{ + Q_OBJECT + +public: + Simulator(const SimulatorSettings& params); + virtual ~Simulator(); + + bool isAutopilotConnected() const { return autopilotConnectionStatus; } + bool isSimulatorConnected() const { return simConnectionStatus; } + + QString Name() const { return name; } + void setName(QString str) { name = str; } + + QString SimulatorId() const { return simulatorId; } + void setSimulatorId(QString str) { simulatorId = str; } + + static bool IsStarted() { return isStarted; } + static void setStarted(bool val) { isStarted = val; } + + static QStringList& Instances() { return Simulator::instances; } + static void setInstance(const QString& str) { Simulator::instances.append(str); } + + virtual void stopProcess() {} + virtual void setupUdpPorts(const QString& host, int inPort, int outPort) { Q_UNUSED(host) Q_UNUSED(inPort) Q_UNUSED(outPort)} + +signals: + void processOutput(QString str); + void autopilotConnected(); + void autopilotDisconnected(); + void simulatorConnected(); + void simulatorDisconnected(); + void myStart(); + +public slots: + Q_INVOKABLE virtual bool setupProcess() { return true; } + +private slots: + void onStart(); + void receiveUpdate(); + void onAutopilotConnect(); + void onAutopilotDisconnect(); + void onSimulatorConnectionTimeout(); + void telStatsUpdated(UAVObject* obj); + Q_INVOKABLE void onDeleteSimulator(void); + + virtual void transmitUpdate() = 0; + virtual void processUpdate(const QByteArray& data) = 0; + +protected: + static const float GEE; + static const float FT2M; + static const float KT2MPS; + static const float INHG2KPA; + static const float FPS2CMPS; + static const float DEG2RAD; + static const float RAD2DEG; + +#ifdef DBG_TIMERS + QTime timeRX; + QTime timeTX; +#endif + + QUdpSocket* inSocket; + QUdpSocket* outSocket; + +// ActuatorDesired* actDesired; +// ManualControlCommand* manCtrlCommand; +// VelocityActual* velActual; +// PositionActual* posActual; +// BaroAltitude* altActual; +// CameraDesired *camDesired; +// AccessoryDesired *acsDesired; + Accels *accels; + Gyros *gyros; + AttitudeActual *attActual; + HomeLocation *posHome; + FlightStatus *flightStatus; + GPSPosition *gpsPosition; + GCSReceiver *gcsReceiver; + ActuatorCommand *actCommand; + AttitudeSettings *attSettings; + SonarAltitude *sonarAlt; + + GCSTelemetryStats* telStats; + SimulatorSettings settings; + + QMutex lock; + +private: + int updatePeriod; + int simTimeout; + volatile bool autopilotConnectionStatus; + volatile bool simConnectionStatus; + QTimer* txTimer; + QTimer* simTimer; + QString name; + QString simulatorId; + volatile static bool isStarted; + static QStringList instances; + + void setupObjects(); + void resetAllObjects(); + void setupInputObject(UAVObject* obj, quint32 updateRate); + void setupOutputObject(UAVObject* obj); + void setupWatchedObject(UAVObject *obj); + void setupDefaultObject(UAVObject *obj); +}; + +class SimulatorCreator +{ +public: + SimulatorCreator(QString id, QString descr) : + classId(id), + description(descr) + {} + virtual ~SimulatorCreator() {} + + QString ClassId() const { return classId; } + QString Description() const { return description; } + + virtual Simulator* createSimulator(const SimulatorSettings& params) = 0; + +private: + QString classId; + QString description; +}; + +#endif // ISIMULATORV2_H diff --git a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp index fa8ff053f..38df0eb52 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp @@ -256,7 +256,10 @@ void NotifyPluginOptionsPage::addDynamicField(UAVObjectField* objField) _dynamicFieldCondition->removeItem(smaller); _dynamicFieldCondition->removeItem(bigger); } - _dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(_selectedNotification->getCondition()))); + int cond=_selectedNotification->getCondition(); + if(cond<0) + return; + _dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(cond))); connect(_dynamicFieldCondition, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_changedIndex_rangeValue(QString))); @@ -434,8 +437,10 @@ void NotifyPluginOptionsPage::updateConfigView(NotificationItem* notification) _optionsPage->SoundCollectionList->setCurrentIndex(_optionsPage->SoundCollectionList->findText("default")); _optionsPage->Sound3->setCurrentIndex(_optionsPage->Sound3->findText(notification->getSound3())); } - - _dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(notification->getCondition()))); + int cond=notification->getCondition(); + if(cond<0) + return; + _dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(cond))); _sayOrder->setCurrentIndex(notification->getSayOrder()); diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp index 072c54be3..7fedb99ab 100644 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp @@ -304,7 +304,7 @@ void PFDGadgetWidget::updateAirspeed(UAVObject *object) { UAVObjectField* eastField = object->getField("East"); if (northField && eastField) { double val = floor(sqrt(pow(northField->getDouble(),2) + pow(eastField->getDouble(),2))*10)/10; - groundspeedTarget = 3.6*val*speedScaleHeight/3000; + groundspeedTarget = 3.6*val*speedScaleHeight/30; if (!dialTimer.isActive()) dialTimer.start(); // Rearm the dial Timer which might be stopped. @@ -321,7 +321,7 @@ void PFDGadgetWidget::updateAltitude(UAVObject *object) { UAVObjectField* downField = object->getField("Down"); if (downField) { // The altitude scale represents 30 meters - altitudeTarget = -floor(downField->getDouble()*10)/10*altitudeScaleHeight/3000; + altitudeTarget = -floor(downField->getDouble()*10)/10*altitudeScaleHeight/30; if (!dialTimer.isActive()) dialTimer.start(); // Rearm the dial Timer which might be stopped. diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/images/view-refresh.svg b/ground/openpilotgcs/src/plugins/pipxtreme/images/view-refresh.svg deleted file mode 100644 index 3d0cc562d..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/images/view-refresh.svg +++ /dev/null @@ -1,230 +0,0 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.pro b/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.pro deleted file mode 100644 index cd3d2f230..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.pro +++ /dev/null @@ -1,38 +0,0 @@ -TEMPLATE = lib -TARGET = PipXtreme - -QT += svg -QT += opengl - -include(../../openpilotgcsplugin.pri) -include(../../plugins/coreplugin/coreplugin.pri) -include(../../plugins/uavobjects/uavobjects.pri) -include(../../plugins/uavtalk/uavtalk.pri) -include(../../plugins/rawhid/rawhid.pri) - -INCLUDEPATH += ../../libs/qextserialport/src - -HEADERS += pipxtremegadget.h \ - pipxtremegadgetconfiguration.h \ - pipxtremegadgetfactory.h \ - pipxtremegadgetoptionspage.h \ - pipxtremegadgetwidget.h \ - pipxtremeplugin.h \ - widgetbar.h - -SOURCES += pipxtremegadget.cpp \ - pipxtremegadgetconfiguration.cpp \ - pipxtremegadgetfactory.cpp \ - pipxtremegadgetoptionspage.cpp \ - pipxtremegadgetwidget.cpp \ - pipxtremeplugin.cpp \ - widgetbar.cpp - -OTHER_FILES += pipxtreme.pluginspec - -FORMS += \ - pipxtreme.ui \ - pipxtremegadgetoptionspage.ui - -RESOURCES += \ - pipxtreme.qrc diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.qrc b/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.qrc deleted file mode 100644 index d397a930b..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.qrc +++ /dev/null @@ -1,5 +0,0 @@ - - - images/view-refresh.svg - - diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.ui b/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.ui deleted file mode 100644 index d5547494d..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtreme.ui +++ /dev/null @@ -1,1026 +0,0 @@ - - - PipXtremeWidget - - - - 0 - 0 - 571 - 527 - - - - Form - - - - - - - - - 100 - 0 - - - - The PC port serial baud rate - - - - - - - - 200 - 0 - - - - Set the PC port the modem is connected too - - - - - - - true - - - true - - - Connect to the modem (when normal telemetry is not used) - - - Connect - - - - - - - Refresh the list of serial and USB ports available - - - ... - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Serial Baudrate - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - Qt::Horizontal - - - - - - - - - Serial Number (hex) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - 75 - false - true - - - - false - - - The modems serial number - - - QLineEdit { - border: none; - border-radius: 1px; - padding: 0 8px; - background: rgba(0, 0, 0, 16); -/* background: transparent; */ -/* selection-background-color: darkgray;*/ -} - - - true - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - true - - - - - - - Frequency Band - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - 75 - true - - - - The modems frequency band - - - QLineEdit { - border: none; - border-radius: 1px; - padding: 0 8px; - background: rgba(0, 0, 0, 16); -/* background: transparent; */ -/* selection-background-color: darkgray;*/ -} - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - true - - - - - - - Min Frequency - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - 75 - true - - - - The modems minimum allowed frequency - - - QLineEdit { - border: none; - border-radius: 1px; - padding: 0 8px; - background: rgba(0, 0, 0, 16); -/* background: transparent; */ -/* selection-background-color: darkgray;*/ -} - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - true - - - - - - - Max Frequency - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - 75 - true - - - - The modems maximum allowed frequency - - - QLineEdit { - border: none; - border-radius: 1px; - padding: 0 8px; - background: rgba(0, 0, 0, 16); -/* background: transparent; */ -/* selection-background-color: darkgray;*/ -} - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - true - - - - - - - Frequency Step Size - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - 75 - true - - - - The modems minimum frequency step size - - - QLineEdit { - border: none; - border-radius: 1px; - padding: 0 8px; - background: rgba(0, 0, 0, 16); -/* background: transparent; */ -/* selection-background-color: darkgray;*/ -} - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - true - - - - - - - Link State - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - 75 - true - - - - The modems current state - - - QLineEdit { - border: none; - border-radius: 1px; - padding: 0 8px; - background: rgba(0, 0, 0, 16); -/* background: transparent; */ -/* selection-background-color: darkgray;*/ -} - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - true - - - - - - - RSSI - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 1 - 1 - - - - false - - - false - - - background-color: rgb(112, 112, 112); - - - - - - - Rx AFC - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 75 - true - - - - QLineEdit { - border: none; - border-radius: 1px; - padding: 0 8px; - background: rgba(0, 0, 0, 16); -/* background: transparent; */ -/* selection-background-color: darkgray;*/ -} - - - true - - - - - - - Firmware Version - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 75 - true - - - - QLineEdit { - border: none; - border-radius: 1px; - padding: 0 8px; - background: rgba(0, 0, 0, 16); -/* background: transparent; */ -/* selection-background-color: darkgray;*/ -} - - - false - - - true - - - - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Calibrate the modems RF carrier frequency - - - true - - - 255 - - - - - - - Frequency Calibration - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Set the modems RF carrier frequency - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - true - - - 8 - - - 0.000000000000000 - - - 1000.000000000000000 - - - 0.000001000000000 - - - - - - - Frequency (MHz) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 16777215 - 16777215 - - - - Set the maximum RF datarate/channel bandwidth the modem will use - - - - - - - Max RF Datarate (bits/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 16777215 - 16777215 - - - - Set the maximum TX output power the modem will use - - - Qt::LeftToRight - - - 0 - - - - - - - Max RF Tx Power - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 16777215 - 16777215 - - - - Set the modems serial port speed - - - - - - - Serial Port Speed - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Mode - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - true - - - - 16777215 - 16777215 - - - - Set the modems operating mode - - - - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Serial number of the remote modem you want to pair with - - - - - - 8 - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - - Paired Serial Number (hex) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Retries - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 75 - true - - - - QLineEdit { - border: none; - border-radius: 1px; - padding: 0 8px; - background: rgba(0, 0, 0, 16); -/* background: transparent; */ -/* selection-background-color: darkgray;*/ -} - - - false - - - true - - - - - - - RTS time (ms) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Ready-To-Send time is the maximum time the modem waits for more data before sending it. This is to try and make the RF link a little more efficient by creating larger packets. - - - 100 - - - - - - - - - - - AES Encryption Key - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - Courier New - 9 - - - - The AES encryption key - has to be the same key on the remote modem. - - - - - - 32 - - - true - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - Radomise the AES encryption key - - - Rand - - - - - - - Enable/Disable AES encryption - - - Qt::RightToLeft - - - AES Enable - - - - - - - - - Qt::Horizontal - - - - - - - - - true - - - Restore the settings from a file - - - Import - - - - - - - true - - - Save the settings into a file - - - Export - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Click to save your new settings into PipX flash - - - - - - Save to flash - - - - - - - - - Qt::Horizontal - - - - - - - TextLabel - - - - - - - - - Scan whole band to see where their is interference and/or used channels - - - Scan Spectrum - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - true - - - - - - - - - - WidgetBar - QWidget -
widgetbar.h
-
-
- - -
diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetconfiguration.cpp deleted file mode 100644 index c59d49ea6..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetconfiguration.cpp +++ /dev/null @@ -1,66 +0,0 @@ -/** - ****************************************************************************** - * - * @file pipxtremegadgetconfiguration.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @{ - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pipxtremegadgetconfiguration.h" -#include - -/** - * Loads a saved configuration or defaults if non exist. - * - */ -PipXtremeGadgetConfiguration::PipXtremeGadgetConfiguration(QString classId, QSettings* qSettings, QObject *parent) : - IUAVGadgetConfiguration(classId, parent) -{ - //if a saved configuration exists load it - if (qSettings != 0) - { - } -} - -PipXtremeGadgetConfiguration::~PipXtremeGadgetConfiguration() -{ -} - -/** - * Clones a configuration. - * - */ -IUAVGadgetConfiguration *PipXtremeGadgetConfiguration::clone() -{ - PipXtremeGadgetConfiguration *m = new PipXtremeGadgetConfiguration(this->classId()); - return m; -} - -/** - * Saves a configuration. - * - */ -void PipXtremeGadgetConfiguration::saveConfig(QSettings *qSettings) const -{ - if (qSettings) - { - - } -} diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetoptionspage.cpp deleted file mode 100644 index 2fd8057af..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetoptionspage.cpp +++ /dev/null @@ -1,72 +0,0 @@ -/** - ****************************************************************************** - * - * @file pipxtremegadgetoptionspage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @{ - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pipxtremegadgetoptionspage.h" -#include "pipxtremegadgetconfiguration.h" -#include "ui_pipxtremegadgetoptionspage.h" - -PipXtremeGadgetOptionsPage::PipXtremeGadgetOptionsPage(PipXtremeGadgetConfiguration *config, QObject *parent) : - IOptionsPage(parent), - options_page(NULL), - m_config(config) -{ -} - -//creates options page widget -QWidget *PipXtremeGadgetOptionsPage::createPage(QWidget *parent) -{ -// QWidget *widget = new QWidget; -// return widget; - - options_page = new Ui::PipXtremeGadgetOptionsPage(); - QWidget *optionsPageWidget = new QWidget; - options_page->setupUi(optionsPageWidget); - - - - - return optionsPageWidget; -} -/** - * Called when the user presses apply or OK. - * - * Saves the current values - * - */ -void PipXtremeGadgetOptionsPage::apply() -{ - -} - -void PipXtremeGadgetOptionsPage::finish() -{ - if (options_page) - { - delete options_page; - options_page = NULL; - } -} - - diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetoptionspage.ui deleted file mode 100644 index 3436b9567..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetoptionspage.ui +++ /dev/null @@ -1,51 +0,0 @@ - - - PipXtremeGadgetOptionsPage - - - - 0 - 0 - 587 - 359 - - - - - 0 - 0 - - - - Form - - - - 0 - - - - - - - - - 10 - - - - No options to set - - - Qt::AlignCenter - - - - - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetwidget.cpp deleted file mode 100644 index 6dc2d1047..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetwidget.cpp +++ /dev/null @@ -1,1431 +0,0 @@ -/** - ****************************************************************************** - * - * @file pipxtremegadgetwidget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @{ - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include -#include -#include -#include -#include -#include -#include - -#include "pipxtremegadgetwidget.h" - -#define NO_PORT 0 -#define SERIAL_PORT 1 -#define USB_PORT 2 - -// *************************************************************************************** -// config packet details - -#define MAX_RETRIES 7 -#define RETRY_TIME 500 // ms - -#define PIPX_HEADER_MARKER 0x76b38a52 - -enum { - PIPX_PACKET_TYPE_REQ_DETAILS = 0, - PIPX_PACKET_TYPE_DETAILS, - PIPX_PACKET_TYPE_REQ_SETTINGS, - PIPX_PACKET_TYPE_SETTINGS, - PIPX_PACKET_TYPE_REQ_STATE, - PIPX_PACKET_TYPE_STATE, - PIPX_PACKET_TYPE_SPECTRUM -}; - -enum { - FREQBAND_UNKNOWN = 0, - FREQBAND_434MHz, - FREQBAND_868MHz, - FREQBAND_915MHz -}; - -enum { - LINK_DISCONNECTED = 0, - LINK_CONNECTING, - LINK_CONNECTED -}; - -// *************************************************************************************** - -enum { - MODE_NORMAL = 0, // normal 2-way packet mode - MODE_STREAM_TX, // 1-way continuous tx packet mode - MODE_STREAM_RX, // 1-way continuous rx packet mode - MODE_PPM_TX, // PPM tx mode - MODE_PPM_RX, // PPM rx mode - MODE_SCAN_SPECTRUM, // scan the receiver over the whole band - MODE_TX_BLANK_CARRIER_TEST, // blank carrier Tx mode (for calibrating the carrier frequency say) - MODE_TX_SPECTRUM_TEST // pseudo random Tx data mode (for checking the Tx carrier spectrum) -}; - -// *************************************************************************************** - -#define Poly32 0x04c11db7 // 32-bit polynomial .. this should produce the same as the STM32 hardware CRC - -uint32_t CRC_Table32[] = { - 0x00000000, 0x04c11db7, 0x09823b6e, 0x0d4326d9, 0x130476dc, 0x17c56b6b, 0x1a864db2, 0x1e475005, - 0x2608edb8, 0x22c9f00f, 0x2f8ad6d6, 0x2b4bcb61, 0x350c9b64, 0x31cd86d3, 0x3c8ea00a, 0x384fbdbd, - 0x4c11db70, 0x48d0c6c7, 0x4593e01e, 0x4152fda9, 0x5f15adac, 0x5bd4b01b, 0x569796c2, 0x52568b75, - 0x6a1936c8, 0x6ed82b7f, 0x639b0da6, 0x675a1011, 0x791d4014, 0x7ddc5da3, 0x709f7b7a, 0x745e66cd, - 0x9823b6e0, 0x9ce2ab57, 0x91a18d8e, 0x95609039, 0x8b27c03c, 0x8fe6dd8b, 0x82a5fb52, 0x8664e6e5, - 0xbe2b5b58, 0xbaea46ef, 0xb7a96036, 0xb3687d81, 0xad2f2d84, 0xa9ee3033, 0xa4ad16ea, 0xa06c0b5d, - 0xd4326d90, 0xd0f37027, 0xddb056fe, 0xd9714b49, 0xc7361b4c, 0xc3f706fb, 0xceb42022, 0xca753d95, - 0xf23a8028, 0xf6fb9d9f, 0xfbb8bb46, 0xff79a6f1, 0xe13ef6f4, 0xe5ffeb43, 0xe8bccd9a, 0xec7dd02d, - 0x34867077, 0x30476dc0, 0x3d044b19, 0x39c556ae, 0x278206ab, 0x23431b1c, 0x2e003dc5, 0x2ac12072, - 0x128e9dcf, 0x164f8078, 0x1b0ca6a1, 0x1fcdbb16, 0x018aeb13, 0x054bf6a4, 0x0808d07d, 0x0cc9cdca, - 0x7897ab07, 0x7c56b6b0, 0x71159069, 0x75d48dde, 0x6b93dddb, 0x6f52c06c, 0x6211e6b5, 0x66d0fb02, - 0x5e9f46bf, 0x5a5e5b08, 0x571d7dd1, 0x53dc6066, 0x4d9b3063, 0x495a2dd4, 0x44190b0d, 0x40d816ba, - 0xaca5c697, 0xa864db20, 0xa527fdf9, 0xa1e6e04e, 0xbfa1b04b, 0xbb60adfc, 0xb6238b25, 0xb2e29692, - 0x8aad2b2f, 0x8e6c3698, 0x832f1041, 0x87ee0df6, 0x99a95df3, 0x9d684044, 0x902b669d, 0x94ea7b2a, - 0xe0b41de7, 0xe4750050, 0xe9362689, 0xedf73b3e, 0xf3b06b3b, 0xf771768c, 0xfa325055, 0xfef34de2, - 0xc6bcf05f, 0xc27dede8, 0xcf3ecb31, 0xcbffd686, 0xd5b88683, 0xd1799b34, 0xdc3abded, 0xd8fba05a, - 0x690ce0ee, 0x6dcdfd59, 0x608edb80, 0x644fc637, 0x7a089632, 0x7ec98b85, 0x738aad5c, 0x774bb0eb, - 0x4f040d56, 0x4bc510e1, 0x46863638, 0x42472b8f, 0x5c007b8a, 0x58c1663d, 0x558240e4, 0x51435d53, - 0x251d3b9e, 0x21dc2629, 0x2c9f00f0, 0x285e1d47, 0x36194d42, 0x32d850f5, 0x3f9b762c, 0x3b5a6b9b, - 0x0315d626, 0x07d4cb91, 0x0a97ed48, 0x0e56f0ff, 0x1011a0fa, 0x14d0bd4d, 0x19939b94, 0x1d528623, - 0xf12f560e, 0xf5ee4bb9, 0xf8ad6d60, 0xfc6c70d7, 0xe22b20d2, 0xe6ea3d65, 0xeba91bbc, 0xef68060b, - 0xd727bbb6, 0xd3e6a601, 0xdea580d8, 0xda649d6f, 0xc423cd6a, 0xc0e2d0dd, 0xcda1f604, 0xc960ebb3, - 0xbd3e8d7e, 0xb9ff90c9, 0xb4bcb610, 0xb07daba7, 0xae3afba2, 0xaafbe615, 0xa7b8c0cc, 0xa379dd7b, - 0x9b3660c6, 0x9ff77d71, 0x92b45ba8, 0x9675461f, 0x8832161a, 0x8cf30bad, 0x81b02d74, 0x857130c3, - 0x5d8a9099, 0x594b8d2e, 0x5408abf7, 0x50c9b640, 0x4e8ee645, 0x4a4ffbf2, 0x470cdd2b, 0x43cdc09c, - 0x7b827d21, 0x7f436096, 0x7200464f, 0x76c15bf8, 0x68860bfd, 0x6c47164a, 0x61043093, 0x65c52d24, - 0x119b4be9, 0x155a565e, 0x18197087, 0x1cd86d30, 0x029f3d35, 0x065e2082, 0x0b1d065b, 0x0fdc1bec, - 0x3793a651, 0x3352bbe6, 0x3e119d3f, 0x3ad08088, 0x2497d08d, 0x2056cd3a, 0x2d15ebe3, 0x29d4f654, - 0xc5a92679, 0xc1683bce, 0xcc2b1d17, 0xc8ea00a0, 0xd6ad50a5, 0xd26c4d12, 0xdf2f6bcb, 0xdbee767c, - 0xe3a1cbc1, 0xe760d676, 0xea23f0af, 0xeee2ed18, 0xf0a5bd1d, 0xf464a0aa, 0xf9278673, 0xfde69bc4, - 0x89b8fd09, 0x8d79e0be, 0x803ac667, 0x84fbdbd0, 0x9abc8bd5, 0x9e7d9662, 0x933eb0bb, 0x97ffad0c, - 0xafb010b1, 0xab710d06, 0xa6322bdf, 0xa2f33668, 0xbcb4666d, 0xb8757bda, 0xb5365d03, 0xb1f740b4 -}; - -// *************************************************************************************** - -// constructor -PipXtremeGadgetWidget::PipXtremeGadgetWidget(QWidget *parent) : - QWidget(parent), - m_widget(NULL), - m_ioDevice(NULL), - m_stage(PIPX_IDLE) -{ - m_widget = new Ui_PipXtremeWidget(); - m_widget->setupUi(this); - - #if QT_VERSION >= 0x040700 - qsrand(QDateTime::currentDateTime().toMSecsSinceEpoch()); - #else - qsrand(QDateTime::currentDateTime().toTime_t()); - #endif - - device_input_buffer.size = 8192; - device_input_buffer.used = 0; - device_input_buffer.buffer = new quint8 [device_input_buffer.size]; - - memset(&pipx_config_details, 0, sizeof(pipx_config_details)); - memset(&pipx_config_settings, 0, sizeof(pipx_config_settings)); - - m_widget->comboBox_SerialBaudrate->clear(); - m_widget->comboBox_SerialBaudrate->addItem("1200", 1200); - m_widget->comboBox_SerialBaudrate->addItem("2400", 2400); - m_widget->comboBox_SerialBaudrate->addItem("4800", 4800); - m_widget->comboBox_SerialBaudrate->addItem("9600", 9600); - m_widget->comboBox_SerialBaudrate->addItem("19200", 19200); - m_widget->comboBox_SerialBaudrate->addItem("38400", 38400); - m_widget->comboBox_SerialBaudrate->addItem("57600", 57600); - m_widget->comboBox_SerialBaudrate->addItem("115200", 115200); - #if (defined Q_OS_WIN) - m_widget->comboBox_SerialBaudrate->addItem("230400", 230400); - m_widget->comboBox_SerialBaudrate->addItem("460800", 460800); - m_widget->comboBox_SerialBaudrate->addItem("921600", 921600); - #endif - m_widget->comboBox_SerialBaudrate->setCurrentIndex(m_widget->comboBox_SerialBaudrate->findText("57600")); - - m_widget->comboBox_Mode->clear(); - m_widget->comboBox_Mode->addItem("Normal", MODE_NORMAL); - m_widget->comboBox_Mode->addItem("Continuous Stream Tx", MODE_STREAM_TX); - m_widget->comboBox_Mode->addItem("Continuous Stream Rx", MODE_STREAM_RX); - m_widget->comboBox_Mode->addItem("PPM Tx", MODE_PPM_TX); - m_widget->comboBox_Mode->addItem("PPM Rx", MODE_PPM_RX); - m_widget->comboBox_Mode->addItem("Scan Spectrum", MODE_SCAN_SPECTRUM); - m_widget->comboBox_Mode->addItem("Test Tx Blank Carrier Frequency", MODE_TX_BLANK_CARRIER_TEST); - m_widget->comboBox_Mode->addItem("Test Tx Spectrum", MODE_TX_SPECTRUM_TEST); - - m_widget->comboBox_SerialPortSpeed->clear(); - for (int i = 0; i < m_widget->comboBox_SerialBaudrate->count(); i++) - m_widget->comboBox_SerialPortSpeed->addItem(m_widget->comboBox_SerialBaudrate->itemText(i), m_widget->comboBox_SerialBaudrate->itemData(i)); - m_widget->comboBox_SerialPortSpeed->setCurrentIndex(m_widget->comboBox_SerialPortSpeed->findText("57600")); - - m_widget->comboBox_MaxRFBandwidth->clear(); - m_widget->comboBox_MaxRFBandwidth->addItem("500", 500); - m_widget->comboBox_MaxRFBandwidth->addItem("1000", 1000); - m_widget->comboBox_MaxRFBandwidth->addItem("2000", 2000); - m_widget->comboBox_MaxRFBandwidth->addItem("4000", 4000); - m_widget->comboBox_MaxRFBandwidth->addItem("8000", 8000); - m_widget->comboBox_MaxRFBandwidth->addItem("9600", 9600); - m_widget->comboBox_MaxRFBandwidth->addItem("16000", 16000); - m_widget->comboBox_MaxRFBandwidth->addItem("19200", 19200); - m_widget->comboBox_MaxRFBandwidth->addItem("24000", 24000); - m_widget->comboBox_MaxRFBandwidth->addItem("32000", 32000); - m_widget->comboBox_MaxRFBandwidth->addItem("64000", 64000); - m_widget->comboBox_MaxRFBandwidth->addItem("128000", 128000); - m_widget->comboBox_MaxRFBandwidth->addItem("192000", 192000); - m_widget->comboBox_MaxRFBandwidth->addItem("256000", 256000); - m_widget->comboBox_MaxRFBandwidth->setCurrentIndex(m_widget->comboBox_MaxRFBandwidth->findText("128000")); - - m_widget->comboBox_MaxRFTxPower->clear(); - m_widget->comboBox_MaxRFTxPower->addItem("1.25mW", 0); - m_widget->comboBox_MaxRFTxPower->addItem("1.6mW", 1); - m_widget->comboBox_MaxRFTxPower->addItem("3.16mW", 2); - m_widget->comboBox_MaxRFTxPower->addItem("6.3mW", 3); - m_widget->comboBox_MaxRFTxPower->addItem("12.6mW", 4); - m_widget->comboBox_MaxRFTxPower->addItem("25mW", 5); - m_widget->comboBox_MaxRFTxPower->addItem("50mW", 6); - m_widget->comboBox_MaxRFTxPower->addItem("100mW", 7); - m_widget->comboBox_MaxRFTxPower->setCurrentIndex(m_widget->comboBox_MaxRFTxPower->findText("12.6mW")); - - m_widget->doubleSpinBox_Frequency->setSingleStep(0.00015625); - - m_widget->widgetRSSI->setMinimum(-120); - m_widget->widgetRSSI->setMaximum(0); - m_widget->widgetRSSI->setValue(m_widget->widgetRSSI->minimum()); - - m_widget->label_RSSI->setText("RSSI"); - - m_widget->graphicsView_Spectrum->setScene(new QGraphicsScene(this)); - m_widget->graphicsView_Spectrum->setViewport(new QGLWidget(QGLFormat(QGL::SampleBuffers))); -// m_widget->graphicsView_Spectrum->setViewport(new QWidget); - m_widget->graphicsView_Spectrum->setCacheMode(QGraphicsView::CacheBackground); - m_widget->graphicsView_Spectrum->setRenderHints(QPainter::Antialiasing | QPainter::TextAntialiasing | QPainter::SmoothPixmapTransform | QPainter::HighQualityAntialiasing); - QGraphicsScene *spec_scene = m_widget->graphicsView_Spectrum->scene(); - if (spec_scene) - { - spec_scene->setBackgroundBrush(QColor(80, 80, 80)); - spec_scene->clear(); - -// spec_scene->addItem(m_background); -// spec_scene->addItem(m_joystickEnd); -// spec_scene->setSceneRect(m_background->boundingRect()); - } - - m_widget->pushButton_Save->setEnabled(false); - m_widget->pushButton_ScanSpectrum->setEnabled(false); - m_widget->pushButton_Import->setEnabled(false); - m_widget->pushButton_Export->setEnabled(false); - - QIcon rbi; - rbi.addFile(QString(":pipxtreme/images/view-refresh.svg")); - m_widget->refreshPorts->setIcon(rbi); - - // Listen to telemetry connection events - ExtensionSystem::PluginManager *pluginManager = ExtensionSystem::PluginManager::instance(); - if (pluginManager) - { - TelemetryManager *telemetryManager = pluginManager->getObject(); - if (telemetryManager) - { - connect(telemetryManager, SIGNAL(myStart()), this, SLOT(onTelemetryStart())); - connect(telemetryManager, SIGNAL(myStop()), this, SLOT(onTelemetryStop())); - connect(telemetryManager, SIGNAL(connected()), this, SLOT(onTelemetryConnect())); - connect(telemetryManager, SIGNAL(disconnected()), this, SLOT(onTelemetryDisconnect())); - } - } - - getPorts(); - - connect(m_widget->connectButton, SIGNAL(clicked()), this, SLOT(connectDisconnect())); - connect(m_widget->refreshPorts, SIGNAL(clicked()), this, SLOT(getPorts())); - connect(m_widget->pushButton_AESKeyRandom, SIGNAL(clicked()), this, SLOT(randomiseAESKey())); - connect(m_widget->pushButton_ScanSpectrum, SIGNAL(clicked()), this, SLOT(scanSpectrum())); - connect(m_widget->pushButton_Save, SIGNAL(clicked()), this, SLOT(saveToFlash())); - connect(m_widget->lineEdit_AESKey, SIGNAL(textChanged(const QString &)), this, SLOT(textChangedAESKey(const QString &))); - connect(m_widget->pushButton_Import, SIGNAL(clicked()), this, SLOT(importSettings())); - connect(m_widget->pushButton_Export, SIGNAL(clicked()), this, SLOT(exportSettings())); -} - -// destructor .. this never gets called :( -PipXtremeGadgetWidget::~PipXtremeGadgetWidget() -{ - disconnectPort(false); - - device_input_buffer.mutex.lock(); - if (device_input_buffer.buffer) - { - delete [] device_input_buffer.buffer; - device_input_buffer.buffer = NULL; - device_input_buffer.size = 0; - device_input_buffer.used = 0; - } - device_input_buffer.mutex.unlock(); -} - -// *************************************************************************************** - -void PipXtremeGadgetWidget::resizeEvent(QResizeEvent *event) -{ - if (m_widget) - { - if (m_widget->graphicsView_Spectrum) - { - QGraphicsScene *spec_scene = m_widget->graphicsView_Spectrum->scene(); - if (spec_scene) - { -// spec_scene->setSceneRect(QRect(QPoint(0, 0), event->size())); -// spec_scene->setBackgroundBrush(Qt::black); - } - } - } - -// PipXtremeGadgetWidget::resizeEvent(event); -} - -// *************************************************************************************** - -void PipXtremeGadgetWidget::onComboBoxPorts_currentIndexChanged(int index) -{ - if (index < 0) - { - m_widget->comboBox_SerialBaudrate->setEnabled(false); - return; - } - - int type = m_widget->comboBox_Ports->itemData(index).toInt(); - - m_widget->comboBox_SerialBaudrate->setEnabled(type == SERIAL_PORT); -} - -// *************************************************************************************** - -uint32_t PipXtremeGadgetWidget::updateCRC32(uint32_t crc, uint8_t b) -{ - return (crc << 8) ^ CRC_Table32[(crc >> 24) ^ b]; -} - -uint32_t PipXtremeGadgetWidget::updateCRC32Data(uint32_t crc, void *data, int len) -{ - register uint8_t *p = (uint8_t *)data; - register uint32_t _crc = crc; - for (int i = len; i > 0; i--) - _crc = (_crc << 8) ^ CRC_Table32[(_crc >> 24) ^ *p++]; - return _crc; -} - -// Generate the CRC table -void PipXtremeGadgetWidget::makeCRC_Table32() -{ - for (int i = 0; i < 256; i++) - { - uint32_t crc = i; - for (int j = 8; j > 0; j--) - crc = (crc & 1) ? (crc << 1) ^ Poly32 : crc << 1; - CRC_Table32[i] = crc; - } -} - -// *************************************************************************************** - -QString PipXtremeGadgetWidget::getSerialPortDevice(const QString &friendName) -{ - QList ports = QextSerialEnumerator::getPorts(); - - foreach (QextPortInfo port, ports) - { - #ifdef Q_OS_WIN - if (port.friendName == friendName) - return port.portName; - #else - if (port.friendName == friendName) - return port.physName; - #endif - } - - return ""; -} - -bool sortSerialPorts(const QextPortInfo &s1, const QextPortInfo &s2) -{ - return (s1.portName < s2.portName); -} - -void PipXtremeGadgetWidget::getPorts() -{ - disconnect(m_widget->comboBox_Ports, 0, 0, 0); - - m_widget->comboBox_Ports->clear(); - - // ******************************** - // Populate the telemetry combo box with serial ports - - QList serial_ports = QextSerialEnumerator::getPorts(); - - qSort(serial_ports.begin(), serial_ports.end(), sortSerialPorts); - - QStringList list; - - foreach (QextPortInfo port, serial_ports) - list.append(port.friendName); - - for (int i = 0; i < list.count(); i++) - m_widget->comboBox_Ports->addItem("com: " + list.at(i), SERIAL_PORT); - - // ******************************** - // Populate the telemetry combo box with usb ports - - pjrc_rawhid *rawHidHandle = new pjrc_rawhid(); - if (rawHidHandle) - { - int opened = rawHidHandle->open(10, 0x20A0, 0x415C, 0xFF9C, 0x0001); - if (opened > 0) - { - QList usb_ports; - - for (int i = 0; i < opened; i++) - usb_ports.append(rawHidHandle->getserial(i)); - - qSort(usb_ports.begin(), usb_ports.end()); - - for (int i = 0; i < usb_ports.count(); i++) - m_widget->comboBox_Ports->addItem("usb: " + usb_ports.at(i), USB_PORT); - } - - delete rawHidHandle; - } - - // ******************************** - - connect(m_widget->comboBox_Ports, SIGNAL(currentIndexChanged(int)), this, SLOT(onComboBoxPorts_currentIndexChanged(int))); - - onComboBoxPorts_currentIndexChanged(m_widget->comboBox_Ports->currentIndex()); - - // ******************************** -} - -// *************************************************************************************** - -void PipXtremeGadgetWidget::onTelemetryStart() -{ - setEnabled(false); - -// m_widget->connectButton->setEnabled(false); -// m_widget->comboBox_Ports->setEnabled(false); -// m_widget->refreshPorts->setEnabled(false); -// m_widget->comboBox_SerialBaudrate->setEnabled(false); -} - -void PipXtremeGadgetWidget::onTelemetryStop() -{ - setEnabled(true); - -// m_widget->connectButton->setEnabled(true); -// m_widget->comboBox_Ports->setEnabled(true); -// m_widget->refreshPorts->setEnabled(true); -// m_widget->comboBox_SerialBaudrate->setEnabled(true); -} - -// *************************************************************************************** - -void PipXtremeGadgetWidget::onTelemetryConnect() -{ -} - -void PipXtremeGadgetWidget::onTelemetryDisconnect() -{ -} - -// *************************************************************************************** - -void PipXtremeGadgetWidget::disableTelemetry() -{ // Suspend telemetry & polling - - Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); - if (!cm) return; - - cm->disconnectDevice(); - cm->suspendPolling(); -} - -void PipXtremeGadgetWidget::enableTelemetry() -{ // Restart the polling thread - - Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); - if (!cm) return; - - cm->resumePolling(); -} - -// *************************************************************************************** - -void PipXtremeGadgetWidget::randomiseAESKey() -{ - #if QT_VERSION >= 0x040700 - uint32_t crc = ((uint32_t)qrand() << 16) ^ qrand() ^ QDateTime::currentDateTime().toMSecsSinceEpoch(); // only available with Qt 4.7.1 and later - #else - uint32_t crc = ((uint32_t)qrand() << 16) ^ qrand() ^ QDateTime::currentDateTime().toTime_t(); - #endif - - QString key = ""; - for (int i = 0; i < 4; i++) - { - for (int i = 0; i < (27 + (qrand() & 0x7f)); i++) - crc = updateCRC32(crc, qrand()); - - key += QString::number(crc, 16).rightJustified(8, '0'); - } - - m_widget->lineEdit_AESKey->setText(key); -} - -void PipXtremeGadgetWidget::scanSpectrum() -{ -} - -void PipXtremeGadgetWidget::saveToFlash() -{ - QMutexLocker locker_dev(&device_mutex); - QMutexLocker locker_inbuf(&device_input_buffer.mutex); - - if (!m_ioDevice) return; - if (!m_ioDevice->isOpen()) return; - - if (pipx_config_details.serial_number == 0) return; // we first need some details before sending new setings - - QString s; - bool ok; - - t_pipx_config_settings settings; - - settings.mode = m_widget->comboBox_Mode->itemData(m_widget->comboBox_Mode->currentIndex()).toUInt(); - - s = m_widget->lineEdit_PairedSerialNumber->text().trimmed().toLower(); - s.replace(' ', ""); // remove all spaces - if (s.startsWith("0x")) - { - s.remove(0, 2); - s = s.trimmed(); - } - settings.destination_id = s.toUInt(&ok, 16); - if (s.isEmpty() || !ok) - { - error("Check your \"Paired Serial Number\" entry!", 0); - return; - } - - settings.rf_xtal_cap = m_widget->spinBox_FrequencyCalibration->value(); - - s = m_widget->doubleSpinBox_Frequency->text().trimmed(); - s.replace(' ', ""); // remove all spaces - settings.frequency_Hz = (uint32_t)(s.toDouble(&ok) * 1e6); - if (ok) // round it to the 'frequency step size' - settings.frequency_Hz = (uint32_t)(((double)settings.frequency_Hz + pipx_config_details.frequency_step_size / 2) / pipx_config_details.frequency_step_size) * pipx_config_details.frequency_step_size; - if (s.isEmpty() || !ok || settings.frequency_Hz < pipx_config_details.min_frequency_Hz || settings.frequency_Hz > pipx_config_details.max_frequency_Hz) - { - error("Check your \"Frequency\" entry!", 0); - return; - } - - settings.max_rf_bandwidth = m_widget->comboBox_MaxRFBandwidth->itemData(m_widget->comboBox_MaxRFBandwidth->currentIndex()).toInt(); - settings.max_tx_power = m_widget->comboBox_MaxRFTxPower->itemData(m_widget->comboBox_MaxRFTxPower->currentIndex()).toInt(); - settings.serial_baudrate = m_widget->comboBox_SerialPortSpeed->itemData(m_widget->comboBox_SerialPortSpeed->currentIndex()).toInt(); - settings.aes_enable = m_widget->checkBox_AESEnable->isChecked(); - settings.rts_time = m_widget->spinBox_RTSTime->value(); - - memset(settings.aes_key, 0, sizeof(settings.aes_key)); - s = m_widget->lineEdit_AESKey->text().trimmed(); - s.replace(' ', ""); // remove all spaces - while (s.length() < 32) s = '0' + s; - if (settings.aes_enable && s.length() != 32) - { - error("Check your \"AES Key\" entry! .. it must be 32 hex characters long", 0); - return; - } - for (int i = 0; i < (int)sizeof(settings.aes_key); i++) - { - QString s2 = s.left(2); - s.remove(0, 2); - s = s.trimmed(); - settings.aes_key[i] = s2.toUInt(&ok, 16); - if (!ok) - { - error("Check your \"AES Key\" entry! .. it must contain only hex characters (0-9, a-f)", 0); - return; - } - } - - // send the new settings to the modem - sendSettings(pipx_config_details.serial_number, &settings); - - // retrieve them back - m_stage_retries = 0; - m_stage = PIPX_REQ_SETTINGS; -} - -void PipXtremeGadgetWidget::textChangedAESKey(const QString &text) -{ - QString s = text; - s.replace(' ', ""); - m_widget->label_AESkey->setText("AES Encryption Key (" + QString::number(s.length()) + ")"); -} - -// *************************************************************************************** -// send various packets - -void PipXtremeGadgetWidget::sendRequestDetails(uint32_t serial_number) -{ - // ***************** - // create the packet - - t_pipx_config_header header; - header.marker = PIPX_HEADER_MARKER; - header.serial_number = serial_number; - header.type = PIPX_PACKET_TYPE_REQ_DETAILS; - header.spare = 0; - header.data_size = 0; - header.data_crc = 0xffffffff; - header.header_crc = 0; - header.header_crc = updateCRC32Data(0xffffffff, &header, sizeof(t_pipx_config_header)); - - // ***************** - // send the packet - -// QMutexLocker locker_dev(&device_mutex); - if (!m_ioDevice) return; - if (!m_ioDevice->isOpen()) return; - qint64 bytes_written = m_ioDevice->write((const char*)&header, sizeof(t_pipx_config_header)); - - Q_UNUSED(bytes_written) - - // ***************** -} - -void PipXtremeGadgetWidget::sendRequestSettings(uint32_t serial_number) -{ - if (serial_number == 0) - return; - - // ***************** - // create the packet - - t_pipx_config_header header; - header.marker = PIPX_HEADER_MARKER; - header.serial_number = serial_number; - header.type = PIPX_PACKET_TYPE_REQ_SETTINGS; - header.spare = 0; - header.data_size = 0; - header.data_crc = 0xffffffff; - header.header_crc = 0; - header.header_crc = updateCRC32Data(0xffffffff, &header, sizeof(t_pipx_config_header)); - - // ***************** - // send the packet - -// QMutexLocker locker_dev(&device_mutex); - if (!m_ioDevice) return; - if (!m_ioDevice->isOpen()) return; - qint64 bytes_written = m_ioDevice->write((const char*)&header, sizeof(t_pipx_config_header)); - -// qDebug() << "PipX m_ioDevice->write: " << QString::number(bytes_written) << endl; - - Q_UNUSED(bytes_written) - -// error("Bytes written", bytes_written); // TEST ONLY - - // ***************** -} - -void PipXtremeGadgetWidget::sendRequestState(uint32_t serial_number) -{ - if (serial_number == 0) - return; - - // ***************** - // create the packet - - t_pipx_config_header header; - header.marker = PIPX_HEADER_MARKER; - header.serial_number = serial_number; - header.type = PIPX_PACKET_TYPE_REQ_STATE; - header.spare = 0; - header.data_size = 0; - header.data_crc = 0xffffffff; - header.header_crc = 0; - header.header_crc = updateCRC32Data(0xffffffff, &header, sizeof(t_pipx_config_header)); - - // ***************** - // send the packet - -// QMutexLocker locker_dev(&device_mutex); - if (!m_ioDevice) return; - if (!m_ioDevice->isOpen()) return; - qint64 bytes_written = m_ioDevice->write((const char*)&header, sizeof(t_pipx_config_header)); - -// qDebug() << "PipX m_ioDevice->write: " << QString::number(bytes_written) << endl; - - Q_UNUSED(bytes_written) - -// error("Bytes written", bytes_written); // TEST ONLY - - // ***************** -} - -void PipXtremeGadgetWidget::sendSettings(uint32_t serial_number, t_pipx_config_settings *settings) -{ - if (serial_number == 0) - return; - - if (!settings) - return; - - uint8_t buffer[sizeof(t_pipx_config_header) + sizeof(t_pipx_config_settings)]; - - t_pipx_config_header *header = (t_pipx_config_header *)buffer; - uint8_t *data = (uint8_t *) header + sizeof(t_pipx_config_header); - - // ***************** - // create the packet - - memcpy(data, settings, sizeof(t_pipx_config_settings)); - - header->marker = PIPX_HEADER_MARKER; - header->serial_number = serial_number; - header->type = PIPX_PACKET_TYPE_SETTINGS; - header->spare = 0; - header->data_size = sizeof(t_pipx_config_settings); - header->data_crc = updateCRC32Data(0xffffffff, data, header->data_size); - header->header_crc = 0; - header->header_crc = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header)); - - // ***************** - // send the packet - -// QMutexLocker locker_dev(&device_mutex); - if (!m_ioDevice) return; - if (!m_ioDevice->isOpen()) return; - qint64 bytes_written = m_ioDevice->write((const char*)buffer, sizeof(t_pipx_config_header) + header->data_size); - -// error("Bytes written", bytes_written); // TEST ONLY - - Q_UNUSED(bytes_written) - - // ***************** -} - -// *************************************************************************************** -// process rx stream data - -void PipXtremeGadgetWidget::processRxStream() -{ - QMutexLocker locker_dev(&device_mutex); - QMutexLocker locker_inbuf(&device_input_buffer.mutex); - - if (!m_ioDevice) return; - if (!m_ioDevice->isOpen()) return; - - QTimer::singleShot(100, this, SLOT(processRxStream())); - - qint64 bytes_available = m_ioDevice->bytesAvailable(); - if (bytes_available <= 0) return; - - // ensure we have buffer space for the new data - if (!device_input_buffer.buffer) - { // allocate a buffer for the data - device_input_buffer.size = bytes_available * 2; - device_input_buffer.used = 0; - device_input_buffer.buffer = new quint8 [device_input_buffer.size]; - if (!device_input_buffer.buffer) return; - } - else - { - if ((device_input_buffer.used + (bytes_available * 2)) > device_input_buffer.size) - { // need to increase the buffer size - - // create a new larger buffer - int new_size = device_input_buffer.used + bytes_available * 2; - quint8 *new_buf = new quint8 [new_size]; - if (!new_buf) return; - - // copy the data from the old buffer into the new buffer - memmove(new_buf, device_input_buffer.buffer, device_input_buffer.used); - - // delete the old buffer - delete [] device_input_buffer.buffer; - - // keep the new buffer - device_input_buffer.buffer = new_buf; - device_input_buffer.size = new_size; - } - } - - // add the new data into the buffer - qint64 bytes_read = m_ioDevice->read((char *)(device_input_buffer.buffer + device_input_buffer.used), device_input_buffer.size - device_input_buffer.used); - if (bytes_read <= 0) return; - device_input_buffer.used += bytes_read; - - processRxBuffer(); -} - -void PipXtremeGadgetWidget::processRxBuffer() -{ // scan the buffer for a valid packet - - if (!device_input_buffer.buffer || device_input_buffer.used < (int)sizeof(t_pipx_config_header)) - return; // no data as yet or not yet enough data - - while (device_input_buffer.used >= (int)sizeof(t_pipx_config_header)) - { - uint32_t crc1, crc2; - - t_pipx_config_header *header = (t_pipx_config_header *)device_input_buffer.buffer; - uint8_t *data = (uint8_t *)header + sizeof(t_pipx_config_header); - - // check packet marker - if (header->marker != PIPX_HEADER_MARKER) - { // marker not yet found - // remove a byte - int i = 1; - if (i < device_input_buffer.used) - memmove(device_input_buffer.buffer, device_input_buffer.buffer + i, device_input_buffer.used - i); - device_input_buffer.used -= i; - continue; - } - - // check the header CRC - crc1 = header->header_crc; - header->header_crc = 0; - crc2 = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header)); - header->header_crc = crc1; - if (crc2 != crc1) - { // faulty header - int i = 1; - if (i < device_input_buffer.used) - memmove(device_input_buffer.buffer, device_input_buffer.buffer + i, device_input_buffer.used - i); - device_input_buffer.used -= i; - continue; - } - - // valid error free header found! - - int total_packet_size = sizeof(t_pipx_config_header) + header->data_size; - - if (device_input_buffer.used < total_packet_size) - { // not yet got a full packet - break; - } - - if (header->data_size > 0) - { - // check the data crc - crc1 = header->data_crc; - crc2 = updateCRC32Data(0xffffffff, data, header->data_size); - if (crc2 != crc1) - { // faulty data - int i = 1; - if (i < device_input_buffer.used) - memmove(device_input_buffer.buffer, device_input_buffer.buffer + i, device_input_buffer.used - i); - device_input_buffer.used -= i; - continue; - } - } - - processRxPacket(device_input_buffer.buffer, total_packet_size); - - // remove the packet from the buffer - if (total_packet_size < device_input_buffer.used) - memmove(device_input_buffer.buffer, device_input_buffer.buffer + total_packet_size, device_input_buffer.used - total_packet_size); - device_input_buffer.used -= total_packet_size; - } -} - -void PipXtremeGadgetWidget::processRxPacket(quint8 *packet, int packet_size) -{ - if (!packet || packet_size <= 0) - return; - - t_pipx_config_header *header = (t_pipx_config_header *)packet; - uint8_t *data = (uint8_t *)header + sizeof(t_pipx_config_header); - - switch (header->type) - { - case PIPX_PACKET_TYPE_REQ_DETAILS: - break; - - case PIPX_PACKET_TYPE_DETAILS: - if (m_stage == PIPX_REQ_DETAILS) - { - m_stage_retries = 0; - m_stage = PIPX_REQ_SETTINGS; - - if (packet_size < (int)sizeof(t_pipx_config_header) + (int)sizeof(t_pipx_config_details)) - break; // packet size is too small - error - - memcpy(&pipx_config_details, data, sizeof(t_pipx_config_details)); - - if (pipx_config_details.major_version < 0 || (pipx_config_details.major_version <= 0 && pipx_config_details.minor_version < 6)) - { - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Critical); - msgBox.setText("You need to update your PipX modem firmware to V0.5 or later"); - msgBox.exec(); - disconnectPort(true); - return; - } - - m_widget->lineEdit_FirmwareVersion->setText(QString::number(pipx_config_details.major_version) + "." + QString::number(pipx_config_details.minor_version)); - - m_widget->lineEdit_SerialNumber->setText(QString::number(pipx_config_details.serial_number, 16).toUpper()); - - if (pipx_config_details.frequency_band == FREQBAND_434MHz) - m_widget->lineEdit_FrequencyBand->setText("434MHz"); - else - if (pipx_config_details.frequency_band == FREQBAND_868MHz) - m_widget->lineEdit_FrequencyBand->setText("868MHz"); - else - if (pipx_config_details.frequency_band == FREQBAND_915MHz) - m_widget->lineEdit_FrequencyBand->setText("915MHz"); - else - m_widget->lineEdit_FrequencyBand->setText("UNKNOWN [" + QString::number(pipx_config_details.frequency_band) + "]"); - - m_widget->lineEdit_MinFrequency->setText(QString::number((double)pipx_config_details.min_frequency_Hz / 1e6, 'f', 6) + "MHz"); - m_widget->lineEdit_MaxFrequency->setText(QString::number((double)pipx_config_details.max_frequency_Hz / 1e6, 'f', 6) + "MHz"); - - m_widget->doubleSpinBox_Frequency->setMinimum((double)pipx_config_details.min_frequency_Hz / 1e6); - m_widget->doubleSpinBox_Frequency->setMaximum((double)pipx_config_details.max_frequency_Hz / 1e6); - m_widget->doubleSpinBox_Frequency->setSingleStep(((double)pipx_config_details.frequency_step_size * 4) / 1e6); - - m_widget->lineEdit_FrequencyStepSize->setText(QString::number(pipx_config_details.frequency_step_size, 'f', 2) + "Hz"); - - m_widget->pushButton_Save->setEnabled(true); - m_widget->pushButton_ScanSpectrum->setEnabled(true); - m_widget->pushButton_Import->setEnabled(true); - m_widget->pushButton_Export->setEnabled(true); - } - break; - - case PIPX_PACKET_TYPE_REQ_SETTINGS: - break; - - case PIPX_PACKET_TYPE_SETTINGS: - if (m_stage == PIPX_REQ_SETTINGS && pipx_config_details.serial_number != 0) - { - if (packet_size < (int)sizeof(t_pipx_config_header) + (int)sizeof(t_pipx_config_settings)) - break; // packet size is too small - error - - m_stage_retries = 0; - m_stage = PIPX_REQ_STATE; - - memcpy(&pipx_config_settings, data, sizeof(t_pipx_config_settings)); - - m_widget->comboBox_Mode->setCurrentIndex(m_widget->comboBox_Mode->findData(pipx_config_settings.mode)); - m_widget->lineEdit_PairedSerialNumber->setText(QString::number(pipx_config_settings.destination_id, 16).toUpper()); - m_widget->spinBox_FrequencyCalibration->setValue(pipx_config_settings.rf_xtal_cap); - m_widget->doubleSpinBox_Frequency->setValue((double)pipx_config_settings.frequency_Hz / 1e6); - m_widget->comboBox_MaxRFBandwidth->setCurrentIndex(m_widget->comboBox_MaxRFBandwidth->findData(pipx_config_settings.max_rf_bandwidth)); - m_widget->comboBox_MaxRFTxPower->setCurrentIndex(m_widget->comboBox_MaxRFTxPower->findData(pipx_config_settings.max_tx_power)); - m_widget->comboBox_SerialPortSpeed->setCurrentIndex(m_widget->comboBox_SerialPortSpeed->findData(pipx_config_settings.serial_baudrate)); - m_widget->spinBox_RTSTime->setValue(pipx_config_settings.rts_time); - - QString key = ""; - for (int i = 0; i < (int)sizeof(pipx_config_settings.aes_key); i++) - key += QString::number(pipx_config_settings.aes_key[i], 16).rightJustified(2, '0'); - m_widget->lineEdit_AESKey->setText(key); - m_widget->checkBox_AESEnable->setChecked(pipx_config_settings.aes_enable); - } - - break; - - case PIPX_PACKET_TYPE_REQ_STATE: - break; - - case PIPX_PACKET_TYPE_STATE: - if (m_stage == PIPX_REQ_STATE && pipx_config_details.serial_number != 0) - { - if (packet_size < (int)sizeof(t_pipx_config_header) + (int)sizeof(t_pipx_config_state)) - break; // packet size is too small - error - - m_stage_retries = 0; -// m_stage = PIPX_REQ_STATE; - - memcpy(&pipx_config_state, data, sizeof(t_pipx_config_state)); - - switch (pipx_config_state.link_state) - { - case LINK_DISCONNECTED: - m_widget->lineEdit_LinkState->setText("Disconnected"); - break; - case LINK_CONNECTING: - m_widget->lineEdit_LinkState->setText("Connecting"); - break; - case LINK_CONNECTED: - m_widget->lineEdit_LinkState->setText("Connected"); - break; - default: - m_widget->lineEdit_LinkState->setText("Unknown [" + QString::number(pipx_config_state.link_state) + "]"); - break; - } - if (pipx_config_state.rssi < m_widget->widgetRSSI->minimum()) - m_widget->widgetRSSI->setValue(m_widget->widgetRSSI->minimum()); - else - if (pipx_config_state.rssi > m_widget->widgetRSSI->maximum()) - m_widget->widgetRSSI->setValue(m_widget->widgetRSSI->maximum()); - else - m_widget->widgetRSSI->setValue(pipx_config_state.rssi); - m_widget->label_RSSI->setText("RSSI " + QString::number(pipx_config_state.rssi) + "dBm"); - m_widget->lineEdit_RxAFC->setText(QString::number(pipx_config_state.afc) + "Hz"); - m_widget->lineEdit_Retries->setText(QString::number(pipx_config_state.retries)); - } - - break; - - case PIPX_PACKET_TYPE_SPECTRUM: // a packet with scanned spectrum data - if (pipx_config_details.serial_number != 0) - { - if (packet_size < (int)sizeof(t_pipx_config_header) + (int)sizeof(t_pipx_config_spectrum)) - break; // packet size is too small - error - - memcpy(&pipx_config_spectrum, data, sizeof(t_pipx_config_spectrum)); - int8_t *spec_data = (int8_t *)(data + sizeof(t_pipx_config_spectrum)); - - if (pipx_config_spectrum.magnitudes > 0) - { - m_widget->label_19->setText(QString::number(pipx_config_spectrum.start_frequency) + " " + QString::number(pipx_config_spectrum.frequency_step_size) + " " + QString::number(pipx_config_spectrum.magnitudes)); -/* - QGraphicsScene *spec_scene = m_widget->graphicsView_Spectrum->scene(); - if (spec_scene) - { - if (pipx_config_spectrum.start_frequency - pipx_config_details.min_frequency_Hz <= 0) - spec_scene->clear(); - - int w = 500; - int h = 500; - - float xscale = (float)w / (pipx_config_details.max_frequency_Hz - pipx_config_details.min_frequency_Hz); - float yscale = h / 128.0f; - - float xs = xscale * (pipx_config_spectrum.start_frequency - pipx_config_details.min_frequency_Hz); - - for (int i = 0; i < pipx_config_spectrum.magnitudes; i++) - { - int x = -(w / 2) + xs + (xscale * i * pipx_config_spectrum.frequency_step_size); - int rssi = (int)spec_data[i] + 128; - int y = yscale * rssi; - spec_scene->addLine(x, -h / 2, x, (-h / 2) - y, QPen(Qt::green, 1, Qt::SolidLine, Qt::SquareCap)); - } - } -*/ - } - } - - break; - - default: - break; - } -} - - -// *************************************************************************************** - -void PipXtremeGadgetWidget::processStream() -{ - QMutexLocker locker_dev(&device_mutex); - QMutexLocker locker_inbuf(&device_input_buffer.mutex); - - if (!m_ioDevice) return; - if (!m_ioDevice->isOpen()) return; - - switch (m_stage) - { - case PIPX_IDLE: - QTimer::singleShot(RETRY_TIME, this, SLOT(processStream())); - break; - - case PIPX_REQ_DETAILS: - if (++m_stage_retries > MAX_RETRIES) - { - disconnectPort(true, false); - break; - } - sendRequestDetails(0); - QTimer::singleShot(RETRY_TIME, this, SLOT(processStream())); - break; - - case PIPX_REQ_SETTINGS: - if (++m_stage_retries > MAX_RETRIES) - { - disconnectPort(true, false); - break; - } - sendRequestSettings(pipx_config_details.serial_number); - QTimer::singleShot(RETRY_TIME, this, SLOT(processStream())); - break; - - case PIPX_REQ_STATE: - if (++m_stage_retries > MAX_RETRIES) - { - disconnectPort(true, false); - break; - } - sendRequestState(pipx_config_details.serial_number); - QTimer::singleShot(RETRY_TIME, this, SLOT(processStream())); - break; - - default: - m_stage_retries = 0; - m_stage = PIPX_IDLE; - QTimer::singleShot(RETRY_TIME, this, SLOT(processStream())); - break; - } -} - -// *************************************************************************************** - -void PipXtremeGadgetWidget::disconnectPort(bool enable_telemetry, bool lock_stuff) -{ // disconnect the comms port - - if (lock_stuff) - { - QMutexLocker locker_dev(&device_mutex); - QMutexLocker locker_inbuf(&device_input_buffer.mutex); - } - - m_stage_retries = 0; - m_stage = PIPX_IDLE; - - device_input_buffer.used = 0; - - memset(&pipx_config_details, 0, sizeof(pipx_config_details)); - memset(&pipx_config_settings, 0, sizeof(pipx_config_settings)); - - if (m_ioDevice) - { - m_ioDevice->close(); - disconnect(m_ioDevice, 0, 0, 0); - delete m_ioDevice; - m_ioDevice = NULL; - } - - m_widget->connectButton->setText("Connect"); - m_widget->comboBox_SerialBaudrate->setEnabled(true); - m_widget->comboBox_Ports->setEnabled(true); - m_widget->refreshPorts->setEnabled(true); - m_widget->pushButton_ScanSpectrum->setEnabled(false); - m_widget->pushButton_Save->setEnabled(false); - m_widget->pushButton_Import->setEnabled(false); - m_widget->pushButton_Export->setEnabled(false); - - m_widget->lineEdit_FirmwareVersion->setText(""); - m_widget->lineEdit_SerialNumber->setText(""); - m_widget->lineEdit_FrequencyBand->setText(""); - m_widget->lineEdit_MinFrequency->setText(""); - m_widget->lineEdit_MaxFrequency->setText(""); - m_widget->lineEdit_FrequencyStepSize->setText(""); - m_widget->lineEdit_LinkState->setText(""); - m_widget->widgetRSSI->setValue(m_widget->widgetRSSI->minimum()); - m_widget->label_RSSI->setText("RSSI"); - m_widget->lineEdit_RxAFC->setText(""); - m_widget->lineEdit_Retries->setText(""); - m_widget->lineEdit_PairedSerialNumber->setText(""); - m_widget->spinBox_FrequencyCalibration->setValue(0); - m_widget->doubleSpinBox_Frequency->setValue(0); - m_widget->lineEdit_AESKey->setText(""); - m_widget->checkBox_AESEnable->setChecked(false); - - if (enable_telemetry) - enableTelemetry(); -} - -void PipXtremeGadgetWidget::connectPort() -{ // connect the comms port - - disconnectPort(true); - - QMutexLocker locker_dev(&device_mutex); - - int device_idx = m_widget->comboBox_Ports->currentIndex(); - if (device_idx < 0) - return; - - QString device_str = m_widget->comboBox_Ports->currentText().trimmed(); - if (device_str.isEmpty()) - return; - - int type = NO_PORT; - if (device_str.toLower().startsWith("com: ")) - { - type = SERIAL_PORT; - device_str.remove(0, 5); - device_str = device_str.trimmed(); - } - else - if (device_str.toLower().startsWith("usb: ")) - { - type = USB_PORT; - device_str.remove(0, 5); - device_str = device_str.trimmed(); - } - -// type = m_widget->comboBox_Ports->itemData(device_idx).toInt(); - -// qDebug() << QString::number(type) << ": " << device_str; - - // Suspend GCS telemety & polling - disableTelemetry(); - - switch (type) - { - case SERIAL_PORT: // serial port - { - QString str = getSerialPortDevice(device_str); - if (str.isEmpty()) - break; - - int br_idx = m_widget->comboBox_SerialBaudrate->currentIndex(); - if (br_idx < 0) - break; - - int baudrate = m_widget->comboBox_SerialBaudrate->itemData(br_idx).toInt(); - - BaudRateType bdt = BAUD57600; - switch (baudrate) - { - case 1200: bdt = BAUD1200; break; - case 2400: bdt = BAUD2400; break; - case 4800: bdt = BAUD4800; break; - case 9600: bdt = BAUD9600; break; - case 19200: bdt = BAUD19200; break; - case 38400: bdt = BAUD38400; break; - case 57600: bdt = BAUD57600; break; - case 115200: bdt = BAUD115200; break; - case 128000: bdt = BAUD128000; break; - case 256000: bdt = BAUD256000; break; - #if (defined Q_OS_WIN) - case 230400: bdt = BAUD230400; break; - case 460800: bdt = BAUD460800; break; - case 921600: bdt = BAUD921600; break; - #endif - } - - PortSettings settings; - settings.BaudRate = bdt; - settings.DataBits = DATA_8; - settings.Parity = PAR_NONE; - settings.StopBits = STOP_1; - settings.FlowControl = FLOW_OFF; - settings.Timeout_Millisec = 1000; -// settings.setQueryMode(QextSerialBase::EventDriven); - -// QextSerialPort *serial_dev = new QextSerialPort(str, settings, QextSerialPort::Polling); -// QextSerialPort *serial_dev = new QextSerialPort(str, settings, QextSerialPort::EventDriven); - QextSerialPort *serial_dev = new QextSerialPort(str, settings); - if (!serial_dev) - break; - -// if (!serial_dev->open(QIODevice::ReadWrite | QIODevice::Unbuffered)) - if (!serial_dev->open(QIODevice::ReadWrite)) - { - delete serial_dev; - break; - } - - m_ioDevice = serial_dev; - break; - } - - case USB_PORT: // USB port - { - RawHID *usb_dev = new RawHID(device_str); - if (!usb_dev) - break; - -// if (!usb_dev->open(QIODevice::ReadWrite | QIODevice::Unbuffered)) - if (!usb_dev->open(QIODevice::ReadWrite)) - { - delete usb_dev; - break; - } - - m_ioDevice = usb_dev; - break; - } - - default: // unknown port type - break; - } - - if (!m_ioDevice) - { // failed to connect .. restore GCS telemetry and polling - enableTelemetry(); - } - else - { // connected OK - memset(&pipx_config_details, 0, sizeof(pipx_config_details)); - memset(&pipx_config_settings, 0, sizeof(pipx_config_settings)); - - m_widget->connectButton->setText("Disconnect"); - m_widget->comboBox_SerialBaudrate->setEnabled(false); - m_widget->comboBox_Ports->setEnabled(false); - m_widget->refreshPorts->setEnabled(false); - - m_ioDevice->setTextModeEnabled(false); - QTimer::singleShot(100, this, SLOT(processRxStream())); -// connect(m_ioDevice, SIGNAL(readyRead()), this, SLOT(processRxStream())); - - m_stage_retries = 0; - m_stage = PIPX_REQ_DETAILS; - QTimer::singleShot(100, this, SLOT(processStream())); - } -} - -// *************************************************************************************** - -void PipXtremeGadgetWidget::connectDisconnect() -{ - if (m_ioDevice) - disconnectPort(true); // disconnect - else - connectPort(); // connect -} - -// *************************************************************************************** - -void PipXtremeGadgetWidget::importSettings() -{ - QString filename = "pipx_" + QString::number(pipx_config_details.serial_number, 16).rightJustified(8, '0') + ".ini"; - - QFileDialog::Options options; - QString selectedFilter; - filename = QFileDialog::getOpenFileName(this, - tr("Load from PipX settings file"), - filename, - tr("PipX settings (*.ini)"), - &selectedFilter, - options - ).trimmed(); - if (filename.isEmpty()) - return; - - if (!QFileInfo(filename).isReadable()) - { - QMessageBox msgBox; - msgBox.setText(tr("Can't read file ") + QFileInfo(filename).absoluteFilePath()); - msgBox.exec(); - return; - } - - QSettings settings(filename, QSettings::IniFormat); - - uint32_t serial_number = settings.value("details/serial_number", 0).toUInt(); - if (serial_number && serial_number != pipx_config_details.serial_number) - { -// return; - } - - pipx_config_settings.mode = settings.value("settings/mode", 0).toUInt(); - pipx_config_settings.destination_id = settings.value("settings/paired_serial_number", 0).toUInt(); - pipx_config_settings.rf_xtal_cap = settings.value("settings/frequency_calibration", 0x7f).toUInt(); - pipx_config_settings.frequency_Hz = settings.value("settings/frequency", (pipx_config_details.min_frequency_Hz + pipx_config_details.max_frequency_Hz) / 2).toUInt(); - pipx_config_settings.max_rf_bandwidth = settings.value("settings/max_rf_bandwidth", 128000).toUInt(); - pipx_config_settings.max_tx_power = settings.value("settings/max_tx_power", 4).toUInt(); - pipx_config_settings.serial_baudrate = settings.value("settings/serial_baudrate", 57600).toUInt(); - pipx_config_settings.aes_enable = settings.value("settings/aes_enable", false).toBool(); - for (int i = 0; i < (int)sizeof(pipx_config_settings.aes_key); i++) - pipx_config_settings.aes_key[i] = settings.value("settings/aes_key_" + QString::number(i), 0).toUInt(); - pipx_config_settings.rts_time = settings.value("settings/ready_to_send_time", 10).toUInt(); - - m_widget->comboBox_Mode->setCurrentIndex(m_widget->comboBox_Mode->findData(pipx_config_settings.mode)); - m_widget->lineEdit_PairedSerialNumber->setText(QString::number(pipx_config_settings.destination_id, 16).toUpper()); - m_widget->spinBox_FrequencyCalibration->setValue(pipx_config_settings.rf_xtal_cap); - m_widget->doubleSpinBox_Frequency->setValue((double)pipx_config_settings.frequency_Hz / 1e6); - m_widget->comboBox_MaxRFBandwidth->setCurrentIndex(m_widget->comboBox_MaxRFBandwidth->findData(pipx_config_settings.max_rf_bandwidth)); - m_widget->comboBox_MaxRFTxPower->setCurrentIndex(m_widget->comboBox_MaxRFTxPower->findData(pipx_config_settings.max_tx_power)); - m_widget->comboBox_SerialPortSpeed->setCurrentIndex(m_widget->comboBox_SerialPortSpeed->findData(pipx_config_settings.serial_baudrate)); - m_widget->spinBox_RTSTime->setValue(pipx_config_settings.rts_time); - - QString key = ""; - for (int i = 0; i < (int)sizeof(pipx_config_settings.aes_key); i++) - key += QString::number(pipx_config_settings.aes_key[i], 16).rightJustified(2, '0'); - m_widget->lineEdit_AESKey->setText(key); - m_widget->checkBox_AESEnable->setChecked(pipx_config_settings.aes_enable); -} - -void PipXtremeGadgetWidget::exportSettings() -{ - QString filename = "pipx_" + QString::number(pipx_config_details.serial_number, 16).rightJustified(8, '0') + ".ini"; - - filename = QFileDialog::getSaveFileName(this, - tr("Save to PipX settings file"), - filename, - tr("PipX settings (*.ini)") - ).trimmed(); - if (filename.isEmpty()) - return; -/* - if (QFileInfo(filename).exists()) - { - QMessageBox msgBox; - msgBox.setText(tr("File already exists.")); - msgBox.setInformativeText(tr("Do you want to overwrite the existing file?")); - msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); - msgBox.setDefaultButton(QMessageBox::Ok); - if (msgBox.exec() == QMessageBox::Ok) - QFileInfo(filename).absoluteDir().remove(QFileInfo(filename).fileName()); - else - return; - } -*/ QDir dir = QFileInfo(filename).absoluteDir(); - if (!dir.exists()) - { - QMessageBox msgBox; - msgBox.setText(tr("Can't write file ") + QFileInfo(filename).absoluteFilePath() + " since directory " + dir.absolutePath() + " doesn't exist!"); - msgBox.exec(); - return; - } - - QSettings settings(filename, QSettings::IniFormat); - settings.setValue("details/serial_number", pipx_config_details.serial_number); - settings.setValue("details/min_frequency", pipx_config_details.min_frequency_Hz); - settings.setValue("details/max_frequency", pipx_config_details.max_frequency_Hz); - settings.setValue("details/frequency_band", pipx_config_details.frequency_band); - settings.setValue("settings/mode", pipx_config_settings.mode); - settings.setValue("settings/paired_serial_number", pipx_config_settings.destination_id); - settings.setValue("settings/frequency_calibration", pipx_config_settings.rf_xtal_cap); - settings.setValue("settings/frequency", pipx_config_settings.frequency_Hz); - settings.setValue("settings/max_rf_bandwidth", pipx_config_settings.max_rf_bandwidth); - settings.setValue("settings/max_tx_power", pipx_config_settings.max_tx_power); - settings.setValue("settings/serial_baudrate", pipx_config_settings.serial_baudrate); - settings.setValue("settings/aes_enable", pipx_config_settings.aes_enable); - settings.setValue("settings/ready_to_send_time", pipx_config_settings.rts_time); - for (int i = 0; i < (int)sizeof(pipx_config_settings.aes_key); i++) - settings.setValue("settings/aes_key_" + QString::number(i), pipx_config_settings.aes_key[i]); -} - -// *************************************************************************************** -// Shows a message box with an error string. - -void PipXtremeGadgetWidget::error(QString errorString, int errorNumber) -{ - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Critical); - msgBox.setText(errorString + " [" + QString::number(errorNumber) + "]"); - msgBox.exec(); -} - -// *************************************************************************************** diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetwidget.h b/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetwidget.h deleted file mode 100644 index 25b0e7ccb..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/pipxtremegadgetwidget.h +++ /dev/null @@ -1,205 +0,0 @@ -/** - ****************************************************************************** - * - * @file pipxtremegadgetwidget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @{ - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIPXTREMEGADGETWIDGET_H -#define PIPXTREMEGADGETWIDGET_H - -#include "ui_pipxtreme.h" - -#include -#include - -#include "uavtalk/telemetrymanager.h" -#include "extensionsystem/pluginmanager.h" -#include "uavobjects/uavobjectmanager.h" -#include "uavobjects/uavobject.h" - -#include "coreplugin/icore.h" -#include "coreplugin/connectionmanager.h" - -#include "rawhid/rawhidplugin.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "widgetbar.h" - -// ************************* -// pipx config comms packets - -#pragma pack(push, 1) - -typedef struct -{ - uint32_t marker; - uint32_t serial_number; - uint8_t type; - uint8_t spare; - uint16_t data_size; - uint32_t header_crc; - uint32_t data_crc; -// uint8_t data[0]; -} t_pipx_config_header; - -typedef struct -{ - uint8_t major_version; - uint8_t minor_version; - uint32_t serial_number; - uint32_t min_frequency_Hz; - uint32_t max_frequency_Hz; - uint8_t frequency_band; - float frequency_step_size; -} t_pipx_config_details; - -typedef struct -{ - uint8_t mode; - uint8_t link_state; - int16_t rssi; - int32_t afc; - uint16_t retries; -} t_pipx_config_state; - -typedef struct -{ - uint8_t mode; - uint32_t serial_baudrate; - uint32_t destination_id; - uint32_t frequency_Hz; - uint32_t max_rf_bandwidth; - uint8_t max_tx_power; - uint8_t rf_xtal_cap; - bool aes_enable; - uint8_t aes_key[16]; - uint8_t rts_time; - uint8_t spare[16]; -} t_pipx_config_settings; - -typedef struct -{ - uint32_t start_frequency; - uint16_t frequency_step_size; - uint16_t magnitudes; -// int8_t magnitude[0]; -} t_pipx_config_spectrum; - -#pragma pack(pop) - -// ************************* - -typedef struct -{ - quint8 *buffer; - int size; - int used; - QMutex mutex; -} t_buffer; - -// ************************* - -class PipXtremeGadgetWidget : public QWidget -{ - Q_OBJECT - -public: - PipXtremeGadgetWidget(QWidget *parent = 0); - ~PipXtremeGadgetWidget(); - -public slots: - void onTelemetryStart(); - void onTelemetryStop(); - void onTelemetryConnect(); - void onTelemetryDisconnect(); - - void onComboBoxPorts_currentIndexChanged(int index); - -protected: - void resizeEvent(QResizeEvent *event); - -private: - typedef enum { PIPX_IDLE, PIPX_REQ_DETAILS, PIPX_REQ_SETTINGS, PIPX_REQ_STATE} PipXStage; - - Ui_PipXtremeWidget *m_widget; - - QIODevice *m_ioDevice; - QMutex device_mutex; - - t_buffer device_input_buffer; - - PipXStage m_stage; - int m_stage_retries; - -// QVector buffer; - - t_pipx_config_details pipx_config_details; - t_pipx_config_settings pipx_config_settings; - t_pipx_config_state pipx_config_state; - t_pipx_config_spectrum pipx_config_spectrum; - - uint32_t updateCRC32(uint32_t crc, uint8_t b); - uint32_t updateCRC32Data(uint32_t crc, void *data, int len); - void makeCRC_Table32(); - - QString getSerialPortDevice(const QString &friendName); - - void disableTelemetry(); - void enableTelemetry(); - - void sendRequestDetails(uint32_t serial_number); - void sendRequestSettings(uint32_t serial_number); - void sendRequestState(uint32_t serial_number); - void sendSettings(uint32_t serial_number, t_pipx_config_settings *settings); - - void processRxBuffer(); - void processRxPacket(quint8 *packet, int packet_size); - - void disconnectPort(bool enable_telemetry, bool lock_stuff = true); - void connectPort(); - -private slots: - void importSettings(); - void exportSettings(); - void connectDisconnect(); - void error(QString errorString, int errorNumber); - void getPorts(); - void randomiseAESKey(); - void scanSpectrum(); - void saveToFlash(); - void textChangedAESKey(const QString &text); - void processStream(); - void processRxStream(); - -}; - -#endif diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/widgetbar.cpp b/ground/openpilotgcs/src/plugins/pipxtreme/widgetbar.cpp deleted file mode 100644 index cebb68c01..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/widgetbar.cpp +++ /dev/null @@ -1,157 +0,0 @@ -/** - ****************************************************************************** - * - * @file widgetbar.cpp - * @author Cathy Moss Copyright (C) 2011. - * Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup ConfigPlugin Configuration Plugin - * @{ - * @brief A bar display widget - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - #include - - #include "widgetbar.h" - - WidgetBar::WidgetBar(QWidget *parent) - : QWidget(parent) - { - m_maximum = 0; - m_minimum = -120; - m_value = -60; - -// m_orientation = Qt::Vertical; - m_orientation = Qt::Horizontal; - - setBackgroundRole(QPalette::Base); - setAutoFillBackground(true); - } - - QSize WidgetBar::minimumSizeHint() const - { - return QSize(8, 8); - } - -// QSize WidgetBar::sizeHint() const -// { -// return QSize(200, 400); -// } - - void WidgetBar::setMaximum(int value) - { - m_maximum = value; - update(); - } - - void WidgetBar::setMinimum(int value) - { - m_minimum = value; - update(); - } - - void WidgetBar::setValue(int value) - { - if (value < m_minimum) value = m_minimum; - else - if (value > m_maximum) value = m_maximum; - - m_value = value; - update(); - } - -void WidgetBar::setOrientation(Qt::Orientation orientation) -{ - m_orientation = orientation; - update(); -} - -void WidgetBar::paintEvent(QPaintEvent * /* event */) -{ - QPainter painter(this); - painter.setRenderHint(QPainter::Antialiasing, false); - - int range = abs(m_maximum - m_minimum); - if (range < 1) range = 1; - - int value = m_value; - if (value < m_minimum) value = m_minimum; - else - if (value > m_maximum) value = m_maximum; - - float level = (float)(value - m_minimum) / range; // 0.0 to +1.0 - - int length = 0; - QRect rect; - - switch (m_orientation) - { - case Qt::Horizontal: - { - length = (int)((width() - 5) * level + 0.5f); - rect.setLeft(2); - rect.setTop(2); - rect.setWidth(length); - rect.setHeight(height() - 5); - } - break; - - case Qt::Vertical: - { - length = (int)((height() - 5) * level + 0.5f); - rect.setLeft(2); - rect.setTop(height() - 3 - length); - rect.setWidth(width() - 5); - rect.setHeight(length); - } - break; - } - - // background - painter.setPen(QColor(160, 160, 160)); - painter.setBrush(QColor(255, 255, 255)); -// painter.setPen(QColor(80, 80, 80)); -// painter.setPen(QColor(160, 160, 160)); -// painter.setBrush(QColor(160, 160, 160)); - painter.drawRect(QRect(0, 0, width() - 1, height() - 1)); - - if ((m_maximum - m_minimum) > 0) - { - // solid bar - painter.setPen(QColor(128, 128, 255)); - painter.setBrush(QColor(128, 128, 255)); - painter.drawRoundRect(rect, 3, 3); -/* - // colourful bar - for (int i = 0; i < length; i++) - { - if (!(i & 1)) - painter.setPen(QColor(0, 0, 0)); // black - else - painter.setPen(QColor(128, 255, 128)); // green -// painter.setPen(QColor(128, 128, 255)); // blue - - if (m_orientation == Qt::Horizontal) - painter.drawLine(rect.left() + i, rect.top(), rect.left() + i, rect.bottom() + 1); // horizontal bar - else - painter.drawLine(rect.left(), rect.bottom() + 1 - i, rect.right() + 1, rect.bottom() + 1 - i); // vertical bar - } -*/ - } -} diff --git a/ground/openpilotgcs/src/plugins/pipxtreme/widgetbar.h b/ground/openpilotgcs/src/plugins/pipxtreme/widgetbar.h deleted file mode 100644 index 22e84b4d2..000000000 --- a/ground/openpilotgcs/src/plugins/pipxtreme/widgetbar.h +++ /dev/null @@ -1,77 +0,0 @@ -/** - ****************************************************************************** - * - * @file widgetbar.h - * @author Cathy Moss Copyright (C) 2011. - * Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup ConfigPlugin Configuration Plugin - * @{ - * @brief A bar display widget - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef WIDGETBAR_H -#define WIDGETBAR_H - -#include -#include -#include -#include - -QT_MODULE(Gui) - -class WidgetBar : public QWidget -{ - Q_OBJECT - - Q_PROPERTY(int maximum READ maximum WRITE setMaximum) - Q_PROPERTY(int minimum READ minimum WRITE setMinimum) - Q_PROPERTY(int value READ value WRITE setValue) - - Q_PROPERTY(Qt::Orientation orientation READ orientation WRITE setOrientation) - -public: - WidgetBar(QWidget *parent = 0); - - QSize minimumSizeHint() const; -// QSize sizeHint() const; - - void setMaximum(int value); - void setMinimum(int value); - void setValue(int value); - - int maximum() { return m_maximum; } - int minimum() { return m_minimum; } - int value() { return m_value; } - - Qt::Orientation orientation() const { return m_orientation; } - void setOrientation(Qt::Orientation orientation); - -protected: - void paintEvent(QPaintEvent *event); - -private: - int m_maximum; - int m_minimum; - int m_value; - - Qt::Orientation m_orientation; -}; - -#endif diff --git a/ground/openpilotgcs/src/plugins/plugins.pro b/ground/openpilotgcs/src/plugins/plugins.pro index 174ceba17..154335e3a 100644 --- a/ground/openpilotgcs/src/plugins/plugins.pro +++ b/ground/openpilotgcs/src/plugins/plugins.pro @@ -147,6 +147,13 @@ plugin_hitlnew.depends += plugin_uavobjects plugin_hitlnew.depends += plugin_uavtalk SUBDIRS += plugin_hitlnew +#HITLNEW Simulation gadget v2 +plugin_hitl_v2.subdir = hitlv2 +plugin_hitl_v2.depends = plugin_coreplugin +plugin_hitl_v2.depends += plugin_uavobjects +plugin_hitl_v2.depends += plugin_uavtalk +SUBDIRS += plugin_hitl_v2 + # Export and Import GCS Configuration plugin_importexport.subdir = importexport plugin_importexport.depends = plugin_coreplugin @@ -172,13 +179,6 @@ SUBDIRS += plugin_gcscontrol #plugin_antennatrack.depends += plugin_uavtalk #SUBDIRS += plugin_antennatrack -#PipXtreme gadget -plugin_pipxtreme.subdir = pipxtreme -plugin_pipxtreme.depends = plugin_coreplugin -plugin_pipxtreme.depends += plugin_uavobjects -plugin_pipxtreme.depends += plugin_rawhid -SUBDIRS += plugin_pipxtreme - #Scope OpenGL Gadget #plugin_scopeogl.subdir = scopeogl #plugin_scopeogl.depends = plugin_coreplugin diff --git a/ground/openpilotgcs/src/plugins/scope/plotdata.cpp b/ground/openpilotgcs/src/plugins/scope/plotdata.cpp index e05bf7a1b..154a9aa06 100644 --- a/ground/openpilotgcs/src/plugins/scope/plotdata.cpp +++ b/ground/openpilotgcs/src/plugins/scope/plotdata.cpp @@ -53,8 +53,9 @@ PlotData::PlotData(QString p_uavObject, QString p_uavField) curve = 0; scalePower = 0; - interpolationSamples = 1; - interpolationSum = 0.0f; + meanSamples = 1; + meanSum = 0.0f; +// mathFunction=0; correctionSum = 0.0f; correctionCount = 0; yMinimum = 0; @@ -87,7 +88,7 @@ PlotData::~PlotData() } -bool SequencialPlotData::append(UAVObject* obj) +bool SequentialPlotData::append(UAVObject* obj) { if (uavObject == obj->getName()) { @@ -96,28 +97,50 @@ bool SequencialPlotData::append(UAVObject* obj) if (field) { - //Shift data forward and put the new value at the front - - // calculate interpolated (smoothed) value double currentValue = valueAsDouble(obj, field) * pow(10, scalePower); - yDataHistory->append( currentValue ); - interpolationSum += currentValue; - if(yDataHistory->size() > interpolationSamples) { - interpolationSum -= yDataHistory->first(); - yDataHistory->pop_front(); + + //Compute boxcar average + if (mathFunction == "Boxcar average" || mathFunction == "Standard deviation"){ + //Put the new value at the front + yDataHistory->append( currentValue ); + + // calculate average value + meanSum += currentValue; + if(yDataHistory->size() > meanSamples) { + meanSum -= yDataHistory->first(); + yDataHistory->pop_front(); + } + + // make sure to correct the sum every meanSamples steps to prevent it + // from running away due to floating point rounding errors + correctionSum+=currentValue; + if (++correctionCount >= meanSamples) { + meanSum = correctionSum; + correctionSum = 0.0f; + correctionCount = 0; + } + + double boxcarAvg=meanSum/yDataHistory->size(); + + if ( mathFunction == "Standard deviation" ){ + //Calculate square of sample standard deviation, with Bessel's correction + double stdSum=0; + for (int i=0; i < yDataHistory->size(); i++){ + stdSum+= pow(yDataHistory->at(i)- boxcarAvg,2)/(meanSamples-1); + } + yData->append(sqrt(stdSum)); + } + else { + yData->append(boxcarAvg); + } } - // make sure to correct the sum every interpolationSamples steps to prevent it - // from running away due to flouting point rounding errors - correctionSum += currentValue; - if (++correctionCount >= interpolationSamples) { - interpolationSum = correctionSum; - correctionSum = 0.0f; - correctionCount = 0; + else{ + yData->append( currentValue ); } - yData->append(interpolationSum/yDataHistory->size()); - if (yData->size() > m_xWindowSize) { + + if (yData->size() > m_xWindowSize) { //If new data overflows the window, remove old data... yData->pop_front(); - } else + } else //...otherwise, add a new y point at position xData xData->insert(xData->size(), xData->size()); //notify the gui of changes in the data @@ -137,30 +160,49 @@ bool ChronoPlotData::append(UAVObject* obj) //qDebug() << "uavObject: " << uavObject << ", uavField: " << uavField; if (field) { - //Put the new value at the front - QDateTime NOW = QDateTime::currentDateTime(); - - // calculate interpolated (smoothed) value + QDateTime NOW = QDateTime::currentDateTime(); //THINK ABOUT REIMPLEMENTING THIS TO SHOW UAVO TIME, NOT SYSTEM TIME double currentValue = valueAsDouble(obj, field) * pow(10, scalePower); - yDataHistory->append( currentValue ); - interpolationSum += currentValue; - if(yDataHistory->size() > interpolationSamples) { - interpolationSum -= yDataHistory->first(); - yDataHistory->pop_front(); + + //Compute boxcar average + if (meanSamples > 1){ + //Put the new value at the front + yDataHistory->append( currentValue ); + + // calculate average value + meanSum += currentValue; + if(yDataHistory->size() > meanSamples) { + meanSum -= yDataHistory->first(); + yDataHistory->pop_front(); + } + // make sure to correct the sum every meanSamples steps to prevent it + // from running away due to floating point rounding errors + correctionSum+=currentValue; + if (++correctionCount >= meanSamples) { + meanSum = correctionSum; + correctionSum = 0.0f; + correctionCount = 0; + } + + double boxcarAvg=meanSum/yDataHistory->size(); +//qDebug()<size(); i++){ + stdSum+= pow(yDataHistory->at(i)- boxcarAvg,2)/(meanSamples-1); + } + yData->append(sqrt(stdSum)); + } + else { + yData->append(boxcarAvg); + } } - // make sure to correct the sum every interpolationSamples steps to prevent it - // from running away due to flouting point rounding errors - correctionSum += currentValue; - if (++correctionCount >= interpolationSamples) { - interpolationSum = correctionSum; - correctionSum = 0.0f; - correctionCount = 0; + else{ + yData->append( currentValue ); } double valueX = NOW.toTime_t() + NOW.time().msec() / 1000.0; - double valueY = interpolationSum/yDataHistory->size(); xData->append(valueX); - yData->append(valueY); //qDebug() << "Data " << uavObject << "." << field->getName() << " X,Y:" << valueX << "," << valueY; diff --git a/ground/openpilotgcs/src/plugins/scope/plotdata.h b/ground/openpilotgcs/src/plugins/scope/plotdata.h index a547f2b91..204f1a7bd 100644 --- a/ground/openpilotgcs/src/plugins/scope/plotdata.h +++ b/ground/openpilotgcs/src/plugins/scope/plotdata.h @@ -29,11 +29,6 @@ #define PLOTDATA_H #include "uavobject.h" -#include "baroaltitude.h" -#include "positionactual.h" -#include "attituderaw.h" -#include "manualcontrolcommand.h" - #include "qwt/src/qwt.h" #include "qwt/src/qwt_plot.h" @@ -49,7 +44,7 @@ \brief Defines the different type of plots. */ enum PlotType { - SequencialPlot, + SequentialPlot, ChronoPlot, UAVObjectPlot, @@ -72,8 +67,9 @@ public: QString uavSubField; bool haveSubField; int scalePower; //This is the power to which each value must be raised - int interpolationSamples; - double interpolationSum; + int meanSamples; + double meanSum; + QString mathFunction; double correctionSum; int correctionCount; double yMinimum; @@ -98,16 +94,16 @@ signals: }; /*! - \brief The sequencial plot have a fixed size buffer of data. All the curves in one plot + \brief The sequential plot have a fixed size buffer of data. All the curves in one plot have the same size buffer. */ -class SequencialPlotData : public PlotData +class SequentialPlotData : public PlotData { Q_OBJECT public: - SequencialPlotData(QString uavObject, QString uavField) + SequentialPlotData(QString uavObject, QString uavField) : PlotData(uavObject, uavField) {} - ~SequencialPlotData() {} + ~SequentialPlotData() {} /*! \brief Append new data to the plot @@ -118,7 +114,7 @@ public: \brief The type of plot */ virtual PlotType plotType() { - return SequencialPlot; + return SequentialPlot; } /*! diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp index b4b1f24fa..d9b33b185 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp @@ -49,8 +49,8 @@ void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config) widget->setXWindowSize(sgConfig->dataSize()); widget->setRefreshInterval(sgConfig->refreshInterval()); - if(sgConfig->plotType() == SequencialPlot ) - widget->setupSequencialPlot(); + if(sgConfig->plotType() == SequentialPlot ) + widget->setupSequentialPlot(); else if(sgConfig->plotType() == ChronoPlot) widget->setupChronoPlot(); // else if(sgConfig->plotType() == UAVObjectPlot) @@ -61,14 +61,16 @@ void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config) QString uavObject = plotCurveConfig->uavObject; QString uavField = plotCurveConfig->uavField; int scale = plotCurveConfig->yScalePower; - int interpolation = plotCurveConfig->yInterpolationSamples; + int mean = plotCurveConfig->yMeanSamples; + QString mathFunction = plotCurveConfig->mathFunction; QRgb color = plotCurveConfig->color; widget->addCurvePlot( uavObject, uavField, scale, - interpolation, + mean, + mathFunction, QPen( QBrush(QColor(color),Qt::SolidPattern), // (qreal)2, (qreal)1, diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp index 3228497f3..57b1c134f 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp @@ -31,7 +31,8 @@ ScopeGadgetConfiguration::ScopeGadgetConfiguration(QString classId, QSettings* q IUAVGadgetConfiguration(classId, parent), m_plotType((int)ChronoPlot), m_dataSize(60), - m_refreshInterval(1000) + m_refreshInterval(1000), + m_mathFunctionType(0) { uint currentStreamVersion = 0; int plotCurveCount = 0; @@ -65,8 +66,11 @@ ScopeGadgetConfiguration::ScopeGadgetConfiguration(QString classId, QSettings* q color = qSettings->value("color").value(); plotCurveConf->color = color; plotCurveConf->yScalePower = qSettings->value("yScalePower").toInt(); - plotCurveConf->yInterpolationSamples = qSettings->value("yInterpolationSamples").toInt(); - if (!plotCurveConf->yInterpolationSamples) plotCurveConf->yInterpolationSamples = 1; // fallback for backward compatibility with earlier versions + plotCurveConf->mathFunction = qSettings->value("mathFunction").toString(); + plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples").toInt(); + + if (!plotCurveConf->yMeanSamples) plotCurveConf->yMeanSamples = 1; // fallback for backward compatibility with earlier versions //IS THIS STILL NECESSARY? + plotCurveConf->yMinimum = qSettings->value("yMinimum").toDouble(); plotCurveConf->yMaximum = qSettings->value("yMaximum").toDouble(); @@ -105,8 +109,9 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone() int plotDatasLoadIndex = 0; ScopeGadgetConfiguration *m = new ScopeGadgetConfiguration(this->classId()); - m->setPlotType(m_plotType); + m->setPlotType( m_plotType); m->setDataSize( m_dataSize); + m->setMathFunctionType( m_mathFunctionType); m->setRefreashInterval( m_refreshInterval); plotCurveCount = m_PlotCurveConfigs.size(); @@ -120,7 +125,9 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone() newPlotCurveConf->uavField = currentPlotCurveConf->uavField; newPlotCurveConf->color = currentPlotCurveConf->color; newPlotCurveConf->yScalePower = currentPlotCurveConf->yScalePower; - newPlotCurveConf->yInterpolationSamples = currentPlotCurveConf->yInterpolationSamples; + newPlotCurveConf->yMeanSamples = currentPlotCurveConf->yMeanSamples; + newPlotCurveConf->mathFunction = currentPlotCurveConf->mathFunction; + newPlotCurveConf->yMinimum = currentPlotCurveConf->yMinimum; newPlotCurveConf->yMaximum = currentPlotCurveConf->yMaximum; @@ -136,8 +143,9 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone() return m; } + /** - * Saves a configuration. + * Saves a configuration. //REDEFINES saveConfig CHILD BEHAVIOR? * */ void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const { @@ -159,8 +167,9 @@ void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const { qSettings->setValue("uavObject", plotCurveConf->uavObject); qSettings->setValue("uavField", plotCurveConf->uavField); qSettings->setValue("color", plotCurveConf->color); + qSettings->setValue("mathFunction", plotCurveConf->mathFunction); qSettings->setValue("yScalePower", plotCurveConf->yScalePower); - qSettings->setValue("yInterpolationSamples", plotCurveConf->yInterpolationSamples); + qSettings->setValue("yMeanSamples", plotCurveConf->yMeanSamples); qSettings->setValue("yMinimum", plotCurveConf->yMinimum); qSettings->setValue("yMaximum", plotCurveConf->yMaximum); diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h index 570ebe1f9..5fcb488e2 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h @@ -41,7 +41,8 @@ struct PlotCurveConfiguration QString uavField; int yScalePower; //This is the power to which each value must be raised QRgb color; - int yInterpolationSamples; + int yMeanSamples; + QString mathFunction; double yMinimum; double yMaximum; }; @@ -56,6 +57,7 @@ public: //configuration setter functions void setPlotType(int value){m_plotType = value;} + void setMathFunctionType(int value){m_mathFunctionType = value;} void setDataSize(int value){m_dataSize = value;} void setRefreashInterval(int value){m_refreshInterval = value;} void addPlotCurveConfig(PlotCurveConfiguration* value){m_PlotCurveConfigs.append(value);} @@ -64,11 +66,12 @@ public: //configurations getter functions int plotType(){return m_plotType;} + int mathFunctionType(){return m_mathFunctionType;} int dataSize(){return m_dataSize;} int refreshInterval(){return m_refreshInterval;} QList plotCurveConfigs(){return m_PlotCurveConfigs;} - void saveConfig(QSettings* settings) const; + void saveConfig(QSettings* settings) const; //THIS SEEMS TO BE UNUSED IUAVGadgetConfiguration *clone(); bool getLoggingEnabled(){return m_LoggingEnabled;}; @@ -84,6 +87,7 @@ private: int m_plotType; //The type of the plot int m_dataSize; //The size of the data buffer to render in the curve plot int m_refreshInterval; //The interval to replot the curve widget. The data buffer is refresh as the data comes in. + int m_mathFunctionType; //The type of math function to be used in the scope analysis QList m_PlotCurveConfigs; void clearPlotData(); diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp index 8489811a5..06111931f 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp @@ -53,7 +53,7 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent) //main layout options_page->setupUi(optionsPageWidget); - options_page->cmbPlotType->addItem("Sequencial Plot",""); + options_page->cmbPlotType->addItem("Sequential Plot",""); options_page->cmbPlotType->addItem("Chronological Plot",""); // Fills the combo boxes for the UAVObjects @@ -69,29 +69,34 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent) //Connect signals to slots cmbUAVObjects.currentIndexChanged connect(options_page->cmbUAVObjects, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_cmbUAVObjects_currentIndexChanged(QString))); + options_page->mathFunctionComboBox->addItem("None"); + options_page->mathFunctionComboBox->addItem("Boxcar average"); + options_page->mathFunctionComboBox->addItem("Standard deviation"); + if(options_page->cmbUAVObjects->currentIndex() >= 0) on_cmbUAVObjects_currentIndexChanged(options_page->cmbUAVObjects->currentText()); - options_page->cmbScale->addItem("E-9", -9); - options_page->cmbScale->addItem("E-6", -6); - options_page->cmbScale->addItem("E-5",-5); - options_page->cmbScale->addItem("E-4",-4); - options_page->cmbScale->addItem("E-3",-3); - options_page->cmbScale->addItem("E-2",-2); - options_page->cmbScale->addItem("E-1",-1); - options_page->cmbScale->addItem("E0",0); - options_page->cmbScale->addItem("E1",1); - options_page->cmbScale->addItem("E2",2); - options_page->cmbScale->addItem("E3",3); - options_page->cmbScale->addItem("E4",4); - options_page->cmbScale->addItem("E5",5); - options_page->cmbScale->addItem("E6",6); - options_page->cmbScale->addItem("E9",9); - options_page->cmbScale->addItem("E12",12); + options_page->cmbScale->addItem("10^-9", -9); + options_page->cmbScale->addItem("10^-6", -6); + options_page->cmbScale->addItem("10^-5",-5); + options_page->cmbScale->addItem("10^-4",-4); + options_page->cmbScale->addItem("10^-3",-3); + options_page->cmbScale->addItem("10^-2",-2); + options_page->cmbScale->addItem("10^-1",-1); + options_page->cmbScale->addItem("1",0); + options_page->cmbScale->addItem("10^1",1); + options_page->cmbScale->addItem("10^2",2); + options_page->cmbScale->addItem("10^3",3); + options_page->cmbScale->addItem("10^4",4); + options_page->cmbScale->addItem("10^5",5); + options_page->cmbScale->addItem("10^6",6); + options_page->cmbScale->addItem("10^9",9); + options_page->cmbScale->addItem("10^12",12); options_page->cmbScale->setCurrentIndex(7); //Set widget values from settings options_page->cmbPlotType->setCurrentIndex(m_config->plotType()); + options_page->mathFunctionComboBox->setCurrentIndex(m_config->mathFunctionType()); options_page->spnDataSize->setValue(m_config->dataSize()); options_page->spnRefreshInterval->setValue(m_config->refreshInterval()); @@ -101,10 +106,11 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent) QString uavObject = plotData->uavObject; QString uavField = plotData->uavField; int scale = plotData->yScalePower; - int interpolation = plotData->yInterpolationSamples; + int mean = plotData->yMeanSamples; + QString mathFunction = plotData->mathFunction; QVariant varColor = plotData->color; - addPlotCurveConfig(uavObject,uavField,scale,interpolation,varColor); + addPlotCurveConfig(uavObject,uavField,scale,mean,mathFunction,varColor); } if(m_config->plotCurveConfigs().count() > 0) @@ -114,6 +120,7 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent) connect(options_page->btnRemoveCurve, SIGNAL(clicked()), this, SLOT(on_btnRemoveCurve_clicked())); connect(options_page->lstCurves, SIGNAL(currentRowChanged(int)), this, SLOT(on_lstCurves_currentRowChanged(int))); connect(options_page->btnColor, SIGNAL(clicked()), this, SLOT(on_btnColor_clicked())); + connect(options_page->mathFunctionComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(on_mathFunctionComboBox_currentIndexChanged(int))); connect(options_page->spnRefreshInterval, SIGNAL(valueChanged(int )), this, SLOT(on_spnRefreshInterval_valueChanged(int))); setYAxisWidgetFromPlotCurve(); @@ -127,11 +134,47 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent) connect(options_page->LoggingEnable, SIGNAL(clicked()), this, SLOT(on_loggingEnable_clicked())); on_loggingEnable_clicked(); + //Disable mouse wheel events + foreach( QSpinBox * sp, findChildren() ) { + sp->installEventFilter( this ); + } + foreach( QDoubleSpinBox * sp, findChildren() ) { + sp->installEventFilter( this ); + } + foreach( QSlider * sp, findChildren() ) { + sp->installEventFilter( this ); + } + foreach( QComboBox * sp, findChildren() ) { + sp->installEventFilter( this ); + } return optionsPageWidget; } +bool ScopeGadgetOptionsPage::eventFilter( QObject * obj, QEvent * evt ) { + //Filter all wheel events, and ignore them + if ( evt->type() == QEvent::Wheel && + (qobject_cast( obj ) || + qobject_cast( obj ) || + qobject_cast( obj ) )) + { + evt->ignore(); + return true; + } + return ScopeGadgetOptionsPage::eventFilter( obj, evt ); +} + +void ScopeGadgetOptionsPage::on_mathFunctionComboBox_currentIndexChanged(int currentIndex){ + if (currentIndex > 0){ + options_page->spnMeanSamples->setEnabled(true); + } + else{ + options_page->spnMeanSamples->setEnabled(false); + } + +} + void ScopeGadgetOptionsPage::on_btnColor_clicked() { QColor color = QColorDialog::getColor( QColor(options_page->btnColor->text())); @@ -152,6 +195,7 @@ void ScopeGadgetOptionsPage::setYAxisWidgetFromPlotCurve() if(listItem == 0) return; + //WHAT IS UserRole DOING? int currentIndex = options_page->cmbUAVObjects->findText( listItem->data(Qt::UserRole + 0).toString()); options_page->cmbUAVObjects->setCurrentIndex(currentIndex); @@ -166,9 +210,13 @@ void ScopeGadgetOptionsPage::setYAxisWidgetFromPlotCurve() setButtonColor(QColor((QRgb)rgb)); - int interpolation = listItem->data(Qt::UserRole + 4).toInt(&parseOK); - if(!parseOK) interpolation = 1; - options_page->spnInterpolationSamples->setValue(interpolation); + int mean = listItem->data(Qt::UserRole + 4).toInt(&parseOK); + if(!parseOK) mean = 1; + options_page->spnMeanSamples->setValue(mean); + + currentIndex = options_page->mathFunctionComboBox->findText( listItem->data(Qt::UserRole + 5).toString()); + options_page->mathFunctionComboBox->setCurrentIndex(currentIndex); + } void ScopeGadgetOptionsPage::setButtonColor(const QColor &color) @@ -221,6 +269,7 @@ void ScopeGadgetOptionsPage::apply() //Apply configuration changes m_config->setPlotType(options_page->cmbPlotType->currentIndex()); + m_config->setMathFunctionType(options_page->mathFunctionComboBox->currentIndex()); m_config->setDataSize(options_page->spnDataSize->value()); m_config->setRefreashInterval(options_page->spnRefreshInterval->value()); @@ -241,10 +290,13 @@ void ScopeGadgetOptionsPage::apply() newPlotCurveConfigs->color = QColor(Qt::black).rgb(); else newPlotCurveConfigs->color = (QRgb)rgb; - - newPlotCurveConfigs->yInterpolationSamples = listItem->data(Qt::UserRole + 4).toInt(&parseOK); + + newPlotCurveConfigs->yMeanSamples = listItem->data(Qt::UserRole + 4).toInt(&parseOK); if(!parseOK) - newPlotCurveConfigs->yInterpolationSamples = 1; + newPlotCurveConfigs->yMeanSamples = 1; + + newPlotCurveConfigs->mathFunction = listItem->data(Qt::UserRole + 5).toString(); + plotCurveConfigs.append(newPlotCurveConfigs); } @@ -271,7 +323,9 @@ void ScopeGadgetOptionsPage::on_btnAddCurve_clicked() if(!parseOK) scale = 0; - int interpolation = options_page->spnInterpolationSamples->value(); + int mean = options_page->spnMeanSamples->value(); + QString mathFunction = options_page->mathFunctionComboBox->currentText(); + QVariant varColor = (int)QColor(options_page->btnColor->text()).rgb(); @@ -281,27 +335,27 @@ void ScopeGadgetOptionsPage::on_btnAddCurve_clicked() options_page->lstCurves->currentItem()->text() == uavObject + "." + uavField) { QListWidgetItem *listWidgetItem = options_page->lstCurves->currentItem(); - setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,interpolation,varColor); + setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,mean,mathFunction,varColor); }else { - addPlotCurveConfig(uavObject,uavField,scale,interpolation,varColor); + addPlotCurveConfig(uavObject,uavField,scale,mean,mathFunction,varColor); options_page->lstCurves->setCurrentRow(options_page->lstCurves->count() - 1); } } -void ScopeGadgetOptionsPage::addPlotCurveConfig(QString uavObject, QString uavField, int scale, int interpolation, QVariant varColor) +void ScopeGadgetOptionsPage::addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor) { //Add a new curve config to the list QString listItemDisplayText = uavObject + "." + uavField; options_page->lstCurves->addItem(listItemDisplayText); QListWidgetItem *listWidgetItem = options_page->lstCurves->item(options_page->lstCurves->count() - 1); - setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,interpolation,varColor); + setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,mean,mathFunction,varColor); } -void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetItem,QString uavObject, QString uavField, int scale, int interpolation, QVariant varColor) +void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetItem,QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor) { bool parseOK = false; @@ -317,7 +371,8 @@ void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetI listWidgetItem->setData(Qt::UserRole + 1,QVariant(uavField)); listWidgetItem->setData(Qt::UserRole + 2,QVariant(scale)); listWidgetItem->setData(Qt::UserRole + 3,varColor); - listWidgetItem->setData(Qt::UserRole + 4,QVariant(interpolation)); + listWidgetItem->setData(Qt::UserRole + 4,QVariant(mean)); + listWidgetItem->setData(Qt::UserRole + 5,QVariant(mathFunction)); } /*! diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h index 54042741e..009f02337 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h @@ -66,11 +66,12 @@ private: Ui::ScopeGadgetOptionsPage *options_page; ScopeGadgetConfiguration *m_config; - void addPlotCurveConfig(QString uavObject, QString uavField, int scale, int interpolation, QVariant varColor); - void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, int interpolation, QVariant varColor); + void addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor); + void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor); void setYAxisWidgetFromPlotCurve(); void setButtonColor(const QColor &color); void validateRefreshInterval(); + bool eventFilter( QObject * obj, QEvent * evt ); private slots: void on_spnRefreshInterval_valueChanged(int ); @@ -79,6 +80,7 @@ private slots: void on_btnAddCurve_clicked(); void on_cmbUAVObjects_currentIndexChanged(QString val); void on_btnColor_clicked(); + void on_mathFunctionComboBox_currentIndexChanged(int currentIndex); void on_loggingEnable_clicked(); }; diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui index 320c3d314..c120544aa 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui @@ -6,8 +6,8 @@ 0 0 - 544 - 342 + 548 + 457 @@ -100,7 +100,11 @@
- + + + Qt::StrongFocus + + @@ -111,6 +115,9 @@ + + Qt::StrongFocus + seconds @@ -134,6 +141,9 @@ + + Qt::StrongFocus + ms @@ -161,7 +171,7 @@ - Plot curves + Y-axis @@ -173,7 +183,11 @@
- + + + Qt::StrongFocus + + @@ -183,45 +197,67 @@ - + + + Qt::StrongFocus + + - + Color: - + + + Qt::StrongFocus + Choose - + - Scale: + Y-axis scale factor: - + + + Qt::StrongFocus + false - + - Display smoothed interpolation: + Math window size - - + + + + false + + + + 16777215 + 16777215 + + + + Qt::StrongFocus + samples @@ -239,6 +275,20 @@ + + + + Math function: + + + + + + + Qt::StrongFocus + + + @@ -390,6 +440,22 @@ Update 1 + + cmbPlotType + spnDataSize + spnRefreshInterval + cmbUAVObjects + cmbUAVField + mathFunctionComboBox + spnMeanSamples + btnColor + cmbScale + btnAddCurve + btnRemoveCurve + lstCurves + LoggingEnable + LoggingConnect +
diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp index 140935da3..967ede982 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp @@ -54,15 +54,10 @@ //using namespace Core; -TestDataGen* ScopeGadgetWidget::testDataGen; - // ****************************************************************** ScopeGadgetWidget::ScopeGadgetWidget(QWidget *parent) : QwtPlot(parent) { - //if(testDataGen == 0) - // testDataGen = new TestDataGen(); - setMouseTracking(true); // canvas()->setMouseTracking(true); @@ -147,7 +142,7 @@ void ScopeGadgetWidget::mouseMoveEvent(QMouseEvent *e) void ScopeGadgetWidget::wheelEvent(QWheelEvent *e) { - QwtPlot::wheelEvent(e); + QwtPlot::wheelEvent(e); } /** @@ -274,9 +269,9 @@ void ScopeGadgetWidget::showCurve(QwtPlotItem *item, bool on) mutex.unlock(); } -void ScopeGadgetWidget::setupSequencialPlot() +void ScopeGadgetWidget::setupSequentialPlot() { - preparePlot(SequencialPlot); + preparePlot(SequentialPlot); // QwtText title("Index"); //// title.setFont(QFont("Helvetica", 20)); @@ -357,12 +352,12 @@ void ScopeGadgetWidget::setupChronoPlot() // scaleWidget->setMinBorderDist(0, fmw); } -void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor, int interpolationSamples, QPen pen) +void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor, int meanSamples, QString mathFunction, QPen pen) { PlotData* plotData; - if (m_plotType == SequencialPlot) - plotData = new SequencialPlotData(uavObject, uavFieldSubField); + if (m_plotType == SequentialPlot) + plotData = new SequentialPlotData(uavObject, uavFieldSubField); else if (m_plotType == ChronoPlot) plotData = new ChronoPlotData(uavObject, uavFieldSubField); //else if (m_plotType == UAVObjectPlot) @@ -370,7 +365,8 @@ void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField plotData->m_xWindowSize = m_xWindowSize; plotData->scalePower = scaleOrderFactor; - plotData->interpolationSamples = interpolationSamples; + plotData->meanSamples = meanSamples; + plotData->mathFunction = mathFunction; //If the y-bounds are supplied, set them if (plotData->yMinimum != plotData->yMaximum) @@ -476,7 +472,7 @@ void ScopeGadgetWidget::replotNewData() void ScopeGadgetWidget::setupExamplePlot() { - preparePlot(SequencialPlot); + preparePlot(SequentialPlot); // Show the axes @@ -532,68 +528,6 @@ void ScopeGadgetWidget::clearCurvePlots() } -TestDataGen::TestDataGen() -{ - // Get required UAVObjects - ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager* objManager = pm->getObject(); - - baroAltitude = BaroAltitude::GetInstance(objManager); - gps = PositionActual::GetInstance(objManager); - attRaw = AttitudeRaw::GetInstance(objManager); - manCtrlCmd = ManualControlCommand::GetInstance(objManager); - - //Setup timer - periodMs = 20; - timer = new QTimer(this); - connect(timer, SIGNAL(timeout()), this, SLOT(genTestData())); - timer->start(periodMs); - - debugCounter = 0; - testTime = 0; -} - -void TestDataGen::genTestData() -{ - // Update BaroAltitude object - BaroAltitude::DataFields baroAltitudeData; - baroAltitudeData.Altitude = 500 * sin(1 * testTime) + 200 * cos(4 * testTime) + 800; - baroAltitudeData.Temperature = 30 * sin(0.5 * testTime); - baroAltitudeData.Pressure = baroAltitudeData.Altitude * 0.01 + baroAltitudeData.Temperature; - baroAltitude->setData(baroAltitudeData); - - // Update Attitude Raw data - AttitudeRaw::DataFields attData; -// attData.accels[0] = 4 * sin(2 * testTime) + 1 * cos(6 * testTime) + 4; -// attData.accels[1] = 3 * sin(2.3 * testTime) + 1.5 * cos(3.3 * testTime) + 2; -// attData.accels[2] = 4 * sin(5.3 * testTime) + 1.5 * cos(1.3 * testTime) + 1; - attData.accels[0] = 1; - attData.accels[1] = 4; - attData.accels[2] = 9; - attRaw->setData(attData); - - - ManualControlCommand::DataFields manCtlData; - manCtlData.Channel[0] = 400 * cos(2 * testTime) + 100 * sin(6 * testTime) + 400; - manCtlData.Channel[1] = 350 * cos(2.3 * testTime) + 150 * sin(3.3 * testTime) + 200; - manCtlData.Channel[2] = 450 * cos(5.3 * testTime) + 150 * sin(1.3 * testTime) + 150; - manCtrlCmd->setData(manCtlData); - - testTime += (periodMs / 1000.0); - -// debugCounter++; -// if (debugCounter % (100/periodMs) == 0 ) -// qDebug() << "Test Time = " << testTime; -} - -TestDataGen::~TestDataGen() -{ - if (timer) - timer->stop(); - - delete timer; -} - /* int csvLoggingEnable; int csvLoggingHeaderSaved; @@ -702,6 +636,15 @@ int ScopeGadgetWidget::csvLoggingAddData() ss << ", "; if (plotData2->xData->isEmpty ()) { + ss << ", "; + if (plotData2->xData->isEmpty ()) + { + } + else + { + ss << QString().sprintf("%3.6g",plotData2->yData->last()); + m_csvLoggingDataValid=1; + } } else { diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h index 98da3beb6..f812e6fa6 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h @@ -62,35 +62,6 @@ private: // double baseTime; }; -/*! - \brief This class is used to inject UAVTalk messages for testing. - */ -class TestDataGen : QObject -{ - Q_OBJECT - -public: - - TestDataGen(); - ~TestDataGen(); - -private: - BaroAltitude* baroAltitude; - PositionActual* gps; - AttitudeRaw* attRaw; - ManualControlCommand* manCtrlCmd; - - QTimer *timer; - double testTime; - int periodMs; - - int debugCounter; - -private slots: - void genTestData(); -}; - - class ScopeGadgetWidget : public QwtPlot { Q_OBJECT @@ -99,7 +70,7 @@ public: ScopeGadgetWidget(QWidget *parent = 0); ~ScopeGadgetWidget(); - void setupSequencialPlot(); + void setupSequentialPlot(); void setupChronoPlot(); void setupUAVObjectPlot(); PlotType plotType(){return m_plotType;} @@ -110,7 +81,7 @@ public: int refreshInterval(){return m_refreshInterval;} - void addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, int interpolationSamples = 1, QPen pen = QPen(Qt::black)); + void addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, int meanSamples = 1, QString mathFunction= "None", QPen pen = QPen(Qt::black)); //void removeCurvePlot(QString uavObject, QString uavField); void clearCurvePlots(); int csvLoggingStart(); @@ -148,8 +119,6 @@ private: QList m_connectedUAVObjects; QMap m_curvesData; - static TestDataGen* testDataGen; - QTimer *replotTimer; bool m_csvLoggingStarted; diff --git a/ground/openpilotgcs/src/plugins/uavobjects/tests/uavobjectstest.h b/ground/openpilotgcs/src/plugins/uavobjects/tests/uavobjectstest.h index 107bccb8f..1b5956b11 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/tests/uavobjectstest.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/tests/uavobjectstest.h @@ -18,6 +18,7 @@ private slots: void objectUpdated(UAVObject* obj); void objectUpdatedAuto(UAVObject* obj); void objectUpdatedManual(UAVObject* obj); + void objectUpdatedPeriodic(UAVObject* obj); void objectUnpacked(UAVObject* obj); void updateRequested(UAVObject* obj); void runTest(); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavmetaobject.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavmetaobject.cpp index 54a5a7736..bb45495f5 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavmetaobject.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavmetaobject.cpp @@ -36,16 +36,7 @@ UAVMetaObject::UAVMetaObject(quint32 objID, const QString& name, UAVObject* pare { this->parent = parent; // Setup default metadata of metaobject (can not be changed) - ownMetadata.flightAccess = ACCESS_READWRITE; - ownMetadata.gcsAccess = ACCESS_READWRITE; - ownMetadata.flightTelemetryAcked = 1; - ownMetadata.flightTelemetryUpdateMode = UPDATEMODE_ONCHANGE; - ownMetadata.flightTelemetryUpdatePeriod = 0; - ownMetadata.gcsTelemetryAcked = 1; - ownMetadata.gcsTelemetryUpdateMode = UPDATEMODE_ONCHANGE; - ownMetadata.gcsTelemetryUpdatePeriod = 0; - ownMetadata.loggingUpdateMode = UPDATEMODE_ONCHANGE; - ownMetadata.loggingUpdatePeriod = 0; + UAVObject::MetadataInitialize(ownMetadata); // Setup fields QStringList boolEnum; boolEnum << tr("False") << tr("True"); @@ -54,16 +45,10 @@ UAVMetaObject::UAVMetaObject(quint32 objID, const QString& name, UAVObject* pare QStringList accessModeEnum; accessModeEnum << tr("Read/Write") << tr("Read Only"); QList fields; - fields.append( new UAVObjectField(tr("Flight Access Mode"), tr(""), UAVObjectField::ENUM, 1, accessModeEnum) ); - fields.append( new UAVObjectField(tr("GCS Access Mode"), tr(""), UAVObjectField::ENUM, 1, accessModeEnum) ); - fields.append( new UAVObjectField(tr("Flight Telemetry Acked"), tr(""), UAVObjectField::ENUM, 1, boolEnum) ); - fields.append( new UAVObjectField(tr("Flight Telemetry Update Mode"), tr(""), UAVObjectField::ENUM, 1, updateModeEnum) ); - fields.append( new UAVObjectField(tr("Flight Telemetry Update Period"), tr(""), UAVObjectField::UINT32, 1, QStringList()) ); - fields.append( new UAVObjectField(tr("GCS Telemetry Acked"), tr(""), UAVObjectField::ENUM, 1, boolEnum) ); - fields.append( new UAVObjectField(tr("GCS Telemetry Update Mode"), tr(""), UAVObjectField::ENUM, 1, updateModeEnum) ); - fields.append( new UAVObjectField(tr("GCS Telemetry Update Period"), tr(""), UAVObjectField::UINT32, 1, QStringList()) ); - fields.append( new UAVObjectField(tr("Logging Update Mode"), tr(""), UAVObjectField::ENUM, 1, updateModeEnum) ); - fields.append( new UAVObjectField(tr("Logging Update Period"), tr(""), UAVObjectField::UINT32, 1, QStringList()) ); + fields.append( new UAVObjectField(tr("Modes"), tr(""), UAVObjectField::UINT8, 1, accessModeEnum) ); + fields.append( new UAVObjectField(tr("Flight Telemetry Update Period"), tr(""), UAVObjectField::UINT16, 1, QStringList()) ); + fields.append( new UAVObjectField(tr("GCS Telemetry Update Period"), tr(""), UAVObjectField::UINT16, 1, QStringList()) ); + fields.append( new UAVObjectField(tr("Logging Update Period"), tr(""), UAVObjectField::UINT16, 1, QStringList()) ); // Initialize parent UAVObject::initialize(0); UAVObject::initializeFields(fields, (quint8*)&parentMetadata, sizeof(Metadata)); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp index c7161bc64..47960b060 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp @@ -29,6 +29,18 @@ #include #include +// Constants +#define UAVOBJ_ACCESS_SHIFT 0 +#define UAVOBJ_GCS_ACCESS_SHIFT 1 +#define UAVOBJ_TELEMETRY_ACKED_SHIFT 2 +#define UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT 3 +#define UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT 4 +#define UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT 6 +#define UAVOBJ_UPDATE_MODE_MASK 0x3 + +// Macros +#define SET_BITS(var, shift, value, mask) var = (var & ~(mask << shift)) | (value << shift); + /** * Constructor * @param objID The object ID @@ -456,3 +468,132 @@ void UAVObject::emitTransactionCompleted(bool success) { emit transactionCompleted(this, success); } + +/** + * Initialize a UAVObjMetadata object. + * \param[in] metadata The metadata object + */ +void UAVObject::MetadataInitialize(UAVObject::Metadata& metadata) +{ + metadata.flags = + ACCESS_READWRITE << UAVOBJ_ACCESS_SHIFT | + ACCESS_READWRITE << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UPDATEMODE_ONCHANGE << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UPDATEMODE_ONCHANGE << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; +} + +/** + * Get the UAVObject metadata access member + * \param[in] metadata The metadata object + * \return the access type + */ +UAVObject::AccessMode UAVObject::GetFlightAccess(const UAVObject::Metadata& metadata) +{ + return UAVObject::AccessMode((metadata.flags >> UAVOBJ_ACCESS_SHIFT) & 1); +} + +/** + * Set the UAVObject metadata access member + * \param[in] metadata The metadata object + * \param[in] mode The access mode + */ +void UAVObject::SetFlightAccess(UAVObject::Metadata& metadata, UAVObject::AccessMode mode) +{ + SET_BITS(metadata.flags, UAVOBJ_ACCESS_SHIFT, mode, 1); +} + +/** + * Get the UAVObject metadata GCS access member + * \param[in] metadata The metadata object + * \return the GCS access type + */ +UAVObject::AccessMode UAVObject::GetGcsAccess(const UAVObject::Metadata& metadata) +{ + return UAVObject::AccessMode((metadata.flags >> UAVOBJ_GCS_ACCESS_SHIFT) & 1); +} + +/** + * Set the UAVObject metadata GCS access member + * \param[in] metadata The metadata object + * \param[in] mode The access mode + */ +void UAVObject::SetGcsAccess(UAVObject::Metadata& metadata, UAVObject::AccessMode mode) { + SET_BITS(metadata.flags, UAVOBJ_GCS_ACCESS_SHIFT, mode, 1); +} + +/** + * Get the UAVObject metadata telemetry acked member + * \param[in] metadata The metadata object + * \return the telemetry acked boolean + */ +quint8 UAVObject::GetFlightTelemetryAcked(const UAVObject::Metadata& metadata) { + return (metadata.flags >> UAVOBJ_TELEMETRY_ACKED_SHIFT) & 1; +} + +/** + * Set the UAVObject metadata telemetry acked member + * \param[in] metadata The metadata object + * \param[in] val The telemetry acked boolean + */ +void UAVObject::SetFlightTelemetryAcked(UAVObject::Metadata& metadata, quint8 val) { + SET_BITS(metadata.flags, UAVOBJ_TELEMETRY_ACKED_SHIFT, val, 1); +} + +/** + * Get the UAVObject metadata GCS telemetry acked member + * \param[in] metadata The metadata object + * \return the telemetry acked boolean + */ +quint8 UAVObject::GetGcsTelemetryAcked(const UAVObject::Metadata& metadata) { + return (metadata.flags >> UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT) & 1; +} + +/** + * Set the UAVObject metadata GCS telemetry acked member + * \param[in] metadata The metadata object + * \param[in] val The GCS telemetry acked boolean + */ +void UAVObject::SetGcsTelemetryAcked(UAVObject::Metadata& metadata, quint8 val) { + SET_BITS(metadata.flags, UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT, val, 1); +} + +/** + * Get the UAVObject metadata telemetry update mode + * \param[in] metadata The metadata object + * \return the telemetry update mode + */ +UAVObject::UpdateMode UAVObject::GetFlightTelemetryUpdateMode(const UAVObject::Metadata& metadata) { + return UAVObject::UpdateMode((metadata.flags >> UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK); +} + +/** + * Set the UAVObject metadata telemetry update mode member + * \param[in] metadata The metadata object + * \param[in] val The telemetry update mode + */ +void UAVObject::SetFlightTelemetryUpdateMode(UAVObject::Metadata& metadata, UAVObject::UpdateMode val) { + SET_BITS(metadata.flags, UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT, val, UAVOBJ_UPDATE_MODE_MASK); +} + +/** + * Get the UAVObject metadata GCS telemetry update mode + * \param[in] metadata The metadata object + * \return the GCS telemetry update mode + */ +UAVObject::UpdateMode UAVObject::GetGcsTelemetryUpdateMode(const UAVObject::Metadata& metadata) { + return UAVObject::UpdateMode((metadata.flags >> UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK); +} + +/** + * Set the UAVObject metadata GCS telemetry update mode member + * \param[in] metadata The metadata object + * \param[in] val The GCS telemetry update mode + */ +void UAVObject::SetGcsTelemetryUpdateMode(UAVObject::Metadata& metadata, UAVObject::UpdateMode val) { + SET_BITS(metadata.flags, UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT, val, UAVOBJ_UPDATE_MODE_MASK); +} diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h index aa6db086d..945672c61 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h @@ -36,8 +36,17 @@ #include #include #include +#include #include "uavobjectfield.h" +#define UAVOBJ_ACCESS_SHIFT 0 +#define UAVOBJ_GCS_ACCESS_SHIFT 1 +#define UAVOBJ_TELEMETRY_ACKED_SHIFT 2 +#define UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT 3 +#define UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT 4 +#define UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT 6 +#define UAVOBJ_UPDATE_MODE_MASK 0x3 + class UAVObjectField; class UAVOBJECTS_EXPORT UAVObject: public QObject @@ -52,8 +61,8 @@ public: typedef enum { UPDATEMODE_PERIODIC = 0, /** Automatically update object at periodic intervals */ UPDATEMODE_ONCHANGE = 1, /** Only update object when its data changes */ - UPDATEMODE_MANUAL = 2, /** Manually update object, by calling the updated() function */ - UPDATEMODE_NEVER = 3 /** Object is never updated */ + UPDATEMODE_THROTTLED = 2, /** Object is updated on change, but not more often than the interval time */ + UPDATEMODE_MANUAL = 3 /** Manually update object, by calling the updated() function */ } UpdateMode; /** @@ -67,19 +76,25 @@ public: /** * Object metadata, each object has a meta object that holds its metadata. The metadata define * properties for each object and can be used by multiple modules (e.g. telemetry and logger) + * + * The object metadata flags are packed into a single 16 bit integer. + * The bits in the flag field are defined as: + * + * Bit(s) Name Meaning + * ------ ---- ------- + * 0 access Defines the access level for the local transactions (readonly=0 and readwrite=1) + * 1 gcsAccess Defines the access level for the local GCS transactions (readonly=0 and readwrite=1), not used in the flight s/w + * 2 telemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 3 gcsTelemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 4-5 telemetryUpdateMode Update mode used by the telemetry module (UAVObjUpdateMode) + * 6-7 gcsTelemetryUpdateMode Update mode used by the GCS (UAVObjUpdateMode) */ - typedef struct { - quint8 flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ - quint8 gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ - quint8 flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - quint8 flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ - qint32 flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ - quint8 gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - quint8 gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ - qint32 gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - quint8 loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ - qint32 loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ - } __attribute__((packed)) Metadata; + typedef struct { + quint8 flags; /** Defines flags for update and logging modes and whether an update should be ACK'd (bits defined above) */ + quint16 flightTelemetryUpdatePeriod; /** Update period used by the telemetry module (only if telemetry mode is PERIODIC) */ + quint16 gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + quint16 loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ + } __attribute__((packed)) Metadata; UAVObject(quint32 objID, bool isSingleInst, const QString& name); @@ -111,6 +126,21 @@ public: QString toStringData(); void emitTransactionCompleted(bool success); + // Metadata accessors + static void MetadataInitialize(Metadata& meta); + static AccessMode GetFlightAccess(const Metadata& meta); + static void SetFlightAccess(Metadata& meta, AccessMode mode); + static AccessMode GetGcsAccess(const Metadata& meta); + static void SetGcsAccess(Metadata& meta, AccessMode mode); + static quint8 GetFlightTelemetryAcked(const Metadata& meta); + static void SetFlightTelemetryAcked(Metadata& meta, quint8 val); + static quint8 GetGcsTelemetryAcked(const Metadata& meta); + static void SetGcsTelemetryAcked(Metadata& meta, quint8 val); + static UpdateMode GetFlightTelemetryUpdateMode(const Metadata& meta); + static void SetFlightTelemetryUpdateMode(Metadata& meta, UpdateMode val); + static UpdateMode GetGcsTelemetryUpdateMode(const Metadata& meta); + static void SetGcsTelemetryUpdateMode(Metadata& meta, UpdateMode val); + public slots: void requestUpdate(); void updated(); @@ -119,6 +149,7 @@ signals: void objectUpdated(UAVObject* obj); void objectUpdatedAuto(UAVObject* obj); void objectUpdatedManual(UAVObject* obj); + void objectUpdatedPeriodic(UAVObject* obj); void objectUnpacked(UAVObject* obj); void updateRequested(UAVObject* obj); void transactionCompleted(UAVObject* obj, bool success); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp index ed9644988..f5df52396 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -833,7 +833,7 @@ bool UAVObjectField::checkValue(const QVariant& value, quint32 index) // Get metadata UAVObject::Metadata mdata = obj->getMetadata(); // Update value if the access mode permits - if ( mdata.gcsAccess == UAVObject::ACCESS_READWRITE ) + if ( UAVObject::GetFlightAccess(mdata) == UAVObject::ACCESS_READWRITE ) { switch (type) { @@ -873,7 +873,7 @@ void UAVObjectField::setValue(const QVariant& value, quint32 index) // Get metadata UAVObject::Metadata mdata = obj->getMetadata(); // Update value if the access mode permits - if ( mdata.gcsAccess == UAVObject::ACCESS_READWRITE ) + if ( UAVObject::GetGcsAccess(mdata) == UAVObject::ACCESS_READWRITE ) { switch (type) { diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro old mode 100644 new mode 100755 index c88bfc034..bfe2342b3 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -24,18 +24,23 @@ OTHER_FILES += UAVObjects.pluginspec # Add in all of the synthetic/generated uavobject files HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ - $$UAVOBJECT_SYNTHETICS/ahrsstatus.h \ - $$UAVOBJECT_SYNTHETICS/ahrscalibration.h \ $$UAVOBJECT_SYNTHETICS/baroaltitude.h \ $$UAVOBJECT_SYNTHETICS/attitudeactual.h \ - $$UAVOBJECT_SYNTHETICS/ahrssettings.h \ + $$UAVOBJECT_SYNTHETICS/altholdsmoothed.h \ + $$UAVOBJECT_SYNTHETICS/altitudeholddesired.h \ + $$UAVOBJECT_SYNTHETICS/altitudeholdsettings.h \ + $$UAVOBJECT_SYNTHETICS/revocalibration.h \ $$UAVOBJECT_SYNTHETICS/gcstelemetrystats.h \ - $$UAVOBJECT_SYNTHETICS/attituderaw.h \ + $$UAVOBJECT_SYNTHETICS/gyros.h \ + $$UAVOBJECT_SYNTHETICS/gyrosbias.h \ + $$UAVOBJECT_SYNTHETICS/accels.h \ + $$UAVOBJECT_SYNTHETICS/magnetometer.h \ $$UAVOBJECT_SYNTHETICS/camerastabsettings.h \ $$UAVOBJECT_SYNTHETICS/flighttelemetrystats.h \ $$UAVOBJECT_SYNTHETICS/systemstats.h \ $$UAVOBJECT_SYNTHETICS/systemalarms.h \ $$UAVOBJECT_SYNTHETICS/objectpersistence.h \ + $$UAVOBJECT_SYNTHETICS/overosyncstats.h \ $$UAVOBJECT_SYNTHETICS/systemsettings.h \ $$UAVOBJECT_SYNTHETICS/stabilizationsettings.h \ $$UAVOBJECT_SYNTHETICS/manualcontrolsettings.h \ @@ -75,22 +80,27 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/txpidsettings.h \ $$UAVOBJECT_SYNTHETICS/cameradesired.h \ $$UAVOBJECT_SYNTHETICS/faultsettings.h \ - $$UAVOBJECT_SYNTHETICS/waypoint.h \ - $$UAVOBJECT_SYNTHETICS/waypointactive.h \ - $$UAVOBJECT_SYNTHETICS/pathaction.h + $$UAVOBJECT_SYNTHETICS/pipxsettings.h \ + $$UAVOBJECT_SYNTHETICS/pipxstatus.h + SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ - $$UAVOBJECT_SYNTHETICS/ahrsstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/ahrscalibration.cpp \ $$UAVOBJECT_SYNTHETICS/baroaltitude.cpp \ $$UAVOBJECT_SYNTHETICS/attitudeactual.cpp \ - $$UAVOBJECT_SYNTHETICS/ahrssettings.cpp \ + $$UAVOBJECT_SYNTHETICS/altholdsmoothed.cpp \ + $$UAVOBJECT_SYNTHETICS/altitudeholddesired.cpp \ + $$UAVOBJECT_SYNTHETICS/altitudeholdsettings.cpp \ + $$UAVOBJECT_SYNTHETICS/revocalibration.cpp \ $$UAVOBJECT_SYNTHETICS/gcstelemetrystats.cpp \ - $$UAVOBJECT_SYNTHETICS/attituderaw.cpp \ + $$UAVOBJECT_SYNTHETICS/accels.cpp \ + $$UAVOBJECT_SYNTHETICS/gyros.cpp \ + $$UAVOBJECT_SYNTHETICS/gyrosbias.cpp \ + $$UAVOBJECT_SYNTHETICS/magnetometer.cpp \ $$UAVOBJECT_SYNTHETICS/camerastabsettings.cpp \ $$UAVOBJECT_SYNTHETICS/flighttelemetrystats.cpp \ $$UAVOBJECT_SYNTHETICS/systemstats.cpp \ $$UAVOBJECT_SYNTHETICS/systemalarms.cpp \ $$UAVOBJECT_SYNTHETICS/objectpersistence.cpp \ + $$UAVOBJECT_SYNTHETICS/overosyncstats.cpp \ $$UAVOBJECT_SYNTHETICS/systemsettings.cpp \ $$UAVOBJECT_SYNTHETICS/stabilizationsettings.cpp \ $$UAVOBJECT_SYNTHETICS/manualcontrolsettings.cpp \ @@ -131,6 +141,5 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/txpidsettings.cpp \ $$UAVOBJECT_SYNTHETICS/cameradesired.cpp \ $$UAVOBJECT_SYNTHETICS/faultsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/waypoint.cpp \ - $$UAVOBJECT_SYNTHETICS/waypointactive.cpp \ - $$UAVOBJECT_SYNTHETICS/pathaction.cpp + $$UAVOBJECT_SYNTHETICS/pipxsettings.cpp \ + $$UAVOBJECT_SYNTHETICS/pipxstatus.cpp diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.cpp index d38bcdbc5..58aa84ead 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.cpp @@ -61,15 +61,15 @@ $(FIELDSINIT) UAVObject::Metadata $(NAME)::getDefaultMetadata() { UAVObject::Metadata metadata; - metadata.flightAccess = $(FLIGHTACCESS); - metadata.gcsAccess = $(GCSACCESS); - metadata.gcsTelemetryAcked = $(GCSTELEM_ACKED); - metadata.gcsTelemetryUpdateMode = UAVObject::$(GCSTELEM_UPDATEMODE); - metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - metadata.flightTelemetryAcked = $(FLIGHTTELEM_ACKED); - metadata.flightTelemetryUpdateMode = UAVObject::$(FLIGHTTELEM_UPDATEMODE); + metadata.flags = + $(FLIGHTACCESS) << UAVOBJ_ACCESS_SHIFT | + $(GCSACCESS) << UAVOBJ_GCS_ACCESS_SHIFT | + $(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT | + $(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + $(FLIGHTTELEM_UPDATEMODE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + $(GCSTELEM_UPDATEMODE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; metadata.flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - metadata.loggingUpdateMode = UAVObject::$(LOGGING_UPDATEMODE); + metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); return metadata; } @@ -102,7 +102,7 @@ void $(NAME)::setData(const DataFields& data) // Get metadata Metadata mdata = getMetadata(); // Update object if the access mode permits - if ( mdata.gcsAccess == ACCESS_READWRITE ) + if ( UAVObject::GetGcsAccess(mdata) == ACCESS_READWRITE ) { this->data = data; emit objectUpdatedAuto(this); // trigger object updated event diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m index c494c529b..42d388a31 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m @@ -3,10 +3,41 @@ function [] = OPLogConvert(varargin) % THIS FILE IS AUTOMATICALLY GENERATED. outputType='mat'; %Default output is a .mat file +checkCRC = false; +wrongSyncByte=0; +wrongMessageByte=0; +lastWrongSyncByte=0; +lastWrongMessageByte=0; +str1=[]; +str2=[]; +str3=[]; +str4=[]; +str5=[]; + +fprintf('\n\n***OpenPilot log parser***\n\n'); +global crc_table; +crc_table = [ ... + hex2dec('00'),hex2dec('07'),hex2dec('0e'),hex2dec('09'),hex2dec('1c'),hex2dec('1b'),hex2dec('12'),hex2dec('15'),hex2dec('38'),hex2dec('3f'),hex2dec('36'),hex2dec('31'),hex2dec('24'),hex2dec('23'),hex2dec('2a'),hex2dec('2d'), ... + hex2dec('70'),hex2dec('77'),hex2dec('7e'),hex2dec('79'),hex2dec('6c'),hex2dec('6b'),hex2dec('62'),hex2dec('65'),hex2dec('48'),hex2dec('4f'),hex2dec('46'),hex2dec('41'),hex2dec('54'),hex2dec('53'),hex2dec('5a'),hex2dec('5d'), ... + hex2dec('e0'),hex2dec('e7'),hex2dec('ee'),hex2dec('e9'),hex2dec('fc'),hex2dec('fb'),hex2dec('f2'),hex2dec('f5'),hex2dec('d8'),hex2dec('df'),hex2dec('d6'),hex2dec('d1'),hex2dec('c4'),hex2dec('c3'),hex2dec('ca'),hex2dec('cd'), ... + hex2dec('90'),hex2dec('97'),hex2dec('9e'),hex2dec('99'),hex2dec('8c'),hex2dec('8b'),hex2dec('82'),hex2dec('85'),hex2dec('a8'),hex2dec('af'),hex2dec('a6'),hex2dec('a1'),hex2dec('b4'),hex2dec('b3'),hex2dec('ba'),hex2dec('bd'), ... + hex2dec('c7'),hex2dec('c0'),hex2dec('c9'),hex2dec('ce'),hex2dec('db'),hex2dec('dc'),hex2dec('d5'),hex2dec('d2'),hex2dec('ff'),hex2dec('f8'),hex2dec('f1'),hex2dec('f6'),hex2dec('e3'),hex2dec('e4'),hex2dec('ed'),hex2dec('ea'), ... + hex2dec('b7'),hex2dec('b0'),hex2dec('b9'),hex2dec('be'),hex2dec('ab'),hex2dec('ac'),hex2dec('a5'),hex2dec('a2'),hex2dec('8f'),hex2dec('88'),hex2dec('81'),hex2dec('86'),hex2dec('93'),hex2dec('94'),hex2dec('9d'),hex2dec('9a'), ... + hex2dec('27'),hex2dec('20'),hex2dec('29'),hex2dec('2e'),hex2dec('3b'),hex2dec('3c'),hex2dec('35'),hex2dec('32'),hex2dec('1f'),hex2dec('18'),hex2dec('11'),hex2dec('16'),hex2dec('03'),hex2dec('04'),hex2dec('0d'),hex2dec('0a'), ... + hex2dec('57'),hex2dec('50'),hex2dec('59'),hex2dec('5e'),hex2dec('4b'),hex2dec('4c'),hex2dec('45'),hex2dec('42'),hex2dec('6f'),hex2dec('68'),hex2dec('61'),hex2dec('66'),hex2dec('73'),hex2dec('74'),hex2dec('7d'),hex2dec('7a'), ... + hex2dec('89'),hex2dec('8e'),hex2dec('87'),hex2dec('80'),hex2dec('95'),hex2dec('92'),hex2dec('9b'),hex2dec('9c'),hex2dec('b1'),hex2dec('b6'),hex2dec('bf'),hex2dec('b8'),hex2dec('ad'),hex2dec('aa'),hex2dec('a3'),hex2dec('a4'), ... + hex2dec('f9'),hex2dec('fe'),hex2dec('f7'),hex2dec('f0'),hex2dec('e5'),hex2dec('e2'),hex2dec('eb'),hex2dec('ec'),hex2dec('c1'),hex2dec('c6'),hex2dec('cf'),hex2dec('c8'),hex2dec('dd'),hex2dec('da'),hex2dec('d3'),hex2dec('d4'), ... + hex2dec('69'),hex2dec('6e'),hex2dec('67'),hex2dec('60'),hex2dec('75'),hex2dec('72'),hex2dec('7b'),hex2dec('7c'),hex2dec('51'),hex2dec('56'),hex2dec('5f'),hex2dec('58'),hex2dec('4d'),hex2dec('4a'),hex2dec('43'),hex2dec('44'), ... + hex2dec('19'),hex2dec('1e'),hex2dec('17'),hex2dec('10'),hex2dec('05'),hex2dec('02'),hex2dec('0b'),hex2dec('0c'),hex2dec('21'),hex2dec('26'),hex2dec('2f'),hex2dec('28'),hex2dec('3d'),hex2dec('3a'),hex2dec('33'),hex2dec('34'), ... + hex2dec('4e'),hex2dec('49'),hex2dec('40'),hex2dec('47'),hex2dec('52'),hex2dec('55'),hex2dec('5c'),hex2dec('5b'),hex2dec('76'),hex2dec('71'),hex2dec('78'),hex2dec('7f'),hex2dec('6a'),hex2dec('6d'),hex2dec('64'),hex2dec('63'), ... + hex2dec('3e'),hex2dec('39'),hex2dec('30'),hex2dec('37'),hex2dec('22'),hex2dec('25'),hex2dec('2c'),hex2dec('2b'),hex2dec('06'),hex2dec('01'),hex2dec('08'),hex2dec('0f'),hex2dec('1a'),hex2dec('1d'),hex2dec('14'),hex2dec('13'), ... + hex2dec('ae'),hex2dec('a9'),hex2dec('a0'),hex2dec('a7'),hex2dec('b2'),hex2dec('b5'),hex2dec('bc'),hex2dec('bb'),hex2dec('96'),hex2dec('91'),hex2dec('98'),hex2dec('9f'),hex2dec('8a'),hex2dec('8d'),hex2dec('84'),hex2dec('83'), ... + hex2dec('de'),hex2dec('d9'),hex2dec('d0'),hex2dec('d7'),hex2dec('c2'),hex2dec('c5'),hex2dec('cc'),hex2dec('cb'),hex2dec('e6'),hex2dec('e1'),hex2dec('e8'),hex2dec('ef'),hex2dec('fa'),hex2dec('fd'),hex2dec('f4'),hex2dec('f3') ... + ]; if nargin==0 %% - if (exist('uigetfile')) + if (exist('uigetfile')) %#ok [FileName, PathName]=uigetfile('*.opl'); logfile=fullfile(PathName, FileName); @@ -33,26 +64,36 @@ correctSyncByte=hex2dec('3C'); unknownObjIDList=zeros(1,2); % Parse log file, entry by entry +prebuf = fread(fid, 12, 'uint8'); +log_size = dir(logfile); +log_size = log_size.bytes; +last_print = 0; + +startTime=clock; + while (1) - %% Read logging header - timestamp = fread(fid, 1, '*uint32'); if (feof(fid)); break; end - datasize = fread(fid, 1, '*int64'); - - + %% Read message header % get sync field (0x3C, 1 byte) sync = fread(fid, 1, 'uint8'); if sync ~= correctSyncByte - disp ('Wrong sync byte'); - return - end + prebuf = [prebuf(2:end); sync]; + wrongSyncByte = wrongSyncByte + 1; + continue + end + + %% Process header if we are aligned + timestamp = typecast(uint8(prebuf(1:4)), 'uint32'); + datasize = typecast(uint8(prebuf(5:12)), 'uint64'); + % get msg type (quint8 1 byte ) should be 0x20, ignore the rest? msgType = fread(fid, 1, 'uint8'); if msgType ~= correctMsgByte - disp ('Wrong msgType'); - return + wrongMessageByte = wrongMessageByte + 1; + continue end + % get msg size (quint16 2 bytes) excludes crc, include msg header and data payload msgSize = fread(fid, 1, 'uint16'); % get obj id (quint32 4 bytes) @@ -63,6 +104,7 @@ while (1) end %% Read object + try switch objID $(SWITCHCODE) otherwise @@ -73,9 +115,52 @@ $(SWITCHCODE) unknownObjIDList(unknownObjIDListIdx,2)=unknownObjIDList(unknownObjIDListIdx,2)+1; end msgBytesLeft = datasize - 1 - 1 - 2 - 4; + if msgBytesLeft > 255 + msgBytesLeft = 0; + end fread(fid, msgBytesLeft, 'uint8'); end - + catch + % One of the reads failed - indicates EOF + break; + end + + if (wrongSyncByte ~= lastWrongSyncByte || wrongMessageByte~=lastWrongMessageByte ) ||... + (ftell(fid) / log_size - last_print) > 0.01 + + lastWrongSyncByte=wrongSyncByte; + lastWrongMessageByte=wrongMessageByte; + + str1=[]; + for i=1:length([str2 str3 str4 str5]); + str1=[str1 sprintf('\b')]; + end + str2=sprintf('wrongSyncByte instances: % 10d\n', wrongSyncByte ); + str3=sprintf('wrongMessageByte instances: % 10d\n\n', wrongMessageByte ); + + str4=sprintf('Completed bytes: % 9d of % 9d\n', ftell(fid), log_size); + + % Arbitrary times two so that it is at least as long + estTimeRemaining=(log_size-ftell(fid))/(ftell(fid)/etime(clock,startTime)) * 2; + h=floor(estTimeRemaining/3600); + m=floor((estTimeRemaining-h*3600)/60); + s=ceil(estTimeRemaining-h*3600-m*60); + + str5=sprintf('Est. time remaining, %02dh:%02dm:%02ds \n', h,m,s); + + last_print = ftell(fid) / log_size; + + fprintf([str1 str2 str3 str4 str5]); + end + + + prebuf = fread(fid, 12, 'uint8'); +end + +fprintf('%d records in %0.2f seconds.\n', ftell(fid), etime(clock,startTime)); + +for i=2:size(unknownObjIDList,1) %Don't show the first one, as it was simply a dummy placeholder + disp(['Unknown object ID: 0x' dec2hex(unknownObjIDList(i,1),8) ' appeared ' int2str(unknownObjIDList(i,2)) ' times.']); end for i=2:size(unknownObjIDList,1) %Don't show the first one, as it was simply a dummy placeholder @@ -105,7 +190,7 @@ function [structOut]=PruneStructOfArrays(structIn, lastIndex) fieldNames = fieldnames(structIn); for i=1:length(fieldNames) - structOut.(fieldNames{i})=structIn.(fieldNames{i})(1:lastIndex); + structOut.(fieldNames{i})=structIn.(fieldNames{i})(:,1:lastIndex); end @@ -137,3 +222,10 @@ function OPLog2csv(structIn, structName, logfile) dlmwrite(csvfile, headerOut, ''); dlmwrite(csvfile, matOut, '-append'); +function crc = compute_crc(data) + global crc_table; + crc = 0; + for i = 1:length(data) + crc = crc_table(1+bitxor(data(i),crc)); + end + diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h b/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h index bf8fafb19..a725c0bfe 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h @@ -12,18 +12,23 @@ public: int boardRevision; static QString idToBoardName(int id) { - switch (id | 0x0011) { - case 0x0111://MB + switch (id) { + case 0x0101://MB return QString("OpenPilot MainBoard"); break; - case 0x0311://PipX + case 0x0201://INS + return QString("OpenPilot INS"); + break; + case 0x0301://PipX return QString("PipXtreame"); break; - case 0x0411://Coptercontrol + case 0x0401://Coptercontrol return QString("CopterControl"); break; - case 0x0211://INS - return QString("OpenPilot INS"); + case 0x0402://Coptercontrol + // It would be nice to say CC3D here but since currently we use string comparisons + // for firmware compatibility and the filename path that would break + return QString("CopterControl"); break; default: return QString(""); diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index ac64c61d8..a30172fb0 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -35,6 +35,7 @@ #include #include #include +#include // ****************************** // constructor/destructor @@ -150,7 +151,7 @@ void UAVObjectUtilManager::objectPersistenceTransactionCompleted(UAVObject* obj, // the queue: saveState = AWAITING_COMPLETED; disconnect(obj, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(objectPersistenceTransactionCompleted(UAVObject*,bool))); - failureTimer.start(1000); // Create a timeout + failureTimer.start(2000); // Create a timeout } else { // Can be caused by timeout errors on sending. Forget it and send next. qDebug() << "objectPersistenceTranscationCompleted (error)"; @@ -199,25 +200,63 @@ void UAVObjectUtilManager::objectPersistenceOperationFailed() */ void UAVObjectUtilManager::objectPersistenceUpdated(UAVObject * obj) { - qDebug() << "objectPersistenceUpdated: " << obj->getField("Operation")->getValue().toString(); - Q_ASSERT(obj->getName().compare("ObjectPersistence") == 0); - if(saveState == AWAITING_COMPLETED) { - failureTimer.stop(); - // Check flight is saying it completed. This is the only thing flight should do to trigger an update. - Q_ASSERT( obj->getField("Operation")->getValue().toString().compare(QString("Completed")) == 0 ); + Q_ASSERT(obj); + Q_ASSERT(obj->getObjID() == ObjectPersistence::OBJID); + ObjectPersistence::DataFields objectPersistence = ((ObjectPersistence *)obj)->getData(); + if(saveState == AWAITING_COMPLETED && objectPersistence.Operation == ObjectPersistence::OPERATION_ERROR) { + failureTimer.stop(); + objectPersistenceOperationFailed(); + } else if (saveState == AWAITING_COMPLETED && + objectPersistence.Operation == ObjectPersistence::OPERATION_COMPLETED) { + failureTimer.stop(); // Check right object saved UAVObject* savingObj = queue.head(); - Q_ASSERT( obj->getField("ObjectID")->getValue() == savingObj->getObjID() ); + if(objectPersistence.ObjectID != savingObj->getObjID() ) { + objectPersistenceOperationFailed(); + return; + } obj->disconnect(this); queue.dequeue(); // We can now remove the object, it's done. saveState = IDLE; - emit saveCompleted(obj->getField("ObjectID")->getValue().toInt(), true); + + emit saveCompleted(objectPersistence.ObjectID, true); saveNextObject(); } } +/** + * Helper function that makes sure FirmwareIAP is updated and then returns the data + */ +FirmwareIAPObj::DataFields UAVObjectUtilManager::getFirmwareIap() +{ + FirmwareIAPObj::DataFields dummy; + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pm); + if (!pm) + return dummy; + UAVObjectManager *om = pm->getObject(); + Q_ASSERT(om); + if (!om) + return dummy; + + FirmwareIAPObj *firmwareIap = FirmwareIAPObj::GetInstance(om); + Q_ASSERT(firmwareIap); + if (!firmwareIap) + return dummy; + + // The code below will ask for the object update and wait for the updated to be received, + // or the timeout of the timer, set to 1 second. + QEventLoop loop; + connect(firmwareIap, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit())); + QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout + firmwareIap->requestUpdate(); + loop.exec(); + + return firmwareIap->getData(); +} /** * Get the UAV Board model, for anyone interested. Return format is: @@ -225,25 +264,8 @@ void UAVObjectUtilManager::objectPersistenceUpdated(UAVObject * obj) */ int UAVObjectUtilManager::getBoardModel() { - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - if (!pm) - return 0; - UAVObjectManager *om = pm->getObject(); - if (!om) - return 0; - - UAVDataObject *obj = dynamic_cast(om->getObject(QString("FirmwareIAPObj"))); - // The code below will ask for the object update and wait for the updated to be received, - // or the timeout of the timer, set to 1 second. - QEventLoop loop; - connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit())); - QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout - obj->requestUpdate(); - loop.exec(); - - int boardType = (obj->getField("BoardType")->getValue().toInt()) << 8; - boardType += obj->getField("BoardRevision")->getValue().toInt(); - return boardType; + FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap(); + return (firmwareIapData.BoardType << 8) + firmwareIapData.BoardRevision; } /** @@ -252,54 +274,18 @@ int UAVObjectUtilManager::getBoardModel() QByteArray UAVObjectUtilManager::getBoardCPUSerial() { QByteArray cpuSerial; - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - if (!pm) - return 0; - UAVObjectManager *om = pm->getObject(); - if (!om) - return 0; + FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap(); - UAVDataObject *obj = dynamic_cast(om->getObject(QString("FirmwareIAPObj"))); - // The code below will ask for the object update and wait for the updated to be received, - // or the timeout of the timer, set to 1 second. - QEventLoop loop; - connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit())); - QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout - obj->requestUpdate(); - loop.exec(); + for (int i = 0; i < FirmwareIAPObj::CPUSERIAL_NUMELEM; i++) + cpuSerial.append(firmwareIapData.CPUSerial[i]); - UAVObjectField* cpuField = obj->getField("CPUSerial"); - for (uint i = 0; i < cpuField->getNumElements(); ++i) { - cpuSerial.append(cpuField->getValue(i).toUInt()); - } return cpuSerial; } quint32 UAVObjectUtilManager::getFirmwareCRC() { - quint32 fwCRC; - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - if (!pm) - return 0; - UAVObjectManager *om = pm->getObject(); - if (!om) - return 0; - - UAVDataObject *obj = dynamic_cast(om->getObject(QString("FirmwareIAPObj"))); - obj->getField("crc")->setValue(0); - obj->updated(); - // The code below will ask for the object update and wait for the updated to be received, - // or the timeout of the timer, set to 1 second. - QEventLoop loop; - connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit())); - QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout - obj->requestUpdate(); - loop.exec(); - - UAVObjectField* fwCRCField = obj->getField("crc"); - - fwCRC=(quint32)fwCRCField->getValue().toLongLong(); - return fwCRC; + FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap(); + return firmwareIapData.crc; } /** @@ -308,27 +294,11 @@ quint32 UAVObjectUtilManager::getFirmwareCRC() QByteArray UAVObjectUtilManager::getBoardDescription() { QByteArray ret; - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - if (!pm) - return 0; - UAVObjectManager *om = pm->getObject(); - if (!om) - return 0; + FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap(); - UAVDataObject *obj = dynamic_cast(om->getObject(QString("FirmwareIAPObj"))); - // The code below will ask for the object update and wait for the updated to be received, - // or the timeout of the timer, set to 1 second. - QEventLoop loop; - connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit())); - QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout - obj->requestUpdate(); - loop.exec(); + for (int i = 0; i < FirmwareIAPObj::DESCRIPTION_NUMELEM; i++) + ret.append(firmwareIapData.Description[i]); - UAVObjectField* descriptionField = obj->getField("Description"); - // Description starts with an offset of - for (uint i = 0; i < descriptionField->getNumElements(); ++i) { - ret.append(descriptionField->getValue(i).toInt()); - } return ret; } diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.h b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.h index 6c7782b25..6f71123b8 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.h +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.h @@ -43,6 +43,8 @@ #include #include #include +#include + class UAVOBJECTUTIL_EXPORT UAVObjectUtilManager: public QObject { Q_OBJECT @@ -69,6 +71,8 @@ public: static bool descriptionToStructure(QByteArray desc,deviceDescriptorStruct * struc); UAVObjectManager* getObjectManager(); void saveObjectToSD(UAVObject *obj); +protected: + FirmwareIAPObj::DataFields getFirmwareIap(); signals: void saveCompleted(int objectID, bool status); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 4bb570295..7fb8d70c7 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -26,12 +26,13 @@ */ #include "configtaskwidget.h" #include +#include #include "uavsettingsimportexport/uavsettingsimportexportfactory.h" /** * Constructor */ -ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);") +ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL),allowWidgetUpdates(true) { pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); @@ -126,7 +127,7 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel Q_ASSERT(obj); objectUpdates.insert(obj,true); connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*))); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues())); + connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*)), Qt::UniqueConnection); } if(!field.isEmpty() && obj) _field = obj->getField(QString(field)); @@ -175,6 +176,10 @@ ConfigTaskWidget::~ConfigTaskWidget() if(oTw) delete oTw; } + if(timeOut) + { + delete timeOut; + } } void ConfigTaskWidget::saveObjectToSD(UAVObject *obj) @@ -251,8 +256,11 @@ void ConfigTaskWidget::populateWidgets() * object field added to the framework pool * Overwrite this if you need to change the default behavior */ -void ConfigTaskWidget::refreshWidgetsValues() +void ConfigTaskWidget::refreshWidgetsValues(UAVObject * obj) { + if (!allowWidgetUpdates) + return; + bool dirtyBack=dirty; emit refreshWidgetsValuesRequested(); foreach(objectToWidget * ow,objOfInterest) @@ -263,8 +271,8 @@ void ConfigTaskWidget::refreshWidgetsValues() } else { - setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale,ow->isLimited); - + if(ow->object==obj || obj==NULL) + setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale,ow->isLimited); } } @@ -367,7 +375,7 @@ void ConfigTaskWidget::forceShadowUpdates() setDirty(true); } /** - * SLOT function called when on of the widgets contents added to the framework changes + * SLOT function called when one of the widgets contents added to the framework changes */ void ConfigTaskWidget::widgetsContentsChanged() { @@ -412,7 +420,8 @@ void ConfigTaskWidget::widgetsContentsChanged() } } } - smartsave->resetIcons(); + if(smartsave) + smartsave->resetIcons(); setDirty(true); } /** @@ -446,10 +455,10 @@ bool ConfigTaskWidget::isDirty() */ void ConfigTaskWidget::disableObjUpdates() { + allowWidgetUpdates = false; foreach(objectToWidget * obj,objOfInterest) { - if(obj->object) - disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues())); + if(obj->object)disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*))); } } /** @@ -457,10 +466,11 @@ void ConfigTaskWidget::disableObjUpdates() */ void ConfigTaskWidget::enableObjUpdates() { + allowWidgetUpdates = true; foreach(objectToWidget * obj,objOfInterest) { if(obj->object) - connect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues())); + connect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*)), Qt::UniqueConnection); } } /** @@ -779,7 +789,7 @@ void ConfigTaskWidget::reloadButtonClicked() if(!list) return; ObjectPersistence* objper = dynamic_cast( getObjectManager()->getObject(ObjectPersistence::NAME) ); - QTimer * timeOut=new QTimer(this); + timeOut=new QTimer(this); QEventLoop * eventLoop=new QEventLoop(this); connect(timeOut, SIGNAL(timeout()),eventLoop,SLOT(quit())); connect(objper, SIGNAL(objectUpdated(UAVObject*)), eventLoop, SLOT(quit())); @@ -798,13 +808,22 @@ void ConfigTaskWidget::reloadButtonClicked() eventLoop->exec(); if(timeOut->isActive()) { + oTw->object->requestUpdate(); setWidgetFromField(oTw->widget,oTw->field,oTw->index,oTw->scale,oTw->isLimited); } timeOut->stop(); } } - delete eventLoop; - delete timeOut; + if(eventLoop) + { + delete eventLoop; + eventLoop=NULL; + } + if(timeOut) + { + delete timeOut; + timeOut=NULL; + } } /** @@ -944,6 +963,10 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget * widget,double scale) { return (QString)(cb->isChecked()?"TRUE":"FALSE"); } + else if(QLineEdit * cb=qobject_cast(widget)) + { + return (QString)cb->displayText(); + } else return QVariant(); } @@ -990,6 +1013,14 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou cb->setChecked(bvalue); return true; } + else if(QLineEdit * cb=qobject_cast(widget)) + { + if(scale==0) + cb->setText(value.toString()); + else + cb->setText(QString::number((value.toDouble()/scale))); + return true; + } else return false; } @@ -1144,6 +1175,35 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field, } } +void ConfigTaskWidget::disableMouseWheelEvents() +{ + //Disable mouse wheel events + foreach( QSpinBox * sp, findChildren() ) { + sp->installEventFilter( this ); + } + foreach( QDoubleSpinBox * sp, findChildren() ) { + sp->installEventFilter( this ); + } + foreach( QSlider * sp, findChildren() ) { + sp->installEventFilter( this ); + } + foreach( QComboBox * sp, findChildren() ) { + sp->installEventFilter( this ); + } +} + +bool ConfigTaskWidget::eventFilter( QObject * obj, QEvent * evt ) { + //Filter all wheel events, and ignore them + if ( evt->type() == QEvent::Wheel && + (qobject_cast( obj ) || + qobject_cast( obj ) || + qobject_cast( obj ) )) + { + evt->ignore(); + return true; + } + return QWidget::eventFilter( obj, evt ); +} /** @} @} diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index deb297e32..76d6b55bd 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -46,6 +46,7 @@ #include "uavobjectwidgetutils_global.h" #include #include +#include class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget: public QWidget { @@ -85,6 +86,9 @@ public: ConfigTaskWidget(QWidget *parent = 0); ~ConfigTaskWidget(); + void disableMouseWheelEvents(); + bool eventFilter( QObject * obj, QEvent * evt ); + void saveObjectToSD(UAVObject *obj); UAVObjectManager* getObjectManager(); static double listMean(QList list); @@ -141,6 +145,7 @@ private slots: void reloadButtonClicked(); private: bool isConnected; + bool allowWidgetUpdates; QStringList objectsList; QList objOfInterest; ExtensionSystem::PluginManager *pm; @@ -160,13 +165,14 @@ private: void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function); void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale); QString outOfLimitsStyle; + QTimer * timeOut; protected slots: virtual void disableObjUpdates(); virtual void enableObjUpdates(); virtual void clearDirty(); virtual void widgetsContentsChanged(); virtual void populateWidgets(); - virtual void refreshWidgetsValues(); + virtual void refreshWidgetsValues(UAVObject * obj=NULL); virtual void updateObjectsFromWidgets(); virtual void helpButtonPressed(); protected: diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp index 31ae969eb..9b0268a4e 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp @@ -77,7 +77,7 @@ void smartSaveButton::processOperation(QPushButton * button,bool save) foreach(UAVDataObject * obj,objects) { UAVObject::Metadata mdata= obj->getMetadata(); - if(mdata.gcsAccess==UAVObject::ACCESS_READONLY) + if(UAVObject::GetGcsAccess(mdata)==UAVObject::ACCESS_READONLY) continue; up_result=false; current_object=obj; @@ -87,7 +87,7 @@ void smartSaveButton::processOperation(QPushButton * button,bool save) connect(obj,SIGNAL(transactionCompleted(UAVObject*,bool)),this,SLOT(transaction_finished(UAVObject*, bool))); connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); obj->updated(); - timer.start(1000); + timer.start(3000); //qDebug()<<"begin loop"; loop.exec(); //qDebug()<<"end loop"; @@ -113,7 +113,7 @@ void smartSaveButton::processOperation(QPushButton * button,bool save) connect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); utilMngr->saveObjectToSD(obj); - timer.start(1000); + timer.start(3000); loop.exec(); timer.stop(); disconnect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/importsummary.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/importsummary.cpp index a7bf6f367..eb45634ff 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/importsummary.cpp +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/importsummary.cpp @@ -71,18 +71,23 @@ void ImportSummaryDialog::addLine(QString uavObjectName, QString text, bool stat { ui->importSummaryList->setRowCount(ui->importSummaryList->rowCount()+1); int row = ui->importSummaryList->rowCount()-1; - ui->progressBar->setMaximum(row); ui->importSummaryList->setCellWidget(row,0,new QCheckBox(ui->importSummaryList)); QTableWidgetItem *objName = new QTableWidgetItem(uavObjectName); ui->importSummaryList->setItem(row, 1, objName); QCheckBox *box = dynamic_cast(ui->importSummaryList->cellWidget(row,0)); ui->importSummaryList->setItem(row,2,new QTableWidgetItem(text)); + + //Disable editability and selectability in table elements + ui->importSummaryList->item(row,1)->setFlags(!Qt::ItemIsEditable); + ui->importSummaryList->item(row,2)->setFlags(!Qt::ItemIsEditable); + if (status) { box->setChecked(true); } else { box->setChecked(false); box->setEnabled(false); } + this->repaint(); this->showEvent(NULL); } @@ -92,11 +97,22 @@ void ImportSummaryDialog::addLine(QString uavObjectName, QString text, bool stat */ void ImportSummaryDialog::doTheSaving() { + int itemCount=0; ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); UAVObjectUtilManager *utilManager = pm->getObject(); connect(utilManager, SIGNAL(saveCompleted(int,bool)), this, SLOT(updateSaveCompletion())); + for(int i=0; i < ui->importSummaryList->rowCount(); i++) { + QCheckBox *box = dynamic_cast(ui->importSummaryList->cellWidget(i,0)); + if (box->isChecked()) { + ++itemCount; + } + } + if(itemCount==0) + return; + ui->progressBar->setMaximum(itemCount+1); + ui->progressBar->setValue(1); for(int i=0; i < ui->importSummaryList->rowCount(); i++) { QString uavObjectName = ui->importSummaryList->item(i,1)->text(); QCheckBox *box = dynamic_cast(ui->importSummaryList->cellWidget(i,0)); @@ -106,12 +122,21 @@ void ImportSummaryDialog::doTheSaving() this->repaint(); } } + + ui->saveToFlash->setEnabled(false); + ui->closeButton->setEnabled(false); + } void ImportSummaryDialog::updateSaveCompletion() { ui->progressBar->setValue(ui->progressBar->value()+1); + if(ui->progressBar->value()==ui->progressBar->maximum()) + { + ui->saveToFlash->setEnabled(true); + ui->closeButton->setEnabled(true); + } } void ImportSummaryDialog::changeEvent(QEvent *e) diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp index 3552ad752..9c0088efa 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp @@ -79,14 +79,14 @@ UAVSettingsImportExportFactory::UAVSettingsImportExportFactory(QObject *parent): ac->addAction(cmd, Core::Constants::G_FILE_SAVE); connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(importUAVSettings())); + ac = am->actionContainer(Core::Constants::M_HELP); cmd = am->registerAction(new QAction(this), "UAVSettingsImportExportPlugin.UAVDataExport", QList() << Core::Constants::C_GLOBAL_ID); cmd->action()->setText(tr("Export UAV Data...")); - ac->addAction(cmd, Core::Constants::G_FILE_SAVE); + ac->addAction(cmd, Core::Constants::G_HELP_HELP); connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVData())); - } // Slot called by the menu manager on user action diff --git a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp index 186233ca0..c1463013a 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp @@ -27,6 +27,8 @@ #include "telemetry.h" #include "qxtlogger.h" +#include "pipxsettings.h" +#include "objectpersistence.h" #include #include #include @@ -77,7 +79,7 @@ void Telemetry::registerObject(UAVObject* obj) addObject(obj); // Setup object for telemetry updates - updateObject(obj); + updateObject(obj, EV_NONE); } /** @@ -142,6 +144,10 @@ void Telemetry::connectToObjectInstances(UAVObject* obj, quint32 eventMask) { connect(objs[n], SIGNAL(objectUpdatedManual(UAVObject*)), this, SLOT(objectUpdatedManual(UAVObject*))); } + if ( (eventMask&EV_UPDATED_PERIODIC) != 0) + { + connect(objs[n], SIGNAL(objectUpdatedPeriodic(UAVObject*)), this, SLOT(objectUpdatedPeriodic(UAVObject*))); + } if ( (eventMask&EV_UPDATE_REQ) != 0) { connect(objs[n], SIGNAL(updateRequested(UAVObject*)), this, SLOT(updateRequested(UAVObject*))); @@ -152,26 +158,27 @@ void Telemetry::connectToObjectInstances(UAVObject* obj, quint32 eventMask) /** * Update an object based on its metadata properties */ -void Telemetry::updateObject(UAVObject* obj) +void Telemetry::updateObject(UAVObject* obj, quint32 eventType) { // Get metadata UAVObject::Metadata metadata = obj->getMetadata(); + UAVObject::UpdateMode updateMode = UAVObject::GetGcsTelemetryUpdateMode(metadata); // Setup object depending on update mode qint32 eventMask; - if ( metadata.gcsTelemetryUpdateMode == UAVObject::UPDATEMODE_PERIODIC ) + if ( updateMode == UAVObject::UPDATEMODE_PERIODIC ) { // Set update period setUpdatePeriod(obj, metadata.gcsTelemetryUpdatePeriod); // Connect signals for all instances - eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; + eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ | EV_UPDATED_PERIODIC; if( dynamic_cast(obj) != NULL ) { eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) } connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject::UPDATEMODE_ONCHANGE ) + else if ( updateMode == UAVObject::UPDATEMODE_ONCHANGE ) { // Set update period setUpdatePeriod(obj, 0); @@ -183,7 +190,29 @@ void Telemetry::updateObject(UAVObject* obj) } connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject::UPDATEMODE_MANUAL ) + else if ( updateMode == UAVObject::UPDATEMODE_THROTTLED ) + { + // If we received a periodic update, we can change back to update on change + if ((eventType == EV_UPDATED_PERIODIC) || (eventType == EV_NONE)) { + // Set update period + if (eventType == EV_NONE) + setUpdatePeriod(obj, metadata.gcsTelemetryUpdatePeriod); + // Connect signals for all instances + eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ | EV_UPDATED_PERIODIC; + } + else + { + // Otherwise, we just received an object update, so switch to periodic for the timeout period to prevent more updates + // Connect signals for all instances + eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ; + } + if( dynamic_cast(obj) != NULL ) + { + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + } + connectToObjectInstances(obj, eventMask); + } + else if ( updateMode == UAVObject::UPDATEMODE_MANUAL ) { // Set update period setUpdatePeriod(obj, 0); @@ -195,13 +224,6 @@ void Telemetry::updateObject(UAVObject* obj) } connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject::UPDATEMODE_NEVER ) - { - // Set update period - setUpdatePeriod(obj, 0); - // Disconnect from object - connectToObjectInstances(obj, 0); - } } /** @@ -373,7 +395,7 @@ void Telemetry::processObjectQueue() if ( gcsStats.Status != GCSTelemetryStats::STATUS_CONNECTED ) { objQueue.clear(); - if ( objInfo.obj->getObjID() != GCSTelemetryStats::OBJID ) + if ( objInfo.obj->getObjID() != GCSTelemetryStats::OBJID && objInfo.obj->getObjID() != PipXSettings::OBJID && objInfo.obj->getObjID() != ObjectPersistence::OBJID ) { objInfo.obj->emitTransactionCompleted(false); return; @@ -381,14 +403,16 @@ void Telemetry::processObjectQueue() } // Setup transaction (skip if unpack event) - if ( objInfo.event != EV_UNPACKED ) + UAVObject::Metadata metadata = objInfo.obj->getMetadata(); + UAVObject::UpdateMode updateMode = UAVObject::GetGcsTelemetryUpdateMode(metadata); + if ( ( objInfo.event != EV_UNPACKED ) && ( ( objInfo.event != EV_UPDATED_PERIODIC ) || ( updateMode != UAVObject::UPDATEMODE_THROTTLED ) ) ) { UAVObject::Metadata metadata = objInfo.obj->getMetadata(); transInfo.obj = objInfo.obj; transInfo.allInstances = objInfo.allInstances; transInfo.retriesRemaining = MAX_RETRIES; - transInfo.acked = metadata.gcsTelemetryAcked; - if ( objInfo.event == EV_UPDATED || objInfo.event == EV_UPDATED_MANUAL ) + transInfo.acked = UAVObject::GetGcsTelemetryAcked(metadata); + if ( objInfo.event == EV_UPDATED || objInfo.event == EV_UPDATED_MANUAL || objInfo.event == EV_UPDATED_PERIODIC ) { transInfo.objRequest = false; } @@ -408,7 +432,11 @@ void Telemetry::processObjectQueue() UAVMetaObject* metaobj = dynamic_cast(objInfo.obj); if ( metaobj != NULL ) { - updateObject( metaobj->getParentObject() ); + updateObject( metaobj->getParentObject(), EV_NONE ); + } + else if ( updateMode != UAVObject::UPDATEMODE_THROTTLED ) + { + updateObject( objInfo.obj, objInfo.event ); } // The fact we received an unpacked event does not mean that @@ -417,7 +445,6 @@ void Telemetry::processObjectQueue() // stuck: if ( objInfo.event == EV_UNPACKED ) processObjectQueue(); - } /** @@ -453,7 +480,7 @@ void Telemetry::processPeriodicUpdates() objinfo->timeToNextUpdateMs = objinfo->updatePeriodMs - offset; // Send object time.start(); - processObjectUpdates(objinfo->obj, EV_UPDATED_MANUAL, true, false); + processObjectUpdates(objinfo->obj, EV_UPDATED_PERIODIC, true, false); elapsedMs = time.elapsed(); // Update timeToNextUpdateMs with the elapsed delay of sending the object; timeToNextUpdateMs += elapsedMs; @@ -522,6 +549,12 @@ void Telemetry::objectUpdatedManual(UAVObject* obj) processObjectUpdates(obj, EV_UPDATED_MANUAL, false, true); } +void Telemetry::objectUpdatedPeriodic(UAVObject* obj) +{ + QMutexLocker locker(mutex); + processObjectUpdates(obj, EV_UPDATED_PERIODIC, false, true); +} + void Telemetry::objectUnpacked(UAVObject* obj) { QMutexLocker locker(mutex); diff --git a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.h b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.h index 62210e8da..f703f636b 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.h +++ b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.h @@ -63,6 +63,7 @@ signals: private slots: void objectUpdatedAuto(UAVObject* obj); void objectUpdatedManual(UAVObject* obj); + void objectUpdatedPeriodic(UAVObject* obj); void objectUnpacked(UAVObject* obj); void updateRequested(UAVObject* obj); void newObject(UAVObject* obj); @@ -84,10 +85,12 @@ private: * Events generated by objects */ typedef enum { + EV_NONE = 0x00, /** No event */ EV_UNPACKED = 0x01, /** Object data updated by unpacking */ EV_UPDATED = 0x02, /** Object data updated by changing the data structure */ EV_UPDATED_MANUAL = 0x04, /** Object update event manually generated */ - EV_UPDATE_REQ = 0x08 /** Request to update object data */ + EV_UPDATED_PERIODIC = 0x8, /** Object update event generated by timer */ + EV_UPDATE_REQ = 0x010 /** Request to update object data */ } EventMask; typedef struct { @@ -132,7 +135,7 @@ private: void addObject(UAVObject* obj); void setUpdatePeriod(UAVObject* obj, qint32 periodMs); void connectToObjectInstances(UAVObject* obj, quint32 eventMask); - void updateObject(UAVObject* obj); + void updateObject(UAVObject* obj, quint32 eventMask); void processObjectUpdates(UAVObject* obj, EventMask event, bool allInstances, bool priority); void processObjectTransaction(); void processObjectQueue(); diff --git a/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.cpp b/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.cpp index 9bfed2109..881e1bc7d 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.cpp @@ -77,25 +77,22 @@ void TelemetryMonitor::startRetrievingObjects() UAVMetaObject* mobj = dynamic_cast(obj); UAVDataObject* dobj = dynamic_cast(obj); UAVObject::Metadata mdata = obj->getMetadata(); - if ( mdata.gcsTelemetryUpdateMode != UAVObject::UPDATEMODE_NEVER ) + if ( mobj != NULL ) { - if ( mobj != NULL ) + queue.enqueue(obj); + } + else if ( dobj != NULL ) + { + if ( dobj->isSettings() ) { queue.enqueue(obj); } - else if ( dobj != NULL ) + else { - if ( dobj->isSettings() ) + if ( UAVObject::GetFlightTelemetryUpdateMode(mdata) == UAVObject::UPDATEMODE_ONCHANGE ) { queue.enqueue(obj); } - else - { - if ( mdata.flightTelemetryUpdateMode == UAVObject::UPDATEMODE_ONCHANGE ) - { - queue.enqueue(obj); - } - } } } } diff --git a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp index 4c218379d..03da96a6f 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp @@ -112,10 +112,12 @@ void UAVTalk::processInputStream() { quint8 tmp; - while (io->bytesAvailable() > 0) - { - io->read((char*)&tmp, 1); - processInputByte(tmp); + if (io && io->isReadable()) { + while (io->bytesAvailable() > 0) + { + io->read((char*)&tmp, 1); + processInputByte(tmp); + } } } @@ -719,9 +721,8 @@ bool UAVTalk::transmitNack(quint32 objId) qToLittleEndian(dataOffset, &txBuffer[2]); - // Send buffer, check that the transmit backlog does not grow above limit - if ( io->bytesToWrite() < TX_BUFFER_SIZE ) + if (io && io->isWritable() && io->bytesToWrite() < TX_BUFFER_SIZE ) { io->write((const char*)txBuffer, dataOffset+CHECKSUM_LENGTH); } @@ -811,7 +812,7 @@ bool UAVTalk::transmitSingleObject(UAVObject* obj, quint8 type, bool allInstance txBuffer[dataOffset+length] = updateCRC(0, txBuffer, dataOffset + length); // Send buffer, check that the transmit backlog does not grow above limit - if ( io->bytesToWrite() < TX_BUFFER_SIZE ) + if (io && io->isWritable() && io->bytesToWrite() < TX_BUFFER_SIZE ) { io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); } diff --git a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h index 163fb9fa3..de7ca8542 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h +++ b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h @@ -27,6 +27,7 @@ #ifndef UAVTALK_H #define UAVTALK_H +#include #include #include #include @@ -93,7 +94,7 @@ private: typedef enum {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS} RxStateType; // Variables - QIODevice* io; + QPointer io; UAVObjectManager* objMngr; QMutex* mutex; UAVObject* respObj; diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp index eca8728f8..e3ca707b3 100644 --- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp @@ -78,27 +78,6 @@ void deviceWidget::setDfu(DFUObject *dfu) m_dfu = dfu; } -QString deviceWidget::idToBoardName(int id) -{ - switch (id | 0x0011) { - case 0x0111://MB - return QString("OpenPilot MainBoard"); - break; - case 0x0311://PipX - return QString("PipXtreme"); - break; - case 0x0411://Coptercontrol - return QString("CopterControl"); - break; - case 0x0211://INS - return QString("OpenPilot INS"); - break; - default: - return QString(""); - break; - } -} - /** Fills the various fields for the device */ @@ -125,6 +104,9 @@ void deviceWidget::populate() case 0x0401: devicePic->renderer()->load(QString(":/uploader/images/deviceID-0401.svg")); break; + case 0x0402: + devicePic->renderer()->load(QString(":/uploader/images/deviceID-0402.svg")); + break; case 0x0201: devicePic->renderer()->load(QString(":/uploader/images/deviceID-0201.svg")); break; @@ -200,7 +182,7 @@ bool deviceWidget::populateBoardStructuredDescription(QByteArray desc) myDevice->lblCertified->setToolTip(tr("Untagged or custom firmware build")); } - myDevice->lblBrdName->setText(idToBoardName(onBoardDescription.boardType<<8)); + myDevice->lblBrdName->setText(deviceDescriptorStruct::idToBoardName(onBoardDescription.boardType << 8 | onBoardDescription.boardRevision)); return true; } @@ -230,7 +212,7 @@ bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc) myDevice->lblCertifiedL->setPixmap(pix); myDevice->lblCertifiedL->setToolTip(tr("Untagged or custom firmware build")); } - myDevice->lblBrdNameL->setText(deviceDescriptorStruct::idToBoardName(LoadedDescription.boardType<<8)); + myDevice->lblBrdNameL->setText(deviceDescriptorStruct::idToBoardName(LoadedDescription.boardType << 8 | LoadedDescription.boardRevision)); return true; } @@ -378,7 +360,10 @@ void deviceWidget::uploadFirmware() // - Check whether board type matches firmware: int board = m_dfu->devices[deviceID].ID; int firmwareBoard = ((desc.at(12)&0xff)<<8) + (desc.at(13)&0xff); - if (firmwareBoard != board) { + if((board == 0x401 && firmwareBoard == 0x402) || + (board == 0x901 && firmwareBoard == 0x902)) { + // These firmwares are designed to be backwards compatible + } else if (firmwareBoard != board) { status("Error: firmware does not match board", STATUSICON_FAIL); myDevice->updateButton->setEnabled(true); return; @@ -401,10 +386,12 @@ void deviceWidget::uploadFirmware() status("Starting firmware upload", STATUSICON_RUNNING); // We don't know which device was used previously, so we // are cautious and reenter DFU for this deviceID: + emit uploadStarted(); if(!m_dfu->enterDFU(deviceID)) { status("Error:Could not enter DFU mode", STATUSICON_FAIL); myDevice->updateButton->setEnabled(true); + emit uploadEnded(false); return; } OP_DFU::Status ret=m_dfu->StatusRequest(); @@ -418,6 +405,7 @@ void deviceWidget::uploadFirmware() if(!retstatus ) { status("Could not start upload", STATUSICON_FAIL); myDevice->updateButton->setEnabled(true); + emit uploadEnded(false); return; } status("Uploading, please wait...", STATUSICON_RUNNING); @@ -477,6 +465,7 @@ void deviceWidget::uploadFinished(OP_DFU::Status retstatus) disconnect(m_dfu, SIGNAL(operationProgress(QString)), this, SLOT(dfuStatus(QString))); if(retstatus != OP_DFU::Last_operation_Success) { status(QString("Upload failed with code: ") + m_dfu->StatusToString(retstatus).toLatin1().data(), STATUSICON_FAIL); + emit uploadEnded(false); return; } else if (!descriptionArray.isEmpty()) { @@ -486,6 +475,7 @@ void deviceWidget::uploadFinished(OP_DFU::Status retstatus) retstatus = m_dfu->UploadDescription(descriptionArray); if( retstatus != OP_DFU::Last_operation_Success) { status(QString("Upload failed with code: ") + m_dfu->StatusToString(retstatus).toLatin1().data(), STATUSICON_FAIL); + emit uploadEnded(false); return; } @@ -496,10 +486,12 @@ void deviceWidget::uploadFinished(OP_DFU::Status retstatus) retstatus = m_dfu->UploadDescription(myDevice->description->text()); if( retstatus != OP_DFU::Last_operation_Success) { status(QString("Upload failed with code: ") + m_dfu->StatusToString(retstatus).toLatin1().data(), STATUSICON_FAIL); + emit uploadEnded(false); return; } } populate(); + emit uploadEnded(true); status("Upload successful", STATUSICON_OK); } @@ -513,22 +505,47 @@ void deviceWidget::setProgress(int percent) } /** - -Opens an open file dialog. - -*/ + *Opens an open file dialog. + */ QString deviceWidget::setOpenFileName() { QFileDialog::Options options; QString selectedFilter; + QString fwDirectoryStr; + QDir fwDirectory; + + //Format filename for file chooser +#ifdef Q_OS_WIN + fwDirectoryStr=QCoreApplication::applicationDirPath(); + fwDirectory=QDir(fwDirectoryStr); + fwDirectory.cdUp(); + fwDirectory.cd("firmware"); + fwDirectoryStr=fwDirectory.absolutePath(); +#elif defined Q_OS_LINUX + fwDirectoryStr=QCoreApplication::applicationDirPath(); + fwDirectory=QDir(fwDirectoryStr); + fwDirectory.cd("../../.."); + fwDirectoryStr=fwDirectory.absolutePath(); + fwDirectoryStr=fwDirectoryStr+"/fw_"+myDevice->lblBrdName->text().toLower()+"/fw_"+myDevice->lblBrdName->text().toLower()+".opfw"; +#elif defined Q_OS_MAC + fwDirectoryStr=QCoreApplication::applicationDirPath(); + fwDirectory=QDir(fwDirectoryStr); + fwDirectory.cd("../../../../../.."); + fwDirectoryStr=fwDirectory.absolutePath(); + fwDirectoryStr=fwDirectoryStr+"/fw_"+myDevice->lblBrdName->text().toLower()+"/fw_"+myDevice->lblBrdName->text().toLower()+".opfw"; +#endif QString fileName = QFileDialog::getOpenFileName(this, tr("Select firmware file"), - "", + fwDirectoryStr, tr("Firmware Files (*.opfw *.bin)"), &selectedFilter, options); return fileName; } + +/** + *Set the save file name + */ QString deviceWidget::setSaveFileName() { QFileDialog::Options options; diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.h b/ground/openpilotgcs/src/plugins/uploader/devicewidget.h index 3530c3d6a..202023d50 100644 --- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.h @@ -40,6 +40,8 @@ #include #include "uavobjectutilmanager.h" #include "devicedescriptorstruct.h" +#include +#include using namespace OP_DFU; class deviceWidget : public QWidget { @@ -57,7 +59,6 @@ private: deviceDescriptorStruct onBoardDescription; deviceDescriptorStruct LoadedDescription; QByteArray loadedFW; - QString idToBoardName(int id); Ui_deviceWidget *myDevice; int deviceID; DFUObject *m_dfu; @@ -70,7 +71,8 @@ private: bool populateLoadedStructuredDescription(QByteArray arr); signals: - + void uploadStarted(); + void uploadEnded(bool success); public slots: void uploadFirmware(); void loadFirmware(); diff --git a/ground/openpilotgcs/src/plugins/uploader/images/deviceID-0402.svg b/ground/openpilotgcs/src/plugins/uploader/images/deviceID-0402.svg new file mode 100644 index 000000000..90121943d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uploader/images/deviceID-0402.svg @@ -0,0 +1,2389 @@ + + + +image/svg+xmlCC3D + \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.ui b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.ui index c01332629..b873ded19 100644 --- a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.ui +++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.ui @@ -15,7 +15,7 @@ - + Device Information @@ -92,7 +92,7 @@ - + Firmware Information diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.qrc b/ground/openpilotgcs/src/plugins/uploader/uploader.qrc index 7d2677927..083eab94d 100644 --- a/ground/openpilotgcs/src/plugins/uploader/uploader.qrc +++ b/ground/openpilotgcs/src/plugins/uploader/uploader.qrc @@ -12,5 +12,6 @@ images/application-certificate.svg images/warning.svg images/error.svg + images/deviceID-0402.svg diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp index 31788eb57..a1008306c 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -116,6 +116,12 @@ QString UploaderGadgetWidget::getPortDevice(const QString &friendName) } return ""; } + +void UploaderGadgetWidget::connectSignalSlot(QWidget *widget) +{ + connect(qobject_cast(widget),SIGNAL(uploadStarted()),this,SLOT(uploadStarted())); + connect(qobject_cast(widget),SIGNAL(uploadEnded(bool)),this,SLOT(uploadEnded(bool))); +} void UploaderGadgetWidget::onPhisicalHWConnect() { m_config->bootButton->setEnabled(false); @@ -305,6 +311,7 @@ void UploaderGadgetWidget::goToBootloader(UAVObject* callerObj, bool success) } for(int i=0;inumberOfDevices;i++) { deviceWidget* dw = new deviceWidget(this); + connectSignalSlot(dw); dw->setDeviceID(i); dw->setDfu(dfu); dw->populate(); @@ -540,6 +547,7 @@ void UploaderGadgetWidget::systemRescue() } for(int i=0;inumberOfDevices;i++) { deviceWidget* dw = new deviceWidget(this); + connectSignalSlot(dw); dw->setDeviceID(i); dw->setDfu(dfu); dw->populate(); @@ -567,6 +575,19 @@ void UploaderGadgetWidget::cancel() m_eventloop.exit(); } +void UploaderGadgetWidget::uploadStarted() +{ + m_config->bootButton->setEnabled(false); + m_config->safeBootButton->setEnabled(false); +} + +void UploaderGadgetWidget::uploadEnded(bool succeed) +{ + Q_UNUSED(succeed); + m_config->bootButton->setEnabled(true); + m_config->safeBootButton->setEnabled(true); +} + /** Update log entry */ diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h index 2c6814827..5f5706381 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h @@ -88,6 +88,7 @@ private: QLineEdit* openFileNameLE; QEventLoop m_eventloop; QErrorMessage * msg; + void connectSignalSlot(QWidget * widget); private slots: void onPhisicalHWConnect(); void versionMatchCheck(); @@ -102,6 +103,8 @@ private slots: void getSerialPorts(); void perform(); void cancel(); + void uploadStarted(); + void uploadEnded(bool succeed); }; diff --git a/ground/openpilotgcs/src/plugins/welcome/qml/main.qml b/ground/openpilotgcs/src/plugins/welcome/qml/main.qml index 764ce36a5..a2362d3e2 100644 --- a/ground/openpilotgcs/src/plugins/welcome/qml/main.qml +++ b/ground/openpilotgcs/src/plugins/welcome/qml/main.qml @@ -51,37 +51,37 @@ Rectangle { WelcomePageButton { baseIconName: "flightdata" label: "Flight Data" - onClicked: welcomePlugin.openPage("Mode1") + onClicked: welcomePlugin.openPage("Flight data") } WelcomePageButton { baseIconName: "config" label: "Configuration" - onClicked: welcomePlugin.openPage("Mode2") + onClicked: welcomePlugin.openPage("Configuration") } WelcomePageButton { baseIconName: "planner" label: "Flight Planner" - onClicked: welcomePlugin.openPage("Mode3") + onClicked: welcomePlugin.openPage("Flight Planner") } WelcomePageButton { baseIconName: "scopes" label: "Scopes" - onClicked: welcomePlugin.openPage("Mode4") + onClicked: welcomePlugin.openPage("Scopes") } WelcomePageButton { baseIconName: "hitl" - label: "HIL" - onClicked: welcomePlugin.openPage("Mode5") + label: "HITL" + onClicked: welcomePlugin.openPage("HITL") } WelcomePageButton { baseIconName: "firmware" label: "Firmware" - onClicked: welcomePlugin.openPage("Mode6") + onClicked: welcomePlugin.openPage("Firmware") } } //icons grid } // images row diff --git a/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp b/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp index f08a58420..cf36b3036 100644 --- a/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp +++ b/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp @@ -124,7 +124,7 @@ void WelcomeMode::openUrl(const QString &url) void WelcomeMode::openPage(const QString &page) { - Core::ModeManager::instance()->activateMode(page); + Core::ModeManager::instance()->activateModeByWorkspaceName(page); } } // namespace Welcome diff --git a/ground/uavobjgenerator/generators/generator_common.cpp b/ground/uavobjgenerator/generators/generator_common.cpp index cd67b0899..34f097e44 100644 --- a/ground/uavobjgenerator/generators/generator_common.cpp +++ b/ground/uavobjgenerator/generators/generator_common.cpp @@ -38,7 +38,7 @@ void replaceCommonTags(QString& out, ObjectInfo* info) QStringList updateModeStr,accessModeStr; updateModeStr << "UPDATEMODE_PERIODIC" << "UPDATEMODE_ONCHANGE" - << "UPDATEMODE_MANUAL" << "UPDATEMODE_NEVER"; + << "UPDATEMODE_THROTTLED" << "UPDATEMODE_MANUAL"; accessModeStr << "ACCESS_READWRITE" << "ACCESS_READONLY"; diff --git a/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp b/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp index cac8db9c7..97e3e9e92 100644 --- a/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp +++ b/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp @@ -79,7 +79,7 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) QString objectTableName(objectName); QString tableIdxName(objectName.toLower() + "Idx"); QString functionName("Read" + info->name + "Object"); - QString functionCall(functionName + "(fid, timestamp, "); + QString functionCall(functionName + "(fid, timestamp, checkCRC, "); QString objectID(QString().setNum(info->id)); QString isSingleInst = boolTo01String( info->isSingleInst ); @@ -133,7 +133,7 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) // matlabSwitchCode.append("\t\t\t" + objectTableName + "(" + tableIdxName +") = " + functionCall + ";\n"); matlabSwitchCode.append("\t\t\t" + tableIdxName + " = " + tableIdxName +" + 1;\n"); matlabSwitchCode.append("\t\t\t" + objectTableName + "= " + functionCall + objectTableName + ", " + tableIdxName + ");\n"); - matlabSwitchCode.append("\t\t\tif " + tableIdxName + " >= length(" + objectTableName +") %Check to see if pre-allocated memory is exhausted\n"); + matlabSwitchCode.append("\t\t\tif " + tableIdxName + " >= length(" + objectTableName +".timestamp) %Check to see if pre-allocated memory is exhausted\n"); matlabSwitchCode.append("\t\t\t\tFieldNames= fieldnames(" + objectTableName +");\n"); matlabSwitchCode.append("\t\t\t\tfor i=1:length(FieldNames) %Grow structure\n"); matlabSwitchCode.append("\t\t\t\t\t" + objectTableName + ".(FieldNames{i})(:," + tableIdxName + "*2+1) = 0;\n"); @@ -166,6 +166,8 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) matlabFunctionsCode.append("%%\n% " + objectName + " read function\n"); matlabFunctionsCode.append("function [" + objectName + "] = " + functionCall + objectTableName + ", " + tableIdxName + ")" + "\n"); + + matlabFunctionsCode.append("\t" + objectName + ".timestamp(" + tableIdxName + ")= timestamp;\n"); matlabFunctionsCode.append("\tif " + isSingleInst + "\n"); matlabFunctionsCode.append("\t\theaderSize = 8;\n"); @@ -177,6 +179,8 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) // Generate functions code, actual fields of the object QString funcfields; + matlabFunctionsCode.append("\tstartPos = ftell(fid) - headerSize;\n"); + for (int n = 0; n < info->fields.length(); ++n) { // Determine type type = fieldTypeStrMatlab[info->fields[n]->type]; @@ -188,8 +192,20 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) } matlabFunctionsCode.append(funcfields); + matlabFunctionsCode.append("\tobjLen = ftell(fid) - startPos;\n"); + matlabFunctionsCode.append("\t% read CRC\n"); - matlabFunctionsCode.append("\tfread(fid, 1, '*uint8');\n"); + matlabFunctionsCode.append("\tcrc_read = fread(fid, 1, '*uint8');\n"); + + matlabFunctionsCode.append("\tif checkCRC\n"); + matlabFunctionsCode.append("\t\tfseek(fid, startPos, 'bof');\n"); + matlabFunctionsCode.append("\t\tcrc_calc = compute_crc(uint8(fread(fid,objLen,'uint8')));\n"); + matlabFunctionsCode.append("\t\tfread(fid,1,'uint8');\n"); + matlabFunctionsCode.append("\t\tif (crc_calc ~= crc_read)\n"); + matlabFunctionsCode.append("\t\t\tdisp('CRC Error')\n"); + matlabFunctionsCode.append("\t\t\t" + tableIdxName + " = " + tableIdxName + " - 1;\n"); + matlabFunctionsCode.append("\t\tend\n"); + matlabFunctionsCode.append("\tend\n"); matlabFunctionsCode.append("\n\n"); diff --git a/ground/uavobjgenerator/uavobjectparser.cpp b/ground/uavobjgenerator/uavobjectparser.cpp index a0409f06f..a11a53e82 100644 --- a/ground/uavobjgenerator/uavobjectparser.cpp +++ b/ground/uavobjgenerator/uavobjectparser.cpp @@ -34,7 +34,7 @@ UAVObjectParser::UAVObjectParser() fieldTypeStrXML << "int8" << "int16" << "int32" << "uint8" << "uint16" << "uint32" <<"float" << "enum"; - updateModeStrXML << "periodic" << "onchange" << "manual" << "never"; + updateModeStrXML << "periodic" << "onchange" << "throttled" << "manual"; accessModeStr << "ACCESS_READWRITE" << "ACCESS_READONLY"; @@ -209,6 +209,9 @@ QString UAVObjectParser::parseXML(QString& xml, QString& filename) // Sort all fields according to size qStableSort(info->fields.begin(), info->fields.end(), fieldTypeLessThan); + // Sort all fields according to size + qStableSort(info->fields.begin(), info->fields.end(), fieldTypeLessThan); + // Make sure that required elements were found if ( !accessFound ) return QString("Object::access element is missing"); diff --git a/ground/uavobjgenerator/uavobjectparser.h b/ground/uavobjgenerator/uavobjectparser.h index f1e93d8f5..f41c3ce30 100644 --- a/ground/uavobjgenerator/uavobjectparser.h +++ b/ground/uavobjgenerator/uavobjectparser.h @@ -66,8 +66,8 @@ typedef struct { typedef enum { UPDATEMODE_PERIODIC = 0, /** Automatically update object at periodic intervals */ UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ - UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ - UPDATEMODE_NEVER /** Object is never updated */ + UPDATEMODE_THROTTLED, /** Object is updated on change, but not more often than the interval time */ + UPDATEMODE_MANUAL /** Manually update object, by calling the updated() function */ } UpdateMode; diff --git a/hardware/Production/Overo Carrier/Assembly.OutJob b/hardware/Production/Overo Carrier/Assembly.OutJob new file mode 100644 index 000000000..5e5e85057 --- /dev/null +++ b/hardware/Production/Overo Carrier/Assembly.OutJob @@ -0,0 +1,170 @@ +[OutputJobFile] +Version=1.0 + +[OutputGroup1] +Name=Assembly.OutJob +Description= +TargetOutputMedium=PDF +VariantName=[No Variations] +VariantScope=1 +CurrentConfigurationName= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputMedium1=Print Job +OutputMedium1_Type=Printer +OutputMedium1_Printer= +OutputMedium1_PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputMedium2=PDF +OutputMedium2_Type=Publish +OutputMedium3=Folder Structure +OutputMedium3_Type=GeneratedFiles +OutputMedium4=Video +OutputMedium4_Type=Multimedia +OutputType1=Assembly +OutputName1=Assembly Drawings +OutputCategory1=Assembly +OutputDocumentPath1=Overo Carrier.PcbDoc +OutputVariantName1= +OutputEnabled1=1 +OutputEnabled1_OutputMedium1=0 +OutputEnabled1_OutputMedium2=1 +OutputEnabled1_OutputMedium3=0 +OutputEnabled1_OutputMedium4=0 +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +Configuration1_Name1=OutputConfigurationParameter1 +Configuration1_Item1=PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView +Configuration1_Name2=OutputConfigurationParameter2 +Configuration1_Item2=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|Index=0|Mirror=False|Name=Top Assembly Drawing|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=True +Configuration1_Name3=OutputConfigurationParameter3 +Configuration1_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name4=OutputConfigurationParameter4 +Configuration1_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Hidden|FFill=Hidden|FPad=Hidden|FRegion=Hidden|FText=Hidden|FTrack=Hidden|FVia=Hidden|Layer=TopLayer|Polygon=Hidden|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name5=OutputConfigurationParameter5 +Configuration1_Item5=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopOverlay|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name6=OutputConfigurationParameter6 +Configuration1_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Hidden|Layer=MultiLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name7=OutputConfigurationParameter7 +Configuration1_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name8=OutputConfigurationParameter8 +Configuration1_Item8=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical2|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name9=OutputConfigurationParameter9 +Configuration1_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name10=OutputConfigurationParameter10 +Configuration1_Item10=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=False|Index=1|Mirror=True|Name=Bottom Assembly Drawing|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=True +Configuration1_Name11=OutputConfigurationParameter11 +Configuration1_Item11=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical14|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name12=OutputConfigurationParameter12 +Configuration1_Item12=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Hidden|FFill=Hidden|FPad=Hidden|FRegion=Hidden|FText=Hidden|FTrack=Hidden|FVia=Hidden|Layer=BottomLayer|Polygon=Hidden|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name13=OutputConfigurationParameter13 +Configuration1_Item13=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomOverlay|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name14=OutputConfigurationParameter14 +Configuration1_Item14=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Hidden|Layer=MultiLayer|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name15=OutputConfigurationParameter15 +Configuration1_Item15=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name16=OutputConfigurationParameter16 +Configuration1_Item16=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical2|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name17=OutputConfigurationParameter17 +Configuration1_Item17=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +OutputType2=PCB 3D Print +OutputName2=PCB 3D Print Top +OutputCategory2=Documentation +OutputDocumentPath2=Overo Carrier.PcbDoc +OutputVariantName2= +OutputEnabled2=1 +OutputEnabled2_OutputMedium1=0 +OutputEnabled2_OutputMedium2=2 +OutputEnabled2_OutputMedium3=0 +OutputEnabled2_OutputMedium4=0 +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=4.95|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +Configuration2_Name1=OutputConfigurationParameter1 +Configuration2_Item1=Record=Pcb3DPrintView|ResX=300|ResY=300|ViewX=22834646|ViewY=14173228|LookAtX=27821340|LookAtY=26053936|LookAtZ=-1000|QuatX=0|QuatY=0|QuatZ=0|QuatW=1|Zoom=4.86541372263884E-5|UnitsPercent=True|UnitsDPI=True|LockResAspect=True|ViewConfigType=.config_3d|CustomCamera=False|ViewFromTop=True|ViewConfig= +OutputType3=PCB 3D Print +OutputName3=PCB 3D Print Bottom +OutputCategory3=Documentation +OutputDocumentPath3=Overo Carrier.PcbDoc +OutputVariantName3= +OutputEnabled3=1 +OutputEnabled3_OutputMedium1=0 +OutputEnabled3_OutputMedium2=3 +OutputEnabled3_OutputMedium3=0 +OutputEnabled3_OutputMedium4=0 +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=4.95|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +Configuration3_Name1=OutputConfigurationParameter1 +Configuration3_Item1=Record=Pcb3DPrintView|ResX=300|ResY=300|ViewX=22834646|ViewY=14173228|LookAtX=27821340|LookAtY=26053936|LookAtZ=-1000|QuatX=0|QuatY=0|QuatZ=0|QuatW=1|Zoom=4.86541372263884E-5|UnitsPercent=True|UnitsDPI=True|LockResAspect=True|ViewConfigType=.config_3d|CustomCamera=False|ViewFromTop=False|ViewConfig= + +[PublishSettings] +OutputFilePath2=C:\Users\David\Documents\OP-WIP\trunk\hardware\production\Overo Carrier\Project Outputs for Overo Carrier\..\assembly\Overo Carrier Assembly.pdf +ReleaseManaged2=1 +OutputBasePath2=Project Outputs for Overo Carrier +OutputPathMedia2=..\assembly +OutputPathOutputer2=[Output Type] +OutputFileName2=Overo Carrier Assembly.pdf +OpenOutput2=1 +PromptOverwrite2=1 +PublishMethod2=0 +ZoomLevel2=50 +FitSCHPrintSizeToDoc2=1 +FitPCBPrintSizeToDoc2=1 +GenerateNetsInfo2=1 +MarkPins2=1 +MarkNetLabels2=1 +MarkPortsId2=1 +GenerateTOC=1 +OutputFilePath3=C:\Users\David\Documents\OP-WIP\trunk\hardware\production\Overo Carrier\Project Outputs for Overo Carrier\ +ReleaseManaged3=1 +OutputBasePath3=Project Outputs for Overo Carrier +OutputPathMedia3= +OutputPathOutputer3=[Output Type] +OutputFileName3= +OpenOutput3=1 +OutputFilePath4=C:\Users\David\Documents\OP-WIP\trunk\hardware\production\Overo Carrier\Project Outputs for Overo Carrier\ +ReleaseManaged4=1 +OutputBasePath4=Project Outputs for Overo Carrier +OutputPathMedia4= +OutputPathOutputer4=[Output Type] +OutputFileName4= +OpenOutput4=1 +PromptOverwrite4=1 +PublishMethod4=5 +ZoomLevel4=50 +FitSCHPrintSizeToDoc4=1 +FitPCBPrintSizeToDoc4=1 +GenerateNetsInfo4=1 +MarkPins4=1 +MarkNetLabels4=1 +MarkPortsId4=1 +MediaFormat4=Windows Media file (*.wmv,*.wma,*.asf) +FixedDimensions4=1 +Width4=352 +Height4=288 +MultiFile4=0 +FramesPerSecond4=25 +FramesPerSecondDenom4=1 +AviPixelFormat4=7 +AviCompression4=MP42 MS-MPEG4 V2 +AviQuality4=100 +FFmpegVideoCodecId4=13 +FFmpegPixelFormat4=0 +FFmpegQuality4=80 +WmvVideoCodecName4=Windows Media Video V7 +WmvQuality4=80 + +[GeneratedFilesSettings] +RelativeOutputPath2=C:\Users\David\Documents\OP-WIP\trunk\hardware\production\Overo Carrier\Project Outputs for Overo Carrier\..\assembly\Overo Carrier Assembly.pdf +OpenOutputs2=1 +RelativeOutputPath3=C:\Users\David\Documents\OP-WIP\trunk\hardware\production\Overo Carrier\Project Outputs for Overo Carrier\ +OpenOutputs3=1 +AddToProject3=1 +TimestampFolder3=0 +UseOutputName3=0 +OpenODBOutput3=0 +OpenGerberOutput3=0 +OpenNCDrillOutput3=0 +OpenIPCOutput3=0 +EnableReload3=0 +RelativeOutputPath4=C:\Users\David\Documents\OP-WIP\trunk\hardware\production\Overo Carrier\Project Outputs for Overo Carrier\ +OpenOutputs4=1 + diff --git a/hardware/Production/Overo Carrier/Assembly/Overo Carrier Assembly.PDF b/hardware/Production/Overo Carrier/Assembly/Overo Carrier Assembly.PDF new file mode 100644 index 000000000..bea726b99 Binary files /dev/null and b/hardware/Production/Overo Carrier/Assembly/Overo Carrier Assembly.PDF differ diff --git a/hardware/Production/Overo Carrier/BOM/Overo Carrier BOM.xls b/hardware/Production/Overo Carrier/BOM/Overo Carrier BOM.xls new file mode 100644 index 000000000..c27e77d89 Binary files /dev/null and b/hardware/Production/Overo Carrier/BOM/Overo Carrier BOM.xls differ diff --git a/hardware/Production/Overo Carrier/Gerbers/Gerbers for Overo Carrier.zip b/hardware/Production/Overo Carrier/Gerbers/Gerbers for Overo Carrier.zip new file mode 100644 index 000000000..582c50759 Binary files /dev/null and b/hardware/Production/Overo Carrier/Gerbers/Gerbers for Overo Carrier.zip differ diff --git a/hardware/Production/Overo Carrier/Overo Carrier Schematic.pdf b/hardware/Production/Overo Carrier/Overo Carrier Schematic.pdf new file mode 100644 index 000000000..af107cbc4 Binary files /dev/null and b/hardware/Production/Overo Carrier/Overo Carrier Schematic.pdf differ diff --git a/hardware/Production/Overo Carrier/Overo Carrier.PcbDoc b/hardware/Production/Overo Carrier/Overo Carrier.PcbDoc new file mode 100644 index 000000000..f64b934f7 Binary files /dev/null and b/hardware/Production/Overo Carrier/Overo Carrier.PcbDoc differ diff --git a/hardware/Production/Overo Carrier/Overo Carrier.PrjPCB b/hardware/Production/Overo Carrier/Overo Carrier.PrjPCB new file mode 100644 index 000000000..1a20dd0b5 --- /dev/null +++ b/hardware/Production/Overo Carrier/Overo Carrier.PrjPCB @@ -0,0 +1,1088 @@ +[Design] +Version=1.0 +HierarchyMode=0 +ChannelRoomNamingStyle=0 +OutputPath=Project Outputs for Overo Carrier +LogFolderPath= +ReleasesFolder= +ReleaseVaultGUID= +ReleaseVaultName= +ChannelDesignatorFormatString=$Component_$RoomName +ChannelRoomLevelSeperator=_ +OpenOutputs=1 +ArchiveProject=0 +TimestampOutput=0 +SeparateFolders=0 +TemplateLocationPath= +PinSwapBy_Netlabel=1 +PinSwapBy_Pin=1 +AllowPortNetNames=0 +AllowSheetEntryNetNames=1 +AppendSheetNumberToLocalNets=0 +NetlistSinglePinNets=0 +DefaultConfiguration= +UserID=0xFFFFFFFF +DefaultPcbProtel=1 +DefaultPcbPcad=0 +ReorderDocumentsOnCompile=1 +NameNetsHierarchically=0 +PowerPortNamesTakePriority=0 +PushECOToAnnotationFile=1 +DItemRevisionGUID= +ReportSuppressedErrorsInMessages=0 + +[Document1] +DocumentPath=Overo Carrier.SchDoc +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=0 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=0 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document2] +DocumentPath=Overo Carrier.PcbDoc +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document3] +DocumentPath=..\Altium\OpenPilot.PcbLib +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document4] +DocumentPath=..\Altium\OpenPilot.SchLib +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document5] +DocumentPath=..\Altium\Gumstix.SchLib +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document6] +DocumentPath=..\Altium\Gumstix.PcbLib +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document7] +DocumentPath=Assembly.OutJob +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[PCBConfiguration1] +ReleaseItemId= +CurrentRevision= +Name=Default Configuration +Variant=[No Variations] +GenerateBOM=0 + +[Generic_SmartPDF] +AutoOpenFile=0 +AutoOpenOutJob=0 + +[Generic_SmartPDFSettings] +ProjectMode=0 +ZoomPrecision=50 +AddNetsInformation=-1 +AddNetPins=-1 +AddNetNetLabels=-1 +AddNetPorts=-1 +ExportBOM=0 +TemplateFilename= +TemplateStoreRelative=-1 +PCB_PrintColor=0 +SCH_PrintColor=0 +SCH_ShowNoErc=0 +SCH_ShowParameter=0 +SCH_ShowProbes=0 +SCH_ShowBlankets=0 +OutputFileName=OpenPilot GPS v5.SchDoc=C:\Users\David\Documents\SVN\OP-WIP\trunk\hardware\production\OpenPilot GPS v5\OpenPilot GPS v5 Schmatic.pdf +SCH_ExpandLogicalToPhysical=0 +SCH_VariantName=[No Variations] +SCH_ExpandComponentDesignators=-1 +SCH_ExpandNetlabels=0 +SCH_ExpandPorts=0 +SCH_ExpandSheetNumber=0 +SCH_ExpandDocumentNumber=0 +SCH_HasExpandLogicalToPhysicalSheets=-1 +SaveSettingsToOutJob=0 +SCH_NoERCSymbolsToShow="Thin Cross","Thick Cross","Small Cross",Checkbox,Triangle +SCH_ShowNote=-1 +SCH_ShowNoteCollapsed=-1 + +[OutputGroup1] +Name=Netlist Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=CadnetixNetlist +OutputName1=Cadnetix Netlist +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +OutputType2=CalayNetlist +OutputName2=Calay Netlist +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +OutputType3=EDIF +OutputName3=EDIF for PCB +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +OutputType4=EESofNetlist +OutputName4=EESof Netlist +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 +OutputType5=IntergraphNetlist +OutputName5=Intergraph Netlist +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +OutputType6=MentorBoardStationNetlist +OutputName6=Mentor BoardStation Netlist +OutputDocumentPath6= +OutputVariantName6= +OutputDefault6=0 +OutputType7=MultiWire +OutputName7=MultiWire +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +OutputType8=OrCadPCB2Netlist +OutputName8=Orcad/PCB2 Netlist +OutputDocumentPath8= +OutputVariantName8= +OutputDefault8=0 +OutputType9=PADSNetlist +OutputName9=PADS ASCII Netlist +OutputDocumentPath9= +OutputVariantName9= +OutputDefault9=0 +OutputType10=Pcad +OutputName10=Pcad for PCB +OutputDocumentPath10= +OutputVariantName10= +OutputDefault10=0 +OutputType11=PCADNetlist +OutputName11=PCAD Netlist +OutputDocumentPath11= +OutputVariantName11= +OutputDefault11=0 +OutputType12=PCADnltNetlist +OutputName12=PCADnlt Netlist +OutputDocumentPath12= +OutputVariantName12= +OutputDefault12=0 +OutputType13=Protel2Netlist +OutputName13=Protel2 Netlist +OutputDocumentPath13= +OutputVariantName13= +OutputDefault13=0 +OutputType14=ProtelNetlist +OutputName14=Protel +OutputDocumentPath14= +OutputVariantName14= +OutputDefault14=0 +OutputType15=RacalNetlist +OutputName15=Racal Netlist +OutputDocumentPath15= +OutputVariantName15= +OutputDefault15=0 +OutputType16=RINFNetlist +OutputName16=RINF Netlist +OutputDocumentPath16= +OutputVariantName16= +OutputDefault16=0 +OutputType17=SciCardsNetlist +OutputName17=SciCards Netlist +OutputDocumentPath17= +OutputVariantName17= +OutputDefault17=0 +OutputType18=SIMetrixNetlist +OutputName18=SIMetrix +OutputDocumentPath18= +OutputVariantName18= +OutputDefault18=0 +OutputType19=SIMPLISNetlist +OutputName19=SIMPLIS +OutputDocumentPath19= +OutputVariantName19= +OutputDefault19=0 +OutputType20=TangoNetlist +OutputName20=Tango Netlist +OutputDocumentPath20= +OutputVariantName20= +OutputDefault20=0 +OutputType21=TelesisNetlist +OutputName21=Telesis Netlist +OutputDocumentPath21= +OutputVariantName21= +OutputDefault21=0 +OutputType22=Verilog +OutputName22=Verilog File +OutputDocumentPath22= +OutputVariantName22= +OutputDefault22=0 +OutputType23=VHDL +OutputName23=VHDL File +OutputDocumentPath23= +OutputVariantName23= +OutputDefault23=0 +OutputType24=WireListNetlist +OutputName24=WireList Netlist +OutputDocumentPath24= +OutputVariantName24= +OutputDefault24=0 +OutputType25=XSpiceNetlist +OutputName25=XSpice Netlist +OutputDocumentPath25= +OutputVariantName25= +OutputDefault25=0 + +[OutputGroup2] +Name=Simulator Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=AdvSimNetlist +OutputName1=Mixed Sim +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +OutputType2=SIMetrix_Sim +OutputName2=SIMetrix +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +OutputType3=SIMPLIS_Sim +OutputName3=SIMPLIS +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 + +[OutputGroup3] +Name=Documentation Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Composite +OutputName1=Composite Drawing +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType2=Logic Analyser Print +OutputName2=Logic Analyser Prints +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType3=OpenBus Print +OutputName3=OpenBus Prints +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType4=PCB 3D Print +OutputName4=PCB 3D Prints +OutputDocumentPath4= +OutputVariantName4=[No Variations] +OutputDefault4=0 +PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType5=PCB Print +OutputName5=PCB Prints +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType6=Schematic Print +OutputName6=Schematic Prints +OutputDocumentPath6=H:\Projects\OpenPilot.WIP\OP-WIP\trunk\hardware\production\GPS v4.0\OpenPilotGPS.SchDoc +OutputVariantName6= +OutputDefault6=0 +PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +Configuration6_Name1=OutputConfigurationParameter1 +Configuration6_Item1=Record=SchPrintView|ShowNoERC=True|ShowParamSet=True|ShowProbe=True|ShowBlanket=True|ExpandDesignator=True|ExpandNetLabel=False|ExpandPort=False|ExpandSheetNum=False|ExpandDocNum=False +OutputType7=SimView Print +OutputName7=SimView Prints +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType8=Wave Print +OutputName8=Wave Prints +OutputDocumentPath8= +OutputVariantName8= +OutputDefault8=0 +PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType9=WaveSim Print +OutputName9=WaveSim Prints +OutputDocumentPath9= +OutputVariantName9= +OutputDefault9=0 +PageOptions9=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType10=Assembler Source Print +OutputName10=Assembler Source Prints +OutputDocumentPath10= +OutputVariantName10= +OutputDefault10=0 +PageOptions10=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType11=C Source Print +OutputName11=C Source Prints +OutputDocumentPath11= +OutputVariantName11= +OutputDefault11=0 +PageOptions11=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType12=C/C++ Header Print +OutputName12=C/C++ Header Prints +OutputDocumentPath12= +OutputVariantName12= +OutputDefault12=0 +PageOptions12=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType13=C++ Source Print +OutputName13=C++ Source Prints +OutputDocumentPath13= +OutputVariantName13= +OutputDefault13=0 +PageOptions13=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType14=PCB 3D Video +OutputName14=PCB 3D Video +OutputDocumentPath14= +OutputVariantName14=[No Variations] +OutputDefault14=0 +PageOptions14=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType15=Report Print +OutputName15=Report Prints +OutputDocumentPath15= +OutputVariantName15= +OutputDefault15=0 +PageOptions15=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType16=Software Platform Print +OutputName16=Software Platform Prints +OutputDocumentPath16= +OutputVariantName16= +OutputDefault16=0 +PageOptions16=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType17=VHDL Print +OutputName17=VHDL Prints +OutputDocumentPath17= +OutputVariantName17= +OutputDefault17=0 +PageOptions17=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 + +[OutputGroup4] +Name=Assembly Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Assembly +OutputName1=Assembly Drawings +OutputDocumentPath1= +OutputVariantName1=[No Variations] +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType2=Pick Place +OutputName2=Generates pick and place files +OutputDocumentPath2= +OutputVariantName2=[No Variations] +OutputDefault2=0 +OutputType3=Test Points For Assembly +OutputName3=Test Point Report +OutputDocumentPath3= +OutputVariantName3=[No Variations] +OutputDefault3=0 + +[OutputGroup5] +Name=Fabrication Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Drill +OutputName1=Drill Drawing/Guides +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType2=Mask +OutputName2=Solder/Paste Mask Prints +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType3=Final +OutputName3=Final Artwork Prints +OutputDocumentPath3= +OutputVariantName3=[No Variations] +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType4=CompositeDrill +OutputName4=Composite Drill Drawing +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 +PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType5=NC Drill +OutputName5=NC Drill Files +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +Configuration5_Name1=OutputConfigurationParameter1 +Configuration5_Item1=BoardEdgeRoutToolDia=2000000|GenerateBoardEdgeRout=False|GenerateDrilledSlotsG85=False|GenerateEIADrillFile=False|GenerateSeparatePlatedNonPlatedFiles=False|NumberOfDecimals=5|NumberOfUnits=2|OptimizeChangeLocationCommands=True|OriginPosition=Relative|Record=DrillView|Units=Imperial|ZeroesMode=SuppressTrailingZeroes +OutputType6=ODB +OutputName6=ODB++ Files +OutputDocumentPath6= +OutputVariantName6=[No Variations] +OutputDefault6=0 +OutputType7=Plane +OutputName7=Power-Plane Prints +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType8=Test Points +OutputName8=Test Point Report +OutputDocumentPath8= +OutputVariantName8= +OutputDefault8=0 +OutputType9=Gerber +OutputName9=Gerber Files +OutputDocumentPath9= +OutputVariantName9=[No Variations] +OutputDefault9=0 +Configuration9_Name1=OutputConfigurationParameter1 +Configuration9_Item1=AddToAllPlots.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean|CentrePlots=False|DrillDrawingSymbol=GraphicsSymbol|DrillDrawingSymbolSize=500000|EmbeddedApertures=True|FilmBorderSize=10000000|FilmXSize=200000000|FilmYSize=160000000|FlashAllFills=False|FlashPadShapes=True|G54OnApertureChange=False|GenerateDRCRulesFile=True|GenerateReliefShapes=True|GerberUnit=Imperial|IncludeUnconnectedMidLayerPads=False|LeadingAndTrailingZeroesMode=SuppressLeadingZeroes|MaxApertureSize=2500000|MinusApertureTolerance=50|Mirror.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean|MirrorDrillDrawingPlots=False|MirrorDrillGuidePlots=False|NumberOfDecimals=5|OptimizeChangeLocationCommands=True|OriginPosition=Relative|Panelize=False|Plot.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean,16973830~1,16973832~1,16973834~1,16777217~1,16842751~1,16973835~1,16973833~1,16973831~1,16908290~1,16973837~1,16973848~1,16973849~1|PlotPositivePlaneLayers=False|PlotUsedDrillDrawingLayerPairs=True|PlotUsedDrillGuideLayerPairs=True|PlusApertureTolerance=50|Record=GerberView|SoftwareArcs=False|Sorted=False + +[OutputGroup6] +Name=Report Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Script +OutputName1=Script Output +OutputDocumentPath1= +OutputVariantName1=[No Variations] +OutputDefault1=0 +OutputType2=ReportHierarchy +OutputName2=Report Project Hierarchy +OutputDocumentPath2= +OutputVariantName2=[No Variations] +OutputDefault2=0 +OutputType3=SinglePinNetReporter +OutputName3=Report Single Pin Nets +OutputDocumentPath3= +OutputVariantName3=[No Variations] +OutputDefault3=0 +OutputType4=SimpleBOM +OutputName4=Simple BOM +OutputDocumentPath4= +OutputVariantName4=[No Variations] +OutputDefault4=0 +Configuration4_Name1=OutputConfigurationParameter1 +Configuration4_Item1=Record=SimpleBOMView|SimpleBOMMode=0 +OutputType5=ComponentCrossReference +OutputName5=Component Cross Reference Report +OutputDocumentPath5= +OutputVariantName5=[No Variations] +OutputDefault5=0 +OutputType6=BOM_PartType +OutputName6=Bill of Materials +OutputDocumentPath6= +OutputVariantName6=[No Variations] +OutputDefault6=0 +PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +Configuration6_Name1=Filter +Configuration6_Item1=545046300E5446696C74657257726170706572000D46696C7465722E416374697665090F46696C7465722E43726974657269610A04000000000000000000 +Configuration6_Name2=General +Configuration6_Item2=OpenExported=True|AddToProject=False|ForceFit=False|NotFitted=False|Database=False|IncludePCBData=False|ShowExportOptions=True|TemplateFilename=..\Altium\BOM OpenPilot.xlt|BatchMode=5|FormWidth=1200|FormHeight=641|SupplierProdQty=1|SupplierAutoQty=True|SupplierUseCachedPricing=True|SupplierCurrency= +Configuration6_Name3=GroupOrder +Configuration6_Item3=Supplier Part Number 1=True|Footprint=True +Configuration6_Name4=OutputConfigurationParameter1 +Configuration6_Item4=Record=BOMPrintView|ShowNoERC=True|ShowParamSet=True|ShowProbe=True|ShowBlanket=True|ExpandDesignator=True|ExpandNetLabel=False|ExpandPort=False|ExpandSheetNum=False|ExpandDocNum=False +Configuration6_Name5=SortOrder +Configuration6_Item5=Designator=Up|Comment=Up|Footprint=Up +Configuration6_Name6=VisibleOrder +Configuration6_Item6=Description=144|Comment=91|Footprint=89|Value=74|Designator=121|Quantity=45|Supplier Part Number 1=120|Supplier Order Qty 1=47|Supplier Stock 1=69|Supplier Unit Price 1=69|Supplier Subtotal 1=69|Supplier 1=61|Manufacturer 1=246|Manufacturer Part Number 1=246 + +[OutputGroup7] +Name=Other Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Text Print +OutputName1=Text Print +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType2=Text Print +OutputName2=Text Print +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType3=Text Print +OutputName3=Text Print +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType4=Text Print +OutputName4=Text Print +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 +PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType5=Text Print +OutputName5=Text Print +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType6=Text Print +OutputName6=Text Print +OutputDocumentPath6= +OutputVariantName6= +OutputDefault6=0 +PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType7=Text Print +OutputName7=Text Print +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType8=Text Print +OutputName8=Text Print +OutputDocumentPath8= +OutputVariantName8= +OutputDefault8=0 +PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType9=Text Print +OutputName9=Text Print +OutputDocumentPath9= +OutputVariantName9= +OutputDefault9=0 +PageOptions9=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType10=Text Print +OutputName10=Text Print +OutputDocumentPath10= +OutputVariantName10= +OutputDefault10=0 +PageOptions10=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType11=Text Print +OutputName11=Text Print +OutputDocumentPath11= +OutputVariantName11= +OutputDefault11=0 +PageOptions11=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType12=Text Print +OutputName12=Text Print +OutputDocumentPath12= +OutputVariantName12= +OutputDefault12=0 +PageOptions12=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType13=Text Print +OutputName13=Text Print +OutputDocumentPath13= +OutputVariantName13= +OutputDefault13=0 +PageOptions13=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType14=Text Print +OutputName14=Text Print +OutputDocumentPath14= +OutputVariantName14= +OutputDefault14=0 +PageOptions14=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType15=Text Print +OutputName15=Text Print +OutputDocumentPath15= +OutputVariantName15= +OutputDefault15=0 +PageOptions15=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType16=Text Print +OutputName16=Text Print +OutputDocumentPath16= +OutputVariantName16= +OutputDefault16=0 +PageOptions16=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType17=Text Print +OutputName17=Text Print +OutputDocumentPath17= +OutputVariantName17= +OutputDefault17=0 +PageOptions17=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType18=Text Print +OutputName18=Text Print +OutputDocumentPath18= +OutputVariantName18= +OutputDefault18=0 +PageOptions18=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType19=Text Print +OutputName19=Text Print +OutputDocumentPath19= +OutputVariantName19= +OutputDefault19=0 +PageOptions19=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType20=Text Print +OutputName20=Text Print +OutputDocumentPath20= +OutputVariantName20= +OutputDefault20=0 +PageOptions20=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType21=Text Print +OutputName21=Text Print +OutputDocumentPath21= +OutputVariantName21= +OutputDefault21=0 +PageOptions21=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType22=Text Print +OutputName22=Text Print +OutputDocumentPath22= +OutputVariantName22= +OutputDefault22=0 +PageOptions22=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType23=Text Print +OutputName23=Text Print +OutputDocumentPath23= +OutputVariantName23= +OutputDefault23=0 +PageOptions23=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType24=Text Print +OutputName24=Text Print +OutputDocumentPath24= +OutputVariantName24= +OutputDefault24=0 +PageOptions24=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType25=Text Print +OutputName25=Text Print +OutputDocumentPath25= +OutputVariantName25= +OutputDefault25=0 +PageOptions25=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType26=Text Print +OutputName26=Text Print +OutputDocumentPath26= +OutputVariantName26= +OutputDefault26=0 +PageOptions26=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType27=Text Print +OutputName27=Text Print +OutputDocumentPath27= +OutputVariantName27= +OutputDefault27=0 +PageOptions27=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType28=Text Print +OutputName28=Text Print +OutputDocumentPath28= +OutputVariantName28= +OutputDefault28=0 +PageOptions28=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType29=Text Print +OutputName29=Text Print +OutputDocumentPath29= +OutputVariantName29= +OutputDefault29=0 +PageOptions29=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 + +[OutputGroup8] +Name=Validation Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Electrical Rules Check +OutputName1=Electrical Rules Check +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType2=Design Rules Check +OutputName2=Design Rules Check +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 +OutputType3=Differences Report +OutputName3=Differences Report +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType4=Footprint Comparison Report +OutputName4=Footprint Comparison Report +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 + +[OutputGroup9] +Name=Export Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=ExportSTEP +OutputName1=Export STEP +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 + +[Modification Levels] +Type1=1 +Type2=1 +Type3=1 +Type4=1 +Type5=1 +Type6=1 +Type7=1 +Type8=1 +Type9=1 +Type10=1 +Type11=1 +Type12=1 +Type13=1 +Type14=1 +Type15=1 +Type16=1 +Type17=1 +Type18=1 +Type19=1 +Type20=1 +Type21=1 +Type22=1 +Type23=1 +Type24=1 +Type25=1 +Type26=1 +Type27=1 +Type28=1 +Type29=1 +Type30=1 +Type31=1 +Type32=1 +Type33=1 +Type34=1 +Type35=1 +Type36=1 +Type37=1 +Type38=1 +Type39=1 +Type40=1 +Type41=1 +Type42=1 +Type43=1 +Type44=1 +Type45=1 +Type46=1 +Type47=1 +Type48=1 +Type49=1 +Type50=1 +Type51=1 +Type52=1 +Type53=1 +Type54=1 +Type55=1 +Type56=1 +Type57=1 +Type58=1 +Type59=1 +Type60=1 +Type61=1 +Type62=1 +Type63=1 +Type64=1 +Type65=1 +Type66=1 +Type67=1 +Type68=1 +Type69=1 +Type70=1 +Type71=1 +Type72=1 +Type73=1 +Type74=1 + +[Difference Levels] +Type1=1 +Type2=1 +Type3=1 +Type4=1 +Type5=1 +Type6=1 +Type7=1 +Type8=1 +Type9=1 +Type10=1 +Type11=1 +Type12=1 +Type13=1 +Type14=1 +Type15=1 +Type16=1 +Type17=1 +Type18=1 +Type19=1 +Type20=1 +Type21=1 +Type22=1 +Type23=1 +Type24=1 +Type25=1 +Type26=1 +Type27=1 +Type28=1 +Type29=1 +Type30=1 +Type31=1 +Type32=1 +Type33=1 +Type34=1 +Type35=1 +Type36=1 +Type37=1 +Type38=1 +Type39=1 +Type40=1 + +[Electrical Rules Check] +Type1=1 +Type2=1 +Type3=2 +Type4=1 +Type5=2 +Type6=2 +Type7=1 +Type8=1 +Type9=1 +Type10=1 +Type11=2 +Type12=2 +Type13=2 +Type14=1 +Type15=1 +Type16=1 +Type17=1 +Type18=1 +Type19=1 +Type20=1 +Type21=1 +Type22=1 +Type23=1 +Type24=1 +Type25=2 +Type26=2 +Type27=2 +Type28=1 +Type29=1 +Type30=1 +Type31=1 +Type32=2 +Type33=2 +Type34=2 +Type35=1 +Type36=2 +Type37=1 +Type38=2 +Type39=2 +Type40=2 +Type41=0 +Type42=2 +Type43=1 +Type44=1 +Type45=2 +Type46=1 +Type47=2 +Type48=2 +Type49=1 +Type50=2 +Type51=1 +Type52=1 +Type53=1 +Type54=1 +Type55=1 +Type56=2 +Type57=1 +Type58=1 +Type59=0 +Type60=1 +Type61=2 +Type62=2 +Type63=1 +Type64=0 +Type65=2 +Type66=3 +Type67=2 +Type68=2 +Type69=1 +Type70=2 +Type71=2 +Type72=2 +Type73=2 +Type74=1 +Type75=2 +Type76=1 +Type77=1 +Type78=1 +Type79=1 +Type80=2 +Type81=3 +Type82=3 +Type83=3 +Type84=3 +Type85=3 +Type86=2 +Type87=2 +Type88=2 +Type89=1 +Type90=1 +Type91=3 +Type92=3 +Type93=2 +Type94=2 +Type95=2 +Type96=2 +Type97=2 +Type98=0 +Type99=1 +Type100=2 + +[ERC Connection Matrix] +L1=NNNNNNNNNNNWNNNWW +L2=NNWNNNNWWWNWNWNWN +L3=NWEENEEEENEWNEEWN +L4=NNENNNWEENNWNENWN +L5=NNNNNNNNNNNNNNNNN +L6=NNENNNNEENNWNENWN +L7=NNEWNNWEENNWNENWN +L8=NWEENEENEEENNEENN +L9=NWEENEEEENEWNEEWW +L10=NWNNNNNENNEWNNEWN +L11=NNENNNNEEENWNENWN +L12=WWWWNWWNWWWNWWWNN +L13=NNNNNNNNNNNWNNNWW +L14=NWEENEEEENEWNEEWW +L15=NNENNNNEEENWNENWW +L16=WWWWNWWNWWWNWWWNW +L17=WNNNNNNNWNNNWWWWN + +[Annotate] +SortOrder=3 +MatchParameter1=Comment +MatchStrictly1=1 +MatchParameter2=Library Reference +MatchStrictly2=1 +PhysicalNamingFormat=$Component_$RoomName +GlobalIndexSortOrder=3 + +[PrjClassGen] +CompClassManualEnabled=0 +CompClassManualRoomEnabled=0 +NetClassAutoBusEnabled=1 +NetClassAutoCompEnabled=0 +NetClassAutoNamedHarnessEnabled=0 +NetClassManualEnabled=1 + +[LibraryUpdateOptions] +SelectedOnly=0 +PartTypes=0 +FullReplace=1 +UpdateDesignatorLock=1 +UpdatePartIDLock=1 +PreserveParameterLocations=1 +DoGraphics=1 +DoParameters=1 +DoModels=1 +AddParameters=0 +RemoveParameters=0 +AddModels=1 +RemoveModels=1 +UpdateCurrentModels=1 + +[DatabaseUpdateOptions] +SelectedOnly=0 +PartTypes=0 + +[Comparison Options] +ComparisonOptions0=Kind=Net|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions1=Kind=Net Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions2=Kind=Component Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions3=Kind=Rule|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions4=Kind=Differential Pair|MinPercent=50|MinMatch=1|ShowMatch=0|Confirm=0|UseName=0|InclAllRules=0 +ComparisonOptions5=Kind=Structure Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 + +[SmartPDF] +PageOptions=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=Letter|PrintScaleMode=1 + diff --git a/hardware/Production/Overo Carrier/Overo Carrier.SchDoc b/hardware/Production/Overo Carrier/Overo Carrier.SchDoc new file mode 100644 index 000000000..1c6c984c9 Binary files /dev/null and b/hardware/Production/Overo Carrier/Overo Carrier.SchDoc differ diff --git a/make/boards/coptercontrol/board-info.mk b/make/boards/coptercontrol/board-info.mk index 1f8e52610..674ad4152 100644 --- a/make/boards/coptercontrol/board-info.mk +++ b/make/boards/coptercontrol/board-info.mk @@ -1,6 +1,6 @@ BOARD_TYPE := 0x04 -BOARD_REVISION := 0x01 -BOOTLOADER_VERSION := 0x02 +BOARD_REVISION := 0x02 +BOOTLOADER_VERSION := 0x03 HW_TYPE := 0x01 MCU := cortex-m3 @@ -9,6 +9,7 @@ BOARD := STM32103CB_CC_Rev1 MODEL := MD MODEL_SUFFIX := _CC +OPENOCD_JTAG_CONFIG := foss-jtag.revb.cfg OPENOCD_CONFIG := stm32f1x.cfg # Note: These must match the values in link_$(BOARD)_memory.ld diff --git a/make/boards/esc/board-info.mk b/make/boards/esc/board-info.mk new file mode 100755 index 000000000..00c5f6bc0 --- /dev/null +++ b/make/boards/esc/board-info.mk @@ -0,0 +1,20 @@ +BOARD_TYPE := 0x08 +BOARD_REVISION := 0x01 +BOOTLOADER_VERSION := 0x01 +HW_TYPE := 0x01 + +MCU := cortex-m3 +CHIP := STM32F103CBT +BOARD := STM32F103CB_ESC_Rev1 +MODEL := MD +MODEL_SUFFIX := + +OPENOCD_CONFIG := stm32f1x.cfg + +# Note: These must match the values in link_$(BOARD)_memory.ld +BL_BANK_BASE := 0x08000000 # Start of bootloader flash +BL_BANK_SIZE := 0x00003000 # Should include BD_INFO region +FW_BANK_BASE := 0x08003000 # Start of firmware flash +FW_BANK_SIZE := 0x0001D000 # Should include FW_DESC_SIZE + +FW_DESC_SIZE := 0x00000064 diff --git a/make/boards/ins/board-info.mk b/make/boards/ins/board-info.mk index a20bd606c..d36e054cc 100644 --- a/make/boards/ins/board-info.mk +++ b/make/boards/ins/board-info.mk @@ -3,18 +3,21 @@ BOARD_REVISION := 0x01 BOOTLOADER_VERSION := 0x00 HW_TYPE := 0x00 -MCU := cortex-m3 -CHIP := STM32F103RET -BOARD := STM3210E_INS +MCU := cortex-m4 +CHIP := STM32F205RGT +BOARD := STM32F2xx_INS MODEL := HD -MODEL_SUFFIX := _OP +MODEL_SUFFIX := -OPENOCD_CONFIG := stm32f1x.cfg +OPENOCD_CONFIG := stm32f4xx.cfg # Note: These must match the values in link_$(BOARD)_memory.ld BL_BANK_BASE := 0x08000000 # Start of bootloader flash -BL_BANK_SIZE := 0x00002000 # Should include BD_INFO region -FW_BANK_BASE := 0x08002000 # Start of firmware flash +BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region +FW_BANK_BASE := 0x08008000 # Start of firmware flash FW_BANK_SIZE := 0x0001E000 # Should include FW_DESC_SIZE FW_DESC_SIZE := 0x00000064 + +OSCILLATOR_FREQ := 8000000 +SYSCLK_FREQ := 168000000 diff --git a/make/boards/pipxtreme/board-info.mk b/make/boards/pipxtreme/board-info.mk index dbcb314df..045721092 100644 --- a/make/boards/pipxtreme/board-info.mk +++ b/make/boards/pipxtreme/board-info.mk @@ -1,13 +1,21 @@ BOARD_TYPE := 0x03 BOARD_REVISION := 0x01 -BOOTLOADER_VERSION := 0x01 +BOOTLOADER_VERSION := 0x02 HW_TYPE := 0x01 MCU := cortex-m3 CHIP := STM32F103CBT BOARD := STM32103CB_PIPXTREME MODEL := MD -MODEL_SUFFIX := +MODEL_SUFFIX := _PX + +OPENOCD_CONFIG := stm32f1x.cfg + +OPENOCD_JTAG_CONFIG := foss-jtag.revb.cfg +OPENOCD_CONFIG := stm32f1x.cfg + +OPENOCD_JTAG_CONFIG := foss-jtag.revb.cfg +OPENOCD_CONFIG := stm32f1x.cfg # Note: These must match the values in link_$(BOARD)_memory.ld BL_BANK_BASE := 0x08000000 # Start of bootloader flash diff --git a/make/boards/revolution/board-info.mk b/make/boards/revolution/board-info.mk new file mode 100644 index 000000000..6cdd659a8 --- /dev/null +++ b/make/boards/revolution/board-info.mk @@ -0,0 +1,27 @@ +BOARD_TYPE := 0x09 +BOARD_REVISION := 0x02 +BOOTLOADER_VERSION := 0x01 +HW_TYPE := 0x00 + +MCU := cortex-m4 +CHIP := STM32F405RGT +BOARD := STM32F4xx_OP +MODEL := HD +MODEL_SUFFIX := + +OPENOCD_JTAG_CONFIG := stlink-v2.cfg +OPENOCD_CONFIG := stm32f4xx.stlink.cfg + +# Note: These must match the values in link_$(BOARD)_memory.ld +BL_BANK_BASE := 0x08000000 # Start of bootloader flash +BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region + +# Leave the remaining 16KB and 64KB sectors for other uses + +FW_BANK_BASE := 0x08020000 # Start of firmware flash +FW_BANK_SIZE := 0x00040000 # Should include FW_DESC_SIZE + +FW_DESC_SIZE := 0x00000064 + +OSCILLATOR_FREQ := 8000000 +SYSCLK_FREQ := 168000000 diff --git a/make/boards/simposix/board-info.mk b/make/boards/simposix/board-info.mk new file mode 100644 index 000000000..4a637a53d --- /dev/null +++ b/make/boards/simposix/board-info.mk @@ -0,0 +1,24 @@ +BOARD_TYPE := 0x10 +BOARD_REVISION := 0x01 +BOOTLOADER_VERSION := 0x01 +HW_TYPE := 0x00 + +MCU := +CHIP := +BOARD := SIM_POSIX +MODEL := +MODEL_SUFFIX := + +OPENOCD_JTAG_CONFIG := +OPENOCD_CONFIG := + +# Note: These must match the values in link_$(BOARD)_memory.ld +#BL_BANK_BASE := 0x08000000 # Start of bootloader flash +#BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region +#FW_BANK_BASE := 0x08008000 # Start of firmware flash +#FW_BANK_SIZE := 0x00038000 # Should include FW_DESC_SIZE + +#FW_DESC_SIZE := 0x00000064 + +OSCILLATOR_FREQ := 8000000 +SYSCLK_FREQ := 168000000 diff --git a/make/firmware-defs.mk b/make/firmware-defs.mk index 2eb0a13d8..32f2f60bc 100644 --- a/make/firmware-defs.mk +++ b/make/firmware-defs.mk @@ -49,8 +49,6 @@ MSG_OPFIRMWARE := ${quote} OPFW ${quote} MSG_FWINFO := ${quote} FWINFO ${quote} MSG_JTAG_PROGRAM := ${quote} JTAG-PGM ${quote} MSG_JTAG_WIPE := ${quote} JTAG-WIPE ${quote} -MSG_JTAG_RESET := ${quote} JTAG-RST ${quote} -MSG_JTAG_SAFEBOOT := ${quote} JTAG-SAFE ${quote} toprel = $(subst $(realpath $(TOP))/,,$(abspath $(1))) @@ -137,7 +135,7 @@ endef define ASSEMBLE_TEMPLATE $(OUTDIR)/$(notdir $(basename $(1))).o : $(1) @echo $(MSG_ASSEMBLING) $$(call toprel, $$<) - $(V1) $(CC) -c -mthumb $$(ASFLAGS) $$< -o $$@ + $(V1) $(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@ endef # Assemble: create object files from assembler source files. ARM-only @@ -151,7 +149,7 @@ endef define COMPILE_C_TEMPLATE $(OUTDIR)/$(notdir $(basename $(1))).o : $(1) @echo $(MSG_COMPILING) $$(call toprel, $$<) - $(V1) $(CC) -c -mthumb $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ + $(V1) $(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ endef # Compile: create object files from C source files. ARM-only @@ -165,7 +163,7 @@ endef define COMPILE_CPP_TEMPLATE $(OUTDIR)/$(notdir $(basename $(1))).o : $(1) @echo $(MSG_COMPILINGCPP) $$(call toprel, $$<) - $(V1) $(CC) -c -mthumb $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ + $(V1) $(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ endef # Compile: create object files from C++ source files. ARM-only @@ -183,14 +181,14 @@ define LINK_TEMPLATE .PRECIOUS : $(2) $(1): $(2) @echo $(MSG_LINKING) $$(call toprel, $$@) - $(V1) $(CC) -mthumb $$(CFLAGS) $(2) --output $$@ $$(LDFLAGS) + $(V1) $(CC) $(THUMB) $$(CFLAGS) $(2) --output $$@ $$(LDFLAGS) endef # Compile: create assembler files from C source files. ARM/Thumb define PARTIAL_COMPILE_TEMPLATE $($(1):.c=.s) : %.s : %.c @echo $(MSG_ASMFROMC) $$(call toprel, $$<) - $(V1) $(CC) -mthumb -S $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ + $(V1) $(CC) $(THUMB) -S $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ endef # Compile: create assembler files from C source files. ARM only @@ -245,34 +243,5 @@ wipe: -c "flash erase_address pad $(2) $(3)" \ -c "reset run" \ -c "shutdown" - -reset: - @echo $(MSG_JTAG_RESET) resetting device - $(V1) $(OOCD_EXE) \ - $$(OOCD_JTAG_SETUP) \ - $$(OOCD_BOARD_RESET) \ - -c "reset run" \ - -c "shutdown" - -# Enable PWR and BKP clocks (set RCC_APB1ENR[PWREN|BKPEN]) -OOCD_WRITE_BKPDR3 = -c "mww 0x4002101C 0x18000000" -# Enable writes to BKP registers (set PWR_CR[DBP] via bit op alias address) -# -# Direct register access would be: -# mww 0x40007000 0x00000100 -# -# Direct _bit_ access is: -# Bit 8 in 0x40007000 = 0x42000000 + 0x7000 * 32 + 8 * 4 = 420E0020 -OOCD_WRITE_BKPDR3 += -c "mww 0x420E0020 0x00000001" -# Set BR3 to max value to force a safe boot -OOCD_WRITE_BKPDR3 += -c "mwh 0x40006C0C 0xFFFF" -safeboot: - @echo $(MSG_JTAG_SAFEBOOT) forcing boot into safe mode - $(V1) $(OOCD_EXE) \ - $$(OOCD_JTAG_SETUP) \ - $$(OOCD_BOARD_RESET) \ - $$(OOCD_WRITE_BKPDR3) \ - -c "reset run" \ - -c "shutdown" endef diff --git a/matlab/revo/allan_gyro.m b/matlab/revo/allan_gyro.m new file mode 100644 index 000000000..e0752cf1f --- /dev/null +++ b/matlab/revo/allan_gyro.m @@ -0,0 +1,14 @@ +source = gyro; +clear data +data.freq = source(:,3)'; +data.time = unwrap_time(source(:,end))'/1000; +data.rate = 1/mean(diff(data.time)) +tau = 1/data.rate * round(logspace(0,7,200)) +[retval, s, errorb, tau] = allan(data,tau,'gyro') + +% [~,~,gyro_residual] = regress(gyro(:,1)-mean(gyro(:,1)),[gyro(:,4)-mean(gyro(:,4)), (1:size(gyro,1))']); +% data.freq = gyro_residual; +% data.time = unwrap_time(source(:,end))'/1000; +% data.rate = 1/mean(diff(data.time)) +% tau = 1/data.rate * round(logspace(0,7,200)) +% [retval, s, errorb, tau] = allan(data,tau,'gyro') diff --git a/matlab/revo/altitude_plant.mdl b/matlab/revo/altitude_plant.mdl new file mode 100644 index 000000000..669e2dd26 --- /dev/null +++ b/matlab/revo/altitude_plant.mdl @@ -0,0 +1,1304 @@ +Model { + Name "altitude_plant" + Version 7.8 + MdlSubVersion 0 + GraphicalInterface { + NumRootInports 1 + Inport { + BusObject "" + Name "Altitude Setpoint" + } + NumRootOutports 3 + Outport { + BusObject "" + BusOutputAsStruct "off" + Name "Altitude" + } + Outport { + BusObject "" + BusOutputAsStruct "off" + Name "Measured Altitude" + } + Outport { + BusObject "" + BusOutputAsStruct "off" + Name "Measured Accel" + } + ParameterArgumentNames "" + ComputedModelVersion "1.11" + NumModelReferences 0 + NumTestPointedSignals 0 + } + SavedCharacterEncoding "ISO-8859-1" + SaveDefaultBlockParams on + ScopeRefreshTime 0.035000 + OverrideScopeRefreshTime on + DisableAllScopes off + DataTypeOverride "UseLocalSettings" + DataTypeOverrideAppliesTo "AllNumericTypes" + MinMaxOverflowLogging "UseLocalSettings" + MinMaxOverflowArchiveMode "Overwrite" + FPTRunName "Run 1" + MaxMDLFileLineLength 120 + Created "Sun Jan 01 10:58:12 2012" + Creator "jcotton81" + UpdateHistory "UpdateHistoryNever" + ModifiedByFormat "%" + LastModifiedBy "jcotton81" + ModifiedDateFormat "%" + LastModifiedDate "Mon Jan 02 14:46:15 2012" + RTWModifiedTimeStamp 247320281 + ModelVersionFormat "1.%" + ConfigurationManager "None" + SampleTimeColors off + SampleTimeAnnotations off + LibraryLinkDisplay "disabled" + WideLines off + ShowLineDimensions off + ShowPortDataTypes off + ShowDesignRanges off + ShowLoopsOnError on + IgnoreBidirectionalLines off + ShowStorageClass off + ShowTestPointIcons on + ShowSignalResolutionIcons on + ShowViewerIcons on + SortedOrder off + ExecutionContextIcon off + ShowLinearizationAnnotations on + BlockNameDataTip off + BlockParametersDataTip off + BlockDescriptionStringDataTip off + ToolBar on + StatusBar on + BrowserShowLibraryLinks off + BrowserLookUnderMasks off + SimulationMode "normal" + LinearizationMsg "none" + Profile off + ParamWorkspaceSource "MATLABWorkspace" + AccelSystemTargetFile "accel.tlc" + AccelTemplateMakefile "accel_default_tmf" + AccelMakeCommand "make_rtw" + TryForcingSFcnDF off + Object { + $PropName "DataLoggingOverride" + $ObjectID 1 + $ClassName "Simulink.SimulationData.ModelLoggingInfo" + model_ "altitude_plant" + overrideMode_ [0.0] + Array { + Type "Cell" + Dimension 1 + Cell "altitude_plant" + PropName "logAsSpecifiedByModels_" + } + Array { + Type "Cell" + Dimension 1 + Cell [] + PropName "logAsSpecifiedByModelsSSIDs_" + } + } + RecordCoverage off + CovPath "/" + CovSaveName "covdata" + CovMetricSettings "dw" + CovNameIncrementing off + CovHtmlReporting on + CovForceBlockReductionOff on + covSaveCumulativeToWorkspaceVar on + CovSaveSingleToWorkspaceVar on + CovCumulativeVarName "covCumulativeData" + CovCumulativeReport off + CovReportOnPause on + CovModelRefEnable "Off" + CovExternalEMLEnable off + ExtModeBatchMode off + ExtModeEnableFloating on + ExtModeTrigType "manual" + ExtModeTrigMode "normal" + ExtModeTrigPort "1" + ExtModeTrigElement "any" + ExtModeTrigDuration 1000 + ExtModeTrigDurationFloating "auto" + ExtModeTrigHoldOff 0 + ExtModeTrigDelay 0 + ExtModeTrigDirection "rising" + ExtModeTrigLevel 0 + ExtModeArchiveMode "off" + ExtModeAutoIncOneShot off + ExtModeIncDirWhenArm off + ExtModeAddSuffixToVar off + ExtModeWriteAllDataToWs off + ExtModeArmWhenConnect on + ExtModeSkipDownloadWhenConnect off + ExtModeLogAll on + ExtModeAutoUpdateStatusClock on + BufferReuse on + ShowModelReferenceBlockVersion off + ShowModelReferenceBlockIO off + Array { + Type "Handle" + Dimension 1 + Simulink.ConfigSet { + $ObjectID 2 + Version "1.11.1" + Array { + Type "Handle" + Dimension 8 + Simulink.SolverCC { + $ObjectID 3 + Version "1.11.1" + StartTime "0.0" + StopTime "200.0" + AbsTol "auto" + FixedStep "auto" + InitialStep "auto" + MaxNumMinSteps "-1" + MaxOrder 5 + ZcThreshold "auto" + ConsecutiveZCsStepRelTol "10*128*eps" + MaxConsecutiveZCs "1000" + ExtrapolationOrder 4 + NumberNewtonIterations 1 + MaxStep "auto" + MinStep "auto" + MaxConsecutiveMinStep "1" + RelTol "1e-3" + SolverMode "Auto" + ConcurrentTasks off + Solver "ode45" + SolverName "ode45" + SolverJacobianMethodControl "auto" + ShapePreserveControl "DisableAll" + ZeroCrossControl "UseLocalSettings" + ZeroCrossAlgorithm "Nonadaptive" + AlgebraicLoopSolver "TrustRegion" + SolverResetMethod "Fast" + PositivePriorityOrder off + AutoInsertRateTranBlk off + SampleTimeConstraint "Unconstrained" + InsertRTBMode "Whenever possible" + } + Simulink.DataIOCC { + $ObjectID 4 + Version "1.11.1" + Decimation "1" + ExternalInput "[t, u]" + FinalStateName "xFinal" + InitialState "xInitial" + LimitDataPoints on + MaxDataPoints "1000" + LoadExternalInput on + LoadInitialState off + SaveFinalState off + SaveCompleteFinalSimState off + SaveFormat "Array" + SignalLoggingSaveFormat "ModelDataLogs" + SaveOutput on + SaveState off + SignalLogging on + DSMLogging on + InspectSignalLogs off + SaveTime on + ReturnWorkspaceOutputs off + StateSaveName "xout" + TimeSaveName "tout" + OutputSaveName "yout" + SignalLoggingName "logsout" + DSMLoggingName "dsmout" + OutputOption "RefineOutputTimes" + OutputTimes "[]" + ReturnWorkspaceOutputsName "out" + Refine "1" + } + Simulink.OptimizationCC { + $ObjectID 5 + Version "1.11.1" + Array { + Type "Cell" + Dimension 8 + Cell "BooleansAsBitfields" + Cell "PassReuseOutputArgsAs" + Cell "PassReuseOutputArgsThreshold" + Cell "ZeroExternalMemoryAtStartup" + Cell "ZeroInternalMemoryAtStartup" + Cell "OptimizeModelRefInitCode" + Cell "NoFixptDivByZeroProtection" + Cell "UseSpecifiedMinMax" + PropName "DisabledProps" + } + BlockReduction on + BooleanDataType on + ConditionallyExecuteInputs on + InlineParams off + UseIntDivNetSlope off + UseFloatMulNetSlope off + UseSpecifiedMinMax off + InlineInvariantSignals off + OptimizeBlockIOStorage on + BufferReuse on + EnhancedBackFolding off + StrengthReduction off + ExpressionFolding on + BooleansAsBitfields off + BitfieldContainerType "uint_T" + EnableMemcpy on + MemcpyThreshold 64 + PassReuseOutputArgsAs "Structure reference" + ExpressionDepthLimit 2147483647 + FoldNonRolledExpr on + LocalBlockOutputs on + RollThreshold 5 + SystemCodeInlineAuto off + StateBitsets off + DataBitsets off + UseTempVars off + ZeroExternalMemoryAtStartup on + ZeroInternalMemoryAtStartup on + InitFltsAndDblsToZero off + NoFixptDivByZeroProtection off + EfficientFloat2IntCast off + EfficientMapNaN2IntZero on + OptimizeModelRefInitCode off + LifeSpan "inf" + MaxStackSize "Inherit from target" + BufferReusableBoundary on + SimCompilerOptimization "Off" + AccelVerboseBuild off + AccelParallelForEachSubsystem on + } + Simulink.DebuggingCC { + $ObjectID 6 + Version "1.11.1" + RTPrefix "error" + ConsistencyChecking "none" + ArrayBoundsChecking "none" + SignalInfNanChecking "none" + SignalRangeChecking "none" + ReadBeforeWriteMsg "UseLocalSettings" + WriteAfterWriteMsg "UseLocalSettings" + WriteAfterReadMsg "UseLocalSettings" + AlgebraicLoopMsg "warning" + ArtificialAlgebraicLoopMsg "warning" + SaveWithDisabledLinksMsg "warning" + SaveWithParameterizedLinksMsg "warning" + CheckSSInitialOutputMsg on + UnderspecifiedInitializationDetection "Classic" + MergeDetectMultiDrivingBlocksExec "none" + CheckExecutionContextPreStartOutputMsg off + CheckExecutionContextRuntimeOutputMsg off + SignalResolutionControl "UseLocalSettings" + BlockPriorityViolationMsg "warning" + MinStepSizeMsg "warning" + TimeAdjustmentMsg "none" + MaxConsecutiveZCsMsg "error" + MaskedZcDiagnostic "warning" + IgnoredZcDiagnostic "warning" + SolverPrmCheckMsg "warning" + InheritedTsInSrcMsg "warning" + DiscreteInheritContinuousMsg "warning" + MultiTaskDSMMsg "error" + MultiTaskCondExecSysMsg "error" + MultiTaskRateTransMsg "error" + SingleTaskRateTransMsg "none" + TasksWithSamePriorityMsg "warning" + SigSpecEnsureSampleTimeMsg "warning" + CheckMatrixSingularityMsg "none" + IntegerOverflowMsg "warning" + Int32ToFloatConvMsg "warning" + ParameterDowncastMsg "error" + ParameterOverflowMsg "error" + ParameterUnderflowMsg "none" + ParameterPrecisionLossMsg "warning" + ParameterTunabilityLossMsg "warning" + FixptConstUnderflowMsg "none" + FixptConstOverflowMsg "none" + FixptConstPrecisionLossMsg "none" + UnderSpecifiedDataTypeMsg "none" + UnnecessaryDatatypeConvMsg "none" + VectorMatrixConversionMsg "none" + InvalidFcnCallConnMsg "error" + FcnCallInpInsideContextMsg "Enable All" + SignalLabelMismatchMsg "none" + UnconnectedInputMsg "warning" + UnconnectedOutputMsg "warning" + UnconnectedLineMsg "warning" + SFcnCompatibilityMsg "none" + FrameProcessingCompatibilityMsg "warning" + UniqueDataStoreMsg "none" + BusObjectLabelMismatch "warning" + RootOutportRequireBusObject "warning" + AssertControl "UseLocalSettings" + EnableOverflowDetection off + ModelReferenceIOMsg "none" + ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error" + ModelReferenceVersionMismatchMessage "none" + ModelReferenceIOMismatchMessage "none" + ModelReferenceCSMismatchMessage "none" + UnknownTsInhSupMsg "warning" + ModelReferenceDataLoggingMessage "warning" + ModelReferenceSymbolNameMessage "warning" + ModelReferenceExtraNoncontSigs "error" + StateNameClashWarn "warning" + SimStateInterfaceChecksumMismatchMsg "warning" + SimStateOlderReleaseMsg "error" + InitInArrayFormatMsg "warning" + StrictBusMsg "ErrorLevel1" + BusNameAdapt "WarnAndRepair" + NonBusSignalsTreatedAsBus "none" + LoggingUnavailableSignals "error" + BlockIODiagnostic "none" + SFUnusedDataAndEventsDiag "warning" + SFUnexpectedBacktrackingDiag "warning" + SFInvalidInputDataAccessInChartInitDiag "warning" + SFNoUnconditionalDefaultTransitionDiag "warning" + SFTransitionOutsideNaturalParentDiag "warning" + SFUnconditionalTransitionShadowingDiag "warning" + } + Simulink.HardwareCC { + $ObjectID 7 + Version "1.11.1" + ProdBitPerChar 8 + ProdBitPerShort 16 + ProdBitPerInt 32 + ProdBitPerLong 32 + ProdBitPerFloat 32 + ProdBitPerDouble 64 + ProdBitPerPointer 32 + ProdLargestAtomicInteger "Char" + ProdLargestAtomicFloat "None" + ProdIntDivRoundTo "Undefined" + ProdEndianess "Unspecified" + ProdWordSize 32 + ProdShiftRightIntArith on + ProdHWDeviceType "32-bit Generic" + TargetBitPerChar 8 + TargetBitPerShort 16 + TargetBitPerInt 32 + TargetBitPerLong 32 + TargetBitPerFloat 32 + TargetBitPerDouble 64 + TargetBitPerPointer 32 + TargetLargestAtomicInteger "Char" + TargetLargestAtomicFloat "None" + TargetShiftRightIntArith on + TargetIntDivRoundTo "Undefined" + TargetEndianess "Unspecified" + TargetWordSize 32 + TargetTypeEmulationWarnSuppressLevel 0 + TargetPreprocMaxBitsSint 32 + TargetPreprocMaxBitsUint 32 + TargetHWDeviceType "Specified" + TargetUnknown off + ProdEqTarget on + } + Simulink.ModelReferenceCC { + $ObjectID 8 + Version "1.11.1" + UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" + CheckModelReferenceTargetMessage "error" + EnableParallelModelReferenceBuilds off + ParallelModelReferenceErrorOnInvalidPool on + ParallelModelReferenceMATLABWorkerInit "None" + ModelReferenceNumInstancesAllowed "Multi" + PropagateVarSize "Infer from blocks in model" + ModelReferencePassRootInputsByReference on + ModelReferenceMinAlgLoopOccurrences off + PropagateSignalLabelsOutOfModel off + SupportModelReferenceSimTargetCustomCode off + } + Simulink.SFSimCC { + $ObjectID 9 + Version "1.11.1" + SFSimEnableDebug on + SFSimOverflowDetection on + SFSimEcho on + SimBlas on + SimCtrlC on + SimExtrinsic on + SimIntegrity on + SimUseLocalCustomCode off + SimParseCustomCode on + SimBuildMode "sf_incremental_build" + } + Simulink.RTWCC { + $BackupClass "Simulink.RTWCC" + $ObjectID 10 + Version "1.11.1" + Array { + Type "Cell" + Dimension 8 + Cell "IncludeHyperlinkInReport" + Cell "GenerateTraceInfo" + Cell "GenerateTraceReport" + Cell "GenerateTraceReportSl" + Cell "GenerateTraceReportSf" + Cell "GenerateTraceReportEml" + Cell "GenerateSLWebview" + Cell "GenerateCodeMetricsReport" + PropName "DisabledProps" + } + SystemTargetFile "grt.tlc" + GenCodeOnly off + MakeCommand "make_rtw" + GenerateMakefile on + TemplateMakefile "grt_default_tmf" + GenerateReport off + SaveLog off + RTWVerbose on + RetainRTWFile off + ProfileTLC off + TLCDebug off + TLCCoverage off + TLCAssert off + ProcessScriptMode "Default" + ConfigurationMode "Optimized" + ConfigAtBuild off + RTWUseLocalCustomCode off + RTWUseSimCustomCode off + IncludeHyperlinkInReport off + LaunchReport off + TargetLang "C" + IncludeBusHierarchyInRTWFileBlockHierarchyMap off + IncludeERTFirstTime off + GenerateTraceInfo off + GenerateTraceReport off + GenerateTraceReportSl off + GenerateTraceReportSf off + GenerateTraceReportEml off + GenerateCodeInfo off + GenerateSLWebview off + GenerateCodeMetricsReport off + RTWCompilerOptimization "Off" + CheckMdlBeforeBuild "Off" + CustomRebuildMode "OnUpdate" + Array { + Type "Handle" + Dimension 2 + Simulink.CodeAppCC { + $ObjectID 11 + Version "1.11.1" + Array { + Type "Cell" + Dimension 21 + Cell "IgnoreCustomStorageClasses" + Cell "IgnoreTestpoints" + Cell "InsertBlockDesc" + Cell "InsertPolySpaceComments" + Cell "SFDataObjDesc" + Cell "MATLABFcnDesc" + Cell "SimulinkDataObjDesc" + Cell "DefineNamingRule" + Cell "SignalNamingRule" + Cell "ParamNamingRule" + Cell "InlinedPrmAccess" + Cell "CustomSymbolStr" + Cell "CustomSymbolStrGlobalVar" + Cell "CustomSymbolStrType" + Cell "CustomSymbolStrField" + Cell "CustomSymbolStrFcn" + Cell "CustomSymbolStrFcnArg" + Cell "CustomSymbolStrBlkIO" + Cell "CustomSymbolStrTmpVar" + Cell "CustomSymbolStrMacro" + Cell "ReqsInCode" + PropName "DisabledProps" + } + ForceParamTrailComments off + GenerateComments on + IgnoreCustomStorageClasses on + IgnoreTestpoints off + IncHierarchyInIds off + MaxIdLength 31 + PreserveName off + PreserveNameWithParent off + ShowEliminatedStatement off + IncAutoGenComments off + SimulinkDataObjDesc off + SFDataObjDesc off + MATLABFcnDesc off + IncDataTypeInIds off + MangleLength 1 + CustomSymbolStrGlobalVar "$R$N$M" + CustomSymbolStrType "$N$R$M" + CustomSymbolStrField "$N$M" + CustomSymbolStrFcn "$R$N$M$F" + CustomSymbolStrFcnArg "rt$I$N$M" + CustomSymbolStrBlkIO "rtb_$N$M" + CustomSymbolStrTmpVar "$N$M" + CustomSymbolStrMacro "$R$N$M" + DefineNamingRule "None" + ParamNamingRule "None" + SignalNamingRule "None" + InsertBlockDesc off + InsertPolySpaceComments off + SimulinkBlockComments on + MATLABSourceComments off + EnableCustomComments off + InlinedPrmAccess "Literals" + ReqsInCode off + UseSimReservedNames off + } + Simulink.GRTTargetCC { + $BackupClass "Simulink.TargetCC" + $ObjectID 12 + Version "1.11.1" + Array { + Type "Cell" + Dimension 16 + Cell "GeneratePreprocessorConditionals" + Cell "IncludeMdlTerminateFcn" + Cell "CombineOutputUpdateFcns" + Cell "SuppressErrorStatus" + Cell "ERTCustomFileBanners" + Cell "GenerateSampleERTMain" + Cell "GenerateTestInterfaces" + Cell "ModelStepFunctionPrototypeControlCompliant" + Cell "CPPClassGenCompliant" + Cell "MultiInstanceERTCode" + Cell "PurelyIntegerCode" + Cell "SupportComplex" + Cell "SupportAbsoluteTime" + Cell "SupportContinuousTime" + Cell "SupportNonInlinedSFcns" + Cell "PortableWordSizes" + PropName "DisabledProps" + } + TargetFcnLib "ansi_tfl_table_tmw.mat" + TargetLibSuffix "" + TargetPreCompLibLocation "" + TargetFunctionLibrary "ANSI_C" + UtilityFuncGeneration "Auto" + ERTMultiwordTypeDef "System defined" + CodeExecutionProfiling off + ERTMultiwordLength 256 + MultiwordLength 2048 + GenerateFullHeader on + GenerateSampleERTMain off + GenerateTestInterfaces off + IsPILTarget off + ModelReferenceCompliant on + ParMdlRefBuildCompliant on + CompOptLevelCompliant on + ConcurrentExecutionCompliant on + IncludeMdlTerminateFcn on + GeneratePreprocessorConditionals "Disable all" + CombineOutputUpdateFcns off + CombineSignalStateStructs off + SuppressErrorStatus off + ERTFirstTimeCompliant off + IncludeFileDelimiter "Auto" + ERTCustomFileBanners off + SupportAbsoluteTime on + LogVarNameModifier "rt_" + MatFileLogging on + MultiInstanceERTCode off + SupportNonFinite on + SupportComplex on + PurelyIntegerCode off + SupportContinuousTime on + SupportNonInlinedSFcns on + SupportVariableSizeSignals off + EnableShiftOperators on + ParenthesesLevel "Nominal" + PortableWordSizes off + ModelStepFunctionPrototypeControlCompliant off + CPPClassGenCompliant off + AutosarCompliant off + UseMalloc off + ExtMode off + ExtModeStaticAlloc off + ExtModeTesting off + ExtModeStaticAllocSize 1000000 + ExtModeTransport 0 + ExtModeMexFile "ext_comm" + ExtModeIntrfLevel "Level1" + RTWCAPISignals off + RTWCAPIParams off + RTWCAPIStates off + RTWCAPIRootIO off + GenerateASAP2 off + } + PropName "Components" + } + } + PropName "Components" + } + Name "Configuration" + CurrentDlgPage "Solver" + ConfigPrmDlgPosition [ 400, 210, 1280, 840 ] + } + PropName "ConfigurationSets" + } + Simulink.ConfigSet { + $PropName "ActiveConfigurationSet" + $ObjectID 2 + } + BlockDefaults { + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + NamePlacement "normal" + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + ShowName on + BlockRotation 0 + BlockMirror off + } + AnnotationDefaults { + HorizontalAlignment "center" + VerticalAlignment "middle" + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + UseDisplayTextAsClickCallback off + } + LineDefaults { + FontName "Helvetica" + FontSize 9 + FontWeight "normal" + FontAngle "normal" + } + BlockParameterDefaults { + Block { + BlockType Constant + Value "1" + VectorParams1D on + SamplingMode "Sample based" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Inherit from 'Constant value'" + LockScale off + SampleTime "inf" + FramePeriod "inf" + PreserveConstantTs off + } + Block { + BlockType Gain + Gain "1" + Multiplication "Element-wise(K.*u)" + ParamMin "[]" + ParamMax "[]" + ParamDataTypeStr "Inherit: Same as input" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType Inport + Port "1" + OutputFunctionCall off + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + LatchByDelayingOutsideSignal off + LatchInputForFeedbackSignals off + Interpolate on + } + Block { + BlockType Integrator + ExternalReset "none" + InitialConditionSource "internal" + InitialCondition "0" + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + ShowSaturationPort off + ShowStatePort off + AbsoluteTolerance "auto" + IgnoreLimit off + ZeroCross on + ContinuousStateAttributes "''" + } + Block { + BlockType Outport + Port "1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + SourceOfInitialOutputValue "Dialog" + OutputWhenDisabled "held" + InitialOutput "[]" + } + Block { + BlockType RandomNumber + Mean "0" + Variance "1" + Seed "0" + SampleTime "-1" + VectorParams1D on + } + Block { + BlockType SubSystem + ShowPortLabels "FromPortIcon" + Permissions "ReadWrite" + PermitHierarchicalResolution "All" + TreatAsAtomicUnit off + CheckFcnCallInpInsideContextMsg off + SystemSampleTime "-1" + RTWFcnNameOpts "Auto" + RTWFileNameOpts "Auto" + RTWMemSecFuncInitTerm "Inherit from model" + RTWMemSecFuncExecute "Inherit from model" + RTWMemSecDataConstants "Inherit from model" + RTWMemSecDataInternal "Inherit from model" + RTWMemSecDataParameters "Inherit from model" + SimViewingDevice off + DataTypeOverride "UseLocalSettings" + DataTypeOverrideAppliesTo "AllNumericTypes" + MinMaxOverflowLogging "UseLocalSettings" + SFBlockType "NONE" + Variant off + GeneratePreprocessorConditionals off + } + Block { + BlockType Sum + IconShape "rectangular" + Inputs "++" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + AccumDataTypeStr "Inherit: Inherit via internal rule" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + } + System { + Name "altitude_plant" + Location [2567, 115, 3338, 555] + Open on + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + ReportName "simulink-default.rpt" + SIDHighWatermark "69" + Block { + BlockType Inport + Name "Altitude Setpoint" + SID "62" + Position [25, 133, 55, 147] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Sum + Name "Add" + SID "68" + Ports [2, 1] + Position [225, 127, 255, 158] + ZOrder -2 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Constant + Name "Constant" + SID "69" + Position [140, 80, 170, 110] + ZOrder -5 + Value "0" + } + Block { + BlockType Reference + Name "PID Controller (2DOF)" + SID "67" + Ports [2, 1] + Position [140, 130, 195, 170] + ZOrder -7 + LibraryVersion "1.256" + SourceBlock "simulink/Continuous/PID Controller (2DOF)" + SourceType "PID 2dof" + Controller "PID" + TimeDomain "Continuous-time" + SampleTime "1" + IntegratorMethod "Forward Euler" + FilterMethod "Forward Euler" + Form "Parallel" + P "0.1" + I "0.0" + D "0" + N "100" + b "1" + c "1" + InitialConditionSource "internal" + InitialConditionForIntegrator "0" + InitialConditionForFilter "0" + ExternalReset "none" + IgnoreLimit off + ZeroCross on + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + LinearizeAsGain off + AntiWindupMode "none" + Kb "1" + TrackingMode off + Kt "1" + RndMeth "Floor" + SaturateOnIntegerOverflow off + LockScale off + PParamMin "[]" + PParamMax "[]" + PParamDataTypeStr "Inherit: Inherit via internal rule" + IParamMin "[]" + IParamMax "[]" + IParamDataTypeStr "Inherit: Inherit via internal rule" + DParamMin "[]" + DParamMax "[]" + DParamDataTypeStr "Inherit: Inherit via internal rule" + NParamMin "[]" + NParamMax "[]" + NParamDataTypeStr "Inherit: Inherit via internal rule" + bParamMin "[]" + bParamMax "[]" + bParamDataTypeStr "Inherit: Inherit via internal rule" + cParamMin "[]" + cParamMax "[]" + cParamDataTypeStr "Inherit: Inherit via internal rule" + KbParamMin "[]" + KbParamMax "[]" + KbParamDataTypeStr "Inherit: Inherit via internal rule" + KtParamMin "[]" + KtParamMax "[]" + KtParamDataTypeStr "Inherit: Inherit via internal rule" + POutMin "[]" + POutMax "[]" + POutDataTypeStr "Inherit: Inherit via internal rule" + IOutMin "[]" + IOutMax "[]" + IOutDataTypeStr "Inherit: Inherit via internal rule" + DOutMin "[]" + DOutMax "[]" + DOutDataTypeStr "Inherit: Inherit via internal rule" + NOutMin "[]" + NOutMax "[]" + NOutDataTypeStr "Inherit: Inherit via internal rule" + bOutMin "[]" + bOutMax "[]" + bOutDataTypeStr "Inherit: Inherit via internal rule" + cOutMin "[]" + cOutMax "[]" + cOutDataTypeStr "Inherit: Inherit via internal rule" + KbOutMin "[]" + KbOutMax "[]" + KbOutDataTypeStr "Inherit: Inherit via internal rule" + KtOutMin "[]" + KtOutMax "[]" + KtOutDataTypeStr "Inherit: Inherit via internal rule" + IntegratorOutMin "[]" + IntegratorOutMax "[]" + IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" + FilterOutMin "[]" + FilterOutMax "[]" + FilterOutDataTypeStr "Inherit: Inherit via internal rule" + SumOutMin "[]" + SumOutMax "[]" + SumOutDataTypeStr "Inherit: Inherit via internal rule" + Sum1OutMin "[]" + Sum1OutMax "[]" + Sum1OutDataTypeStr "Inherit: Inherit via internal rule" + Sum2OutMin "[]" + Sum2OutMax "[]" + Sum2OutDataTypeStr "Inherit: Inherit via internal rule" + Sum3OutMin "[]" + Sum3OutMax "[]" + Sum3OutDataTypeStr "Inherit: Inherit via internal rule" + SumI1OutMin "[]" + SumI1OutMax "[]" + SumI1OutDataTypeStr "Inherit: Inherit via internal rule" + SumI2OutMin "[]" + SumI2OutMax "[]" + SumI2OutDataTypeStr "Inherit: Inherit via internal rule" + SumI3OutMin "[]" + SumI3OutMax "[]" + SumI3OutDataTypeStr "Inherit: Inherit via internal rule" + SumDOutMin "[]" + SumDOutMax "[]" + SumDOutDataTypeStr "Inherit: Inherit via internal rule" + SumAccumDataTypeStr "Inherit: Inherit via internal rule" + Sum1AccumDataTypeStr "Inherit: Inherit via internal rule" + Sum2AccumDataTypeStr "Inherit: Inherit via internal rule" + Sum3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumDAccumDataTypeStr "Inherit: Inherit via internal rule" + SaturationOutMin "[]" + SaturationOutMax "[]" + SaturationOutDataTypeStr "Inherit: Same as input" + IntegratorContinuousStateAttributes "''" + IntegratorStateMustResolveToSignalObject off + IntegratorRTWStateStorageClass "Auto" + FilterContinuousStateAttributes "''" + FilterStateMustResolveToSignalObject off + FilterRTWStateStorageClass "Auto" + } + Block { + BlockType SubSystem + Name "Subsystem" + SID "57" + Ports [1, 3] + Position [300, 120, 440, 180] + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + RTWSystemCode "Auto" + FunctionWithSeparateData off + Opaque off + RequestExecContextInheritance off + MaskHideContents off + System { + Name "Subsystem" + Location [700, 127, 1473, 405] + Open on + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "Throttle" + SID "58" + Position [25, 33, 55, 47] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType RandomNumber + Name "Accel Noise" + SID "24" + Position [195, 125, 225, 155] + ZOrder -15 + SampleTime "0.1" + } + Block { + BlockType Sum + Name "Add" + SID "25" + Ports [2, 1] + Position [195, 32, 225, 63] + ZOrder -2 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "Acceleration" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Add1" + SID "26" + Ports [2, 1] + Position [260, 117, 290, 148] + ZOrder -2 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Add2" + SID "27" + Ports [2, 1] + Position [480, 87, 510, 118] + ZOrder -2 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType RandomNumber + Name "Altitude Noise" + SID "28" + Position [420, 95, 450, 125] + ZOrder -15 + SampleTime "0.1" + } + Block { + BlockType Gain + Name "Gain" + SID "29" + Position [115, 25, 145, 55] + ZOrder -11 + Gain "9.81" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "Thrust" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Constant + Name "Gravity" + SID "30" + Position [115, 80, 145, 110] + ZOrder -5 + Value "-9.81" + } + Block { + BlockType Integrator + Name "Integrator" + SID "31" + Ports [1, 1] + Position [305, 35, 335, 65] + ZOrder -2 + Port { + PortNumber 1 + Name "Velocity" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Integrator + Name "Integrator1" + SID "32" + Ports [1, 1] + Position [420, 35, 450, 65] + ZOrder -2 + } + Block { + BlockType Outport + Name "Altitude" + SID "59" + Position [520, 43, 550, 57] + ZOrder -9 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "Measured Altitude" + SID "60" + Position [570, 98, 600, 112] + ZOrder -9 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "Measured Accel" + SID "61" + Position [335, 128, 365, 142] + ZOrder -9 + Port "3" + IconDisplay "Port number" + } + Line { + SrcBlock "Add1" + SrcPort 1 + DstBlock "Measured Accel" + DstPort 1 + } + Line { + SrcBlock "Altitude Noise" + SrcPort 1 + DstBlock "Add2" + DstPort 2 + } + Line { + SrcBlock "Accel Noise" + SrcPort 1 + DstBlock "Add1" + DstPort 2 + } + Line { + SrcBlock "Integrator1" + SrcPort 1 + Points [15, 0] + Branch { + Points [-5, 0] + DstBlock "Add2" + DstPort 1 + } + Branch { + DstBlock "Altitude" + DstPort 1 + } + } + Line { + Name "Velocity" + Labels [1, 0] + SrcBlock "Integrator" + SrcPort 1 + DstBlock "Integrator1" + DstPort 1 + } + Line { + Name "Acceleration" + SrcBlock "Add" + SrcPort 1 + Points [15, 0] + Branch { + DstBlock "Add1" + DstPort 1 + } + Branch { + Labels [1, 0] + DstBlock "Integrator" + DstPort 1 + } + } + Line { + SrcBlock "Gravity" + SrcPort 1 + Points [15, 0; 0, -40] + DstBlock "Add" + DstPort 2 + } + Line { + Name "Thrust" + Labels [1, 0] + SrcBlock "Gain" + SrcPort 1 + DstBlock "Add" + DstPort 1 + } + Line { + SrcBlock "Add2" + SrcPort 1 + DstBlock "Measured Altitude" + DstPort 1 + } + Line { + SrcBlock "Throttle" + SrcPort 1 + DstBlock "Gain" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "Altitude" + SID "37" + Position [620, 123, 650, 137] + ZOrder -9 + NamePlacement "alternate" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "Measured Altitude" + SID "38" + Position [685, 143, 715, 157] + ZOrder -9 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "Measured Accel" + SID "39" + Position [485, 163, 515, 177] + ZOrder -9 + Port "3" + IconDisplay "Port number" + } + Line { + SrcBlock "Subsystem" + SrcPort 1 + DstBlock "Altitude" + DstPort 1 + } + Line { + SrcBlock "Subsystem" + SrcPort 2 + Points [105, 0] + Branch { + DstBlock "Measured Altitude" + DstPort 1 + } + Branch { + Points [0, 55; -455, 0; 0, -45] + DstBlock "PID Controller (2DOF)" + DstPort 2 + } + } + Line { + SrcBlock "Subsystem" + SrcPort 3 + DstBlock "Measured Accel" + DstPort 1 + } + Line { + SrcBlock "Altitude Setpoint" + SrcPort 1 + DstBlock "PID Controller (2DOF)" + DstPort 1 + } + Line { + SrcBlock "PID Controller (2DOF)" + SrcPort 1 + DstBlock "Add" + DstPort 2 + } + Line { + SrcBlock "Add" + SrcPort 1 + Points [10, 0; 0, 5] + DstBlock "Subsystem" + DstPort 1 + } + Line { + SrcBlock "Constant" + SrcPort 1 + Points [35, 0] + DstBlock "Add" + DstPort 1 + } + } +} diff --git a/matlab/revo/async_attitude.m b/matlab/revo/async_attitude.m new file mode 100644 index 000000000..ebbe4801f --- /dev/null +++ b/matlab/revo/async_attitude.m @@ -0,0 +1,106 @@ +baro = fixTime(BaroAltitude); +accel = fixTime(Accels); +attitude = fixTime(AttitudeActual); + +%accel.z(end/2:end) = accel.z(end/2:end) + 1; +accel.z = accel.z+2; + +Gamma = diag([1e-15 1e-15 1e-3 1e-5]); % state noise +accel_sigma = 10; +baro_sigma = 0.1; +Nu = diag([10 10 10 1000]); +z = zeros(length(accel.z),4); +Nu_n = zeros([4 4 length(accel.z)]); +Nu_n(:,:,1) = Nu; + +t = max(accel.timestamp(1), baro.timestamp(1)); +last_t = t-1; +last_accel_idx = 1; +last_baro_idx = 1; +i = 1; +timestamp = []; + +z(1) = baro.Altitude(1); +z(1:5,4) = 0; +timestamp(1) = t; +log_accel = 0; +while (last_accel_idx + 1) <= length(accel.z) && (last_baro_idx + 1) <= length(baro.Altitude) + + update_baro = baro.timestamp(last_baro_idx + 1) < t; + update_accel = accel.timestamp(last_accel_idx + 1) < t; + + if 0 && update_accel + [~,idx] = min(abs(attitude.timestamp - accel.timestamp(last_accel_idx+1))); + Rbe = Quat2Rbe([attitude.q1(idx), attitude.q2(idx), attitude.q3(idx), attitude.q4(idx)]); + idx = last_accel_idx + 1; + accel_ned = Rbe * [accel.x(idx); accel.y(idx); accel.z(idx)]; + accel_ned = accel_ned(3); +% if(abs(accel_ned) < 1e-1) +% keyboard +% end + else + accel_ned = accel.z(last_accel_idx + 1); + end + log_accel(i) = accel_ned; + if update_baro && update_accel; + x = [baro.Altitude(last_baro_idx + 1); -accel_ned-9.81]; + last_baro_idx = last_baro_idx + 1; + last_accel_idx = last_accel_idx + 1; + C = [1 0 0 0; 0 0 1 1]; + Sigma = diag([baro_sigma; accel_sigma]); + elseif update_accel + x = -accel_ned - 9.81; + last_accel_idx = last_accel_idx + 1; + C = [0 0 1 1]; + Sigma = [accel_sigma]; + elseif update_baro + x = [baro.Altitude(last_baro_idx + 1)]; + last_baro_idx = last_baro_idx + 1; + C = [1 0 0 0]; + Sigma = [baro_sigma]; + else + % Take a timestep and look for advance + t = t + 0.1; + continue; + end + %[last_baro_idx last_accel_idx] + t = max(baro.timestamp(last_baro_idx), accel.timestamp(last_accel_idx)); + dT = (t - last_t) / 1000; + if(dT == 0) + dT = 1.5 / 1000; + end + assert(dT ~= 0,'WTF'); + last_t = t; + + i = i + 1; + + A = [1 dT 0 0; 0 1 dT 0; 0 0 1 0; 0 0 0 1]; + + P = A * Nu * A' + Gamma; + K = P*C'*(C*P*C'+Sigma)^-1; + + z(i,:) = A * z(i-1,:)' + K * (x - C * A * z(i-1,:)'); + timestamp(i) = t; + Nu = (eye(4) - K * C) * P; + Nu_n(:,:,i) = Nu; + + if mod(i,10000) == 0 + subplot(311) + plot(baro.timestamp, baro.Altitude, '.', timestamp(1:i),z(1:i,1),'r','LineWidth',5) + subplot(312) + plot(timestamp(1:i),z(1:i,2),'k') + subplot(313) + plot(timestamp(1:i),z(1:i,3),'k'); + xlim(timestamp([1,i])) + drawnow + end +end + +subplot(311) +plot(baro.timestamp, baro.Altitude, '.', timestamp(1:i),z(1:i,1),'r','LineWidth',5) +subplot(312) +plot(timestamp(1:i),z(1:i,2),'k') +subplot(313) +plot(timestamp(1:i),z(1:i,3),'k'); +xlim(timestamp([1,i])) + diff --git a/matlab/revo/generate_altitude.m b/matlab/revo/generate_altitude.m new file mode 100644 index 000000000..ef0f186aa --- /dev/null +++ b/matlab/revo/generate_altitude.m @@ -0,0 +1,69 @@ +% Generate the symbolic code for the kalman filter on altitude + +dT = sym('dT','real'); +A = [1 dT 0 0; 0 1 dT 0; 0 0 1 0; 0 0 0 1]; +%Nu = diag([sym('V[1]') sym('V[2]') sym('V[3]') sym('V[4]')]); +%Nu = [sym('V[1][1]') 0 0 0; ... +% 0 sym('V[2][2]') 0 0; ... +% 0 0 sym('V[3][3]') sym('V[3][4]'); ... +% 0 0 sym('V[4][3]') sym('V[4][4]')]; +Nu = [sym('V[1][1]') sym('V[1][2]') sym('V[1][3]') sym('V[1][4]'); ... + sym('V[2][1]') sym('V[2][2]') sym('V[2][3]') sym('V[2][4]'); ... + sym('V[3][1]') sym('V[3][2]') sym('V[3][3]') sym('V[3][4]'); ... + sym('V[4][1]') sym('V[4][2]') sym('V[4][3]') sym('V[4][4]');]; + + +Gamma = diag([sym('G[1]') sym('G[2]') sym('G[3]') sym('G[4]')]); +Sigma = diag([sym('S[1]') sym('S[2]')]); +C = [1 0 0 0; 0 0 1 1]; +state = [sym('z[1]'); sym('z[2]'); sym('z[3]'); sym('z[4]')]; +measure = [sym('x[1]'); sym('x[2]')]; + +P = simplify(A * Nu * A' + Gamma); +K = simplify(P*C'*(C*P*C'+Sigma)^-1); + +% fill in the zeros from above equations to make next calculation sparse +P_mat = [sym('P[1][1]') sym('P[1][2]') sym('P[1][3]') sym('P[1][4]'); ... + sym('P[2][1]') sym('P[2][2]') sym('P[2][3]') sym('P[2][4]'); ... + sym('P[3][1]') sym('P[3][2]') sym('P[3][3]') sym('P[3][4]'); ... + sym('P[4][1]') sym('P[4][3]') sym('P[4][3]') sym('P[4][4]')]; +K_mat = [sym('K[1][1]') sym('K[1][2]'); ... + sym('K[2][1]') sym('K[2][2]'); ... + sym('K[3][1]') sym('K[3][2]'); ... + sym('K[4][1]') sym('K[4][2]')]; + +z_new = A * state + K_mat * (measure - C * A * state); +V = (eye(4) - K_mat * C) * P_mat; + +ccode(P) +ccode(K) +ccode(z_new) +ccode(V) + + +%% For when there is no baro update +% Generate the symbolic code for the kalman filter on altitude +C = [0 0 1 1]; +Sigma = sym('S[2]'); +measure = [sym('x[2]')]; + +P = simplify(A * Nu * A' + Gamma); +K = simplify(P*C'*(C*P*C'+Sigma)^-1); + +% fill in the zeros from above equations to make next calculation sparse +P_mat = [sym('P[1][1]') sym('P[1][2]') sym('P[1][3]') sym('P[1][4]'); ... + sym('P[2][1]') sym('P[2][2]') sym('P[2][3]') sym('P[2][4]'); ... + sym('P[3][1]') sym('P[3][2]') sym('P[3][3]') sym('P[3][4]'); ... + sym('P[4][1]') sym('P[4][3]') sym('P[4][3]') sym('P[4][4]')]; +K_mat = [sym('K[1][1]'); ... + sym('K[2][1]'); ... + sym('K[3][1]'); ... + sym('K[4][1]')]; + +z_new = A * state + K_mat * (measure - C * A * state); +V = (eye(4) - K_mat * C) * P_mat; + +ccode(P) +ccode(K) +ccode(z_new) +ccode(V) diff --git a/matlab/revo/lla2ecef.m b/matlab/revo/lla2ecef.m new file mode 100644 index 000000000..e82cdc9eb --- /dev/null +++ b/matlab/revo/lla2ecef.m @@ -0,0 +1,15 @@ +function ECEF = lla2ecef(latitude,longitude,altitude) + +a = 6378137.0; +e = 8.1819190842622e-2; +DEG2RAD = pi / 180; +sinLat = sin(DEG2RAD * latitude); +sinLon = sin(DEG2RAD * longitude); +cosLat = cos(DEG2RAD * latitude); +cosLon = cos(DEG2RAD * longitude); + +N = a ./ sqrt(1.0 - e * e .* sinLat .* sinLat); + +ECEF(:,1) = (N + altitude) .* cosLat .* cosLon; +ECEF(:,2) = (N + altitude) .* cosLat .* sinLon; +ECEF(:,3) = ((1 - e * e) * N + altitude) .* sinLat; diff --git a/matlab/revo/sensor_log.m b/matlab/revo/sensor_log.m new file mode 100644 index 000000000..de40e3eb7 --- /dev/null +++ b/matlab/revo/sensor_log.m @@ -0,0 +1,154 @@ +fn = '~/Documents/Programming/serial_logger/bma180_l3gd20_desk_20120228.dat'; +fn = '~/Documents/Programming/serial_logger/mpu6000_desk_20120228.dat'; +fn = '~/Documents/Programming/serial_logger/mpu6000_desk2_20110228.dat'; +fn = '~/Documents/Programming/serial_logger/output.dat'; +fid = fopen(fn); +dat = uint8(fread(fid,'uint8')); +fclose(fid); + +accel = zeros(4096,1); +accel_idx = 0; + +gyro = zeros(4096,1); +gyro_idx = 0; + +mag = zeros(4096,1); +mag_idx = 0; + +latitude = zeros(4096,1); +longitude = zeros(4096,1); +altitude = zeros(4096,1); +heading = zeros(4096,1); +groundspeed = zeros(4096,1); +gps_satellites = zeros(4096,1); +gps_time = zeros(4096,1); +gps_idx = 0; + +baro = zeros(4096,1); +baro_idx = 0; + +total = length(dat); +count = 0; +head = 0; +last_time = 0; +good_samples = 0; +bad_samples = 0; +while head < (length(dat) - 200) + + last_head = head; + + count = count + 1; + if count >= 5000 + disp(sprintf('Processed: %0.3g%% Bad: %0.3g%%',(head/total) * 100,bad_samples * 100 / (bad_samples + good_samples))); + count = 0; + end + idx = find(dat(head+1:head+100)==255,1,'first'); + if isempty(idx) + head = head + 100; + continue; + end + head = head + idx; + + + % Get the time + time = double(dat(head+1))* 256 + double(dat(head+2));%typecast(flipud(dat(head+(1:2))),'uint16'); + if min([(time - last_time) (last_time - time)]) > 2 + disp(['Err' num2str(time-last_time)]); + last_time = time; + bad_samples = bad_samples + (head - last_head); + continue + end + last_time = time; + + head = head + 2; + + % Get the accels + accel_idx = accel_idx + 1; + if accel_idx > size(accel,1) + accel(accel_idx * 2,:) = 0; + end + accel(accel_idx,1:3) = typecast(dat(head+(1:12)),'single'); + head = head + 12; + accel(accel_idx,4) = time; + + % Get the gyros + gyro_idx = gyro_idx + 1; + if gyro_idx > size(gyro,1); + gyro(gyro_idx * 2,:) = 0; + end + gyro(gyro_idx,1:4) = typecast(dat(head+(1:16)),'single'); + head = head + 16; + gyro(gyro_idx,5) = time; + + if dat(head+1) == 1 % Process the mag data + head = head+1; + mag_idx = mag_idx + 1; + if mag_idx > size(mag,1) + mag(mag_idx * 2, :) = 0; + end + mag(mag_idx,1:3) = typecast(dat(head + (1:12)),'single'); + head = head+12; + mag(mag_idx,4) = time; + end + + if dat(head+1) == 2 % Process the GPS data + % typedef struct { + % int32_t Latitude; + % int32_t Longitude; + % float Altitude; + % float GeoidSeparation; + % float Heading; + % float Groundspeed; + % float PDOP; + % float HDOP; + % float VDOP; + % uint8_t Status; + % int8_t Satellites; + % } __attribute__((packed)) GPSPositionData; + + head = head+1; + + gps_idx = gps_idx + 1; + if gps_idx > length(latitude) + latitude(gps_idx * 2) = 0; + longitude(gps_idx * 2) = 0; + altitude(gps_idx * 2) = 0; + heading(gps_idx * 2) = 0; + groundspeed(gps_idx * 2) = 0; + gps_satellites(gps_idx * 2) = 0; + gps_time(gps_idx * 2) = 0; + end + + latitude(gps_idx) = double(typecast(dat(head+(1:4)),'int32')) / 1e7; + longitude(gps_idx) = double(typecast(dat(head+(5:8)),'int32')) / 1e7; + altitude(gps_idx) = typecast(dat(head+(9:12)),'single'); + heading(gps_idx) = typecast(dat(head+(17:20)),'single'); + groundspeed(gps_idx) = typecast(dat(head+(21:24)),'single'); + gps_satelites(gps_idx) = dat(head+38); + gps_time(gps_idx) = time; + head = head + 9 * 4 + 2; + end + + if dat(head+1) == 3 % Process the baro data + head = head + 1; + baro_idx = baro_idx + 1; + if baro_idx > size(baro,1) + baro(baro_idx * 2,:) = 0; + end + baro(baro_idx,1) = typecast(dat(head+(1:4)),'single'); + baro(baro_idx,2) = time; + end + + good_samples = good_samples + (head - last_head); +end + +accel(accel_idx+1:end,:) = []; +gyro(gyro_idx+1:end,:) = []; +mag(mag_idx+1:end) = []; +latitude(gps_idx+1:end) = []; +longitude(gps_idx+1:end) = []; +altitude(gps_idx+1:end) = []; +groundspeed(gps_idx+1:end) = []; +gps_satellites(gps_idx+1:end) = []; +gps_time(gps_idx+1:end) = []; +baro(baro_idx+1:end,:) = []; diff --git a/matlab/revo/unwrap_time.m b/matlab/revo/unwrap_time.m new file mode 100644 index 000000000..44961bb19 --- /dev/null +++ b/matlab/revo/unwrap_time.m @@ -0,0 +1,7 @@ +function t = unwrap_time(t) + +wrap = find((t(2:end) - t(1:end-1) ) < -64000); +jump = zeros(size(t)); +jump(wrap+1) = hex2dec('10000'); + +t = t + cumsum(jump); \ No newline at end of file diff --git a/overo b/overo new file mode 160000 index 000000000..335a3486d --- /dev/null +++ b/overo @@ -0,0 +1 @@ +Subproject commit 335a3486dd41e48345209d0a65d49a8cc8b442a1 diff --git a/package/Makefile b/package/Makefile index 5598be8c3..13d12f83c 100644 --- a/package/Makefile +++ b/package/Makefile @@ -30,10 +30,11 @@ CLEAN_FLIGHT := YES endif # Set up targets -FW_TARGETS := $(addprefix fw_, coptercontrol) -FW_TARGETS_TOOLS := $(addprefix fw_, coptercontrol) -BL_TARGETS := $(addprefix bl_, coptercontrol) -BU_TARGETS := $(addprefix bu_, coptercontrol) +ALL_BOARDS := coptercontrol pipxtreme +FW_TARGETS := $(addprefix fw_, $(ALL_BOARDS)) +FW_TARGETS_TOOLS := $(addprefix fw_, $(ALL_BOARDS)) +BL_TARGETS := $(addprefix bl_, $(ALL_BOARDS)) +BU_TARGETS := $(addprefix bu_, $(ALL_BOARDS)) help: @echo diff --git a/package/osx/OpenPilot.dmg b/package/osx/OpenPilot.dmg index 9d231cdf6..f0fa6fbc7 100644 Binary files a/package/osx/OpenPilot.dmg and b/package/osx/OpenPilot.dmg differ diff --git a/package/osx/package b/package/osx/package index 8a4860b5d..11d2a1417 100755 --- a/package/osx/package +++ b/package/osx/package @@ -21,7 +21,10 @@ device=$(hdiutil attach "${TEMP_FILE}" | \ # packaging goes here cp -r "${APP_PATH}" "/Volumes/${VOL_NAME}" #cp -r "${FW_DIR}" "/Volumes/${VOL_NAME}/firmware" -cp "${FW_DIR}/fw_coptercontrol-${PACKAGE_LBL}.opfw" "/Volumes/${VOL_NAME}/firmware" +cp "${FW_DIR}/fw_coptercontrol-${PACKAGE_LBL}.opfw" "/Volumes/${VOL_NAME}/Firmware" +cp "${FW_DIR}/fw_pipxtreme-${PACKAGE_LBL}.opfw" "/Volumes/${VOL_NAME}/Firmware" + +cp "${BUILD_DIR}/uavobject-synthetics/matlab/OPLogConvert.m" "/Volumes/${VOL_NAME}/Utilities" cp "${ROOT_DIR}/HISTORY.txt" "/Volumes/${VOL_NAME}" diff --git a/shared/uavobjectdefinition/accels.xml b/shared/uavobjectdefinition/accels.xml new file mode 100644 index 000000000..3a5e34b84 --- /dev/null +++ b/shared/uavobjectdefinition/accels.xml @@ -0,0 +1,13 @@ + + + The accel data. + + + + + + + + + + diff --git a/shared/uavobjectdefinition/accessorydesired.xml b/shared/uavobjectdefinition/accessorydesired.xml index d0a7b0ed8..dbeb583d9 100644 --- a/shared/uavobjectdefinition/accessorydesired.xml +++ b/shared/uavobjectdefinition/accessorydesired.xml @@ -5,6 +5,6 @@ - + diff --git a/shared/uavobjectdefinition/actuatorcommand.xml b/shared/uavobjectdefinition/actuatorcommand.xml index c0b65bbbc..a28b70df4 100644 --- a/shared/uavobjectdefinition/actuatorcommand.xml +++ b/shared/uavobjectdefinition/actuatorcommand.xml @@ -8,6 +8,6 @@ - + diff --git a/shared/uavobjectdefinition/actuatordesired.xml b/shared/uavobjectdefinition/actuatordesired.xml index f3ad47654..5b7b2f80e 100644 --- a/shared/uavobjectdefinition/actuatordesired.xml +++ b/shared/uavobjectdefinition/actuatordesired.xml @@ -10,6 +10,6 @@ - + diff --git a/shared/uavobjectdefinition/actuatorsettings.xml b/shared/uavobjectdefinition/actuatorsettings.xml index dd64dad15..7f438a22c 100644 --- a/shared/uavobjectdefinition/actuatorsettings.xml +++ b/shared/uavobjectdefinition/actuatorsettings.xml @@ -1,25 +1,6 @@ Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType - - - - - - - - - - - - - - - - - - - @@ -30,6 +11,6 @@ - + diff --git a/shared/uavobjectdefinition/ahrscalibration.xml b/shared/uavobjectdefinition/ahrscalibration.xml deleted file mode 100644 index b56f86985..000000000 --- a/shared/uavobjectdefinition/ahrscalibration.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - Contains the calibration settings for the @ref AHRSCommsModule - - - - - - - - - - - - - - - - - - - - diff --git a/shared/uavobjectdefinition/ahrssettings.xml b/shared/uavobjectdefinition/ahrssettings.xml deleted file mode 100644 index d5756cde8..000000000 --- a/shared/uavobjectdefinition/ahrssettings.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - Settings for the @ref AHRSCommsModule to control the algorithm and what is updated - - - - - - - - - - - - - diff --git a/shared/uavobjectdefinition/ahrsstatus.xml b/shared/uavobjectdefinition/ahrsstatus.xml deleted file mode 100644 index 4065a88cf..000000000 --- a/shared/uavobjectdefinition/ahrsstatus.xml +++ /dev/null @@ -1,25 +0,0 @@ - - - Status for the @ref AHRSCommsModule, including communication errors - - - - - - - - - - - - - - - - - - - - - - diff --git a/shared/uavobjectdefinition/altholdsmoothed.xml b/shared/uavobjectdefinition/altholdsmoothed.xml new file mode 100644 index 000000000..ef1b5f144 --- /dev/null +++ b/shared/uavobjectdefinition/altholdsmoothed.xml @@ -0,0 +1,12 @@ + + + The output on the kalman filter on altitude. + + + + + + + + + diff --git a/shared/uavobjectdefinition/altitudeholddesired.xml b/shared/uavobjectdefinition/altitudeholddesired.xml new file mode 100644 index 000000000..8cb004011 --- /dev/null +++ b/shared/uavobjectdefinition/altitudeholddesired.xml @@ -0,0 +1,13 @@ + + + Holds the desired altitude (from manual control) as well as the desired attitude to pass through + + + + + + + + + + diff --git a/shared/uavobjectdefinition/altitudeholdsettings.xml b/shared/uavobjectdefinition/altitudeholdsettings.xml new file mode 100644 index 000000000..215f1d586 --- /dev/null +++ b/shared/uavobjectdefinition/altitudeholdsettings.xml @@ -0,0 +1,16 @@ + + + Settings for the @ref AltitudeHold module + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/attitudeactual.xml b/shared/uavobjectdefinition/attitudeactual.xml index 6db0e06b2..2d1d66a32 100644 --- a/shared/uavobjectdefinition/attitudeactual.xml +++ b/shared/uavobjectdefinition/attitudeactual.xml @@ -11,6 +11,6 @@ - + diff --git a/shared/uavobjectdefinition/attituderaw.xml b/shared/uavobjectdefinition/attituderaw.xml deleted file mode 100644 index 8a2a69ab7..000000000 --- a/shared/uavobjectdefinition/attituderaw.xml +++ /dev/null @@ -1,13 +0,0 @@ - - - The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. - - - - - - - - - - diff --git a/shared/uavobjectdefinition/attitudesettings.xml b/shared/uavobjectdefinition/attitudesettings.xml index e60c2454b..ca0ba9dc5 100644 --- a/shared/uavobjectdefinition/attitudesettings.xml +++ b/shared/uavobjectdefinition/attitudesettings.xml @@ -14,6 +14,6 @@ - + diff --git a/shared/uavobjectdefinition/baroaltitude.xml b/shared/uavobjectdefinition/baroaltitude.xml index aeabfc68c..8335b56dd 100644 --- a/shared/uavobjectdefinition/baroaltitude.xml +++ b/shared/uavobjectdefinition/baroaltitude.xml @@ -7,6 +7,6 @@ - + diff --git a/shared/uavobjectdefinition/cameradesired.xml b/shared/uavobjectdefinition/cameradesired.xml index 022728f7e..7d9cdbe64 100644 --- a/shared/uavobjectdefinition/cameradesired.xml +++ b/shared/uavobjectdefinition/cameradesired.xml @@ -7,6 +7,6 @@ - + diff --git a/shared/uavobjectdefinition/camerastabsettings.xml b/shared/uavobjectdefinition/camerastabsettings.xml index 069abdeb3..d6956c9fa 100644 --- a/shared/uavobjectdefinition/camerastabsettings.xml +++ b/shared/uavobjectdefinition/camerastabsettings.xml @@ -11,6 +11,6 @@ - + diff --git a/shared/uavobjectdefinition/faultsettings.xml b/shared/uavobjectdefinition/faultsettings.xml index 8d02f0d78..6750c4f99 100644 --- a/shared/uavobjectdefinition/faultsettings.xml +++ b/shared/uavobjectdefinition/faultsettings.xml @@ -7,6 +7,6 @@ - + diff --git a/shared/uavobjectdefinition/firmwareiapobj.xml b/shared/uavobjectdefinition/firmwareiapobj.xml index 51438395e..30b070857 100644 --- a/shared/uavobjectdefinition/firmwareiapobj.xml +++ b/shared/uavobjectdefinition/firmwareiapobj.xml @@ -11,7 +11,7 @@ - + diff --git a/shared/uavobjectdefinition/flightbatterysettings.xml b/shared/uavobjectdefinition/flightbatterysettings.xml index a7f796ea0..c95e7e817 100644 --- a/shared/uavobjectdefinition/flightbatterysettings.xml +++ b/shared/uavobjectdefinition/flightbatterysettings.xml @@ -14,6 +14,6 @@ - + diff --git a/shared/uavobjectdefinition/flightbatterystate.xml b/shared/uavobjectdefinition/flightbatterystate.xml index bc5310b8b..5cefbdd86 100644 --- a/shared/uavobjectdefinition/flightbatterystate.xml +++ b/shared/uavobjectdefinition/flightbatterystate.xml @@ -10,6 +10,6 @@ - + diff --git a/shared/uavobjectdefinition/flightplancontrol.xml b/shared/uavobjectdefinition/flightplancontrol.xml index bc9dbdfa6..f4412f74a 100644 --- a/shared/uavobjectdefinition/flightplancontrol.xml +++ b/shared/uavobjectdefinition/flightplancontrol.xml @@ -5,6 +5,6 @@ - + diff --git a/shared/uavobjectdefinition/flightplansettings.xml b/shared/uavobjectdefinition/flightplansettings.xml index d4c16ec7f..cd1464e8d 100644 --- a/shared/uavobjectdefinition/flightplansettings.xml +++ b/shared/uavobjectdefinition/flightplansettings.xml @@ -5,6 +5,6 @@ - + diff --git a/shared/uavobjectdefinition/flightplanstatus.xml b/shared/uavobjectdefinition/flightplanstatus.xml index fcf086d26..b5667de30 100644 --- a/shared/uavobjectdefinition/flightplanstatus.xml +++ b/shared/uavobjectdefinition/flightplanstatus.xml @@ -9,6 +9,6 @@ - + diff --git a/shared/uavobjectdefinition/flightstatus.xml b/shared/uavobjectdefinition/flightstatus.xml index 849e458d6..22c4f9360 100644 --- a/shared/uavobjectdefinition/flightstatus.xml +++ b/shared/uavobjectdefinition/flightstatus.xml @@ -4,11 +4,11 @@ - + - + diff --git a/shared/uavobjectdefinition/gcsreceiver.xml b/shared/uavobjectdefinition/gcsreceiver.xml index d21598e48..cbc00c965 100644 --- a/shared/uavobjectdefinition/gcsreceiver.xml +++ b/shared/uavobjectdefinition/gcsreceiver.xml @@ -1,10 +1,10 @@ A receiver channel group carried over the telemetry link. - + - - + + diff --git a/shared/uavobjectdefinition/gcstelemetrystats.xml b/shared/uavobjectdefinition/gcstelemetrystats.xml index 3f9c74b1b..3971cffba 100644 --- a/shared/uavobjectdefinition/gcstelemetrystats.xml +++ b/shared/uavobjectdefinition/gcstelemetrystats.xml @@ -10,6 +10,6 @@ - + diff --git a/shared/uavobjectdefinition/guidancesettings.xml b/shared/uavobjectdefinition/guidancesettings.xml index 5d83f92e5..904501af2 100644 --- a/shared/uavobjectdefinition/guidancesettings.xml +++ b/shared/uavobjectdefinition/guidancesettings.xml @@ -2,10 +2,10 @@ Settings for the @ref GuidanceModule - - - - + + + + @@ -14,6 +14,6 @@ - + diff --git a/shared/uavobjectdefinition/gyros.xml b/shared/uavobjectdefinition/gyros.xml new file mode 100644 index 000000000..8240d2a68 --- /dev/null +++ b/shared/uavobjectdefinition/gyros.xml @@ -0,0 +1,13 @@ + + + The gyro data. + + + + + + + + + + diff --git a/shared/uavobjectdefinition/gyrosbias.xml b/shared/uavobjectdefinition/gyrosbias.xml new file mode 100644 index 000000000..b8543e641 --- /dev/null +++ b/shared/uavobjectdefinition/gyrosbias.xml @@ -0,0 +1,12 @@ + + + The gyro data. + + + + + + + + + diff --git a/shared/uavobjectdefinition/homelocation.xml b/shared/uavobjectdefinition/homelocation.xml index c1ed6a5b8..893af7e30 100644 --- a/shared/uavobjectdefinition/homelocation.xml +++ b/shared/uavobjectdefinition/homelocation.xml @@ -12,6 +12,6 @@ - + diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 1327c8d69..0cee2a6d9 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -5,14 +5,16 @@ - - - - + + + + + + + - @@ -22,6 +24,6 @@ - + diff --git a/shared/uavobjectdefinition/magnetometer.xml b/shared/uavobjectdefinition/magnetometer.xml new file mode 100644 index 000000000..006c40298 --- /dev/null +++ b/shared/uavobjectdefinition/magnetometer.xml @@ -0,0 +1,12 @@ + + + The mag data. + + + + + + + + + diff --git a/shared/uavobjectdefinition/manualcontrolcommand.xml b/shared/uavobjectdefinition/manualcontrolcommand.xml index d8dba78d6..00b5f0a12 100644 --- a/shared/uavobjectdefinition/manualcontrolcommand.xml +++ b/shared/uavobjectdefinition/manualcontrolcommand.xml @@ -11,6 +11,6 @@ - + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index 14a92a6cb..c2c8ec715 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -18,17 +18,17 @@ - - - + + + - + - + diff --git a/shared/uavobjectdefinition/mixersettings.xml b/shared/uavobjectdefinition/mixersettings.xml index e2df02ce0..6e0d519f1 100644 --- a/shared/uavobjectdefinition/mixersettings.xml +++ b/shared/uavobjectdefinition/mixersettings.xml @@ -31,6 +31,6 @@ - + diff --git a/shared/uavobjectdefinition/nedaccel.xml b/shared/uavobjectdefinition/nedaccel.xml index 83da85e7e..274fde9e2 100644 --- a/shared/uavobjectdefinition/nedaccel.xml +++ b/shared/uavobjectdefinition/nedaccel.xml @@ -1,12 +1,12 @@ The projection of acceleration in the NED reference frame used by @ref Guidance. - - - + + + - + diff --git a/shared/uavobjectdefinition/objectpersistence.xml b/shared/uavobjectdefinition/objectpersistence.xml index aa7a58e8c..2d73e07b3 100644 --- a/shared/uavobjectdefinition/objectpersistence.xml +++ b/shared/uavobjectdefinition/objectpersistence.xml @@ -1,13 +1,13 @@ Someone who knows please enter this - + - + diff --git a/shared/uavobjectdefinition/overosyncstats.xml b/shared/uavobjectdefinition/overosyncstats.xml new file mode 100644 index 000000000..a98ef3564 --- /dev/null +++ b/shared/uavobjectdefinition/overosyncstats.xml @@ -0,0 +1,13 @@ + + + Maintains statistics on transfer rate to and from over + + + + + + + + + + diff --git a/shared/uavobjectdefinition/pipxsettings.xml b/shared/uavobjectdefinition/pipxsettings.xml new file mode 100644 index 000000000..a8899ff47 --- /dev/null +++ b/shared/uavobjectdefinition/pipxsettings.xml @@ -0,0 +1,24 @@ + + + PipXtreme configurations options. + + + + + + + + + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/pipxstatus.xml b/shared/uavobjectdefinition/pipxstatus.xml new file mode 100755 index 000000000..c9dc2644b --- /dev/null +++ b/shared/uavobjectdefinition/pipxstatus.xml @@ -0,0 +1,31 @@ + + + PipXtreme device status. + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/positionactual.xml b/shared/uavobjectdefinition/positionactual.xml index 5fbf4d01c..cddd81742 100644 --- a/shared/uavobjectdefinition/positionactual.xml +++ b/shared/uavobjectdefinition/positionactual.xml @@ -1,9 +1,9 @@ Contains the current position relative to @ref HomeLocation - - - + + + diff --git a/shared/uavobjectdefinition/positiondesired.xml b/shared/uavobjectdefinition/positiondesired.xml index fab8cf21f..ffffe1370 100644 --- a/shared/uavobjectdefinition/positiondesired.xml +++ b/shared/uavobjectdefinition/positiondesired.xml @@ -1,9 +1,9 @@ The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner - - - + + + diff --git a/shared/uavobjectdefinition/receiveractivity.xml b/shared/uavobjectdefinition/receiveractivity.xml index c2a741d7f..8e30e0889 100644 --- a/shared/uavobjectdefinition/receiveractivity.xml +++ b/shared/uavobjectdefinition/receiveractivity.xml @@ -9,6 +9,6 @@ - + diff --git a/shared/uavobjectdefinition/revocalibration.xml b/shared/uavobjectdefinition/revocalibration.xml new file mode 100644 index 000000000..672e3fb16 --- /dev/null +++ b/shared/uavobjectdefinition/revocalibration.xml @@ -0,0 +1,23 @@ + + + Settings for the INS to control the algorithm and what is updated + + + + + + + + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/sonaraltitude.xml b/shared/uavobjectdefinition/sonaraltitude.xml index 9c52bda24..98b678413 100644 --- a/shared/uavobjectdefinition/sonaraltitude.xml +++ b/shared/uavobjectdefinition/sonaraltitude.xml @@ -5,6 +5,6 @@ - + diff --git a/shared/uavobjectdefinition/stabilizationdesired.xml b/shared/uavobjectdefinition/stabilizationdesired.xml index c1e013be3..02c63cd90 100644 --- a/shared/uavobjectdefinition/stabilizationdesired.xml +++ b/shared/uavobjectdefinition/stabilizationdesired.xml @@ -6,10 +6,10 @@ - + - + diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml index 29c9d8116..7cd7de210 100644 --- a/shared/uavobjectdefinition/stabilizationsettings.xml +++ b/shared/uavobjectdefinition/stabilizationsettings.xml @@ -13,6 +13,15 @@ + + + + + + + + + @@ -27,6 +36,6 @@ - + diff --git a/shared/uavobjectdefinition/systemalarms.xml b/shared/uavobjectdefinition/systemalarms.xml index 09b37bcd2..cc20045b6 100644 --- a/shared/uavobjectdefinition/systemalarms.xml +++ b/shared/uavobjectdefinition/systemalarms.xml @@ -2,7 +2,7 @@ Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + elementnames="OutOfMemory,StackOverflow,CPUOverload,EventSystem,SDCard,Telemetry,ManualControl,Actuator,Attitude,Sensors,Stabilization,Guidance,AHRSComms,Battery,FlightTime,I2C,GPS,BootFault" defaultvalue="Uninitialised"/> diff --git a/shared/uavobjectdefinition/systemsettings.xml b/shared/uavobjectdefinition/systemsettings.xml index ec092df8e..f903e9f80 100644 --- a/shared/uavobjectdefinition/systemsettings.xml +++ b/shared/uavobjectdefinition/systemsettings.xml @@ -2,10 +2,10 @@ Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand - + - + diff --git a/shared/uavobjectdefinition/systemstats.xml b/shared/uavobjectdefinition/systemstats.xml index 3e6bc1547..c11453d20 100644 --- a/shared/uavobjectdefinition/systemstats.xml +++ b/shared/uavobjectdefinition/systemstats.xml @@ -6,6 +6,9 @@ + + + diff --git a/shared/uavobjectdefinition/taskinfo.xml b/shared/uavobjectdefinition/taskinfo.xml index 11b550089..40f0d4bdf 100644 --- a/shared/uavobjectdefinition/taskinfo.xml +++ b/shared/uavobjectdefinition/taskinfo.xml @@ -1,9 +1,9 @@ Task information - - - + + + diff --git a/shared/uavobjectdefinition/txpidsettings.xml b/shared/uavobjectdefinition/txpidsettings.xml index 876ffccc7..5b69063e8 100644 --- a/shared/uavobjectdefinition/txpidsettings.xml +++ b/shared/uavobjectdefinition/txpidsettings.xml @@ -16,7 +16,8 @@ Roll Rate.ILimit, Pitch Rate.ILimit, Roll+Pitch Rate.ILimit, Yaw Rate.ILimit, Roll Attitude.Kp, Pitch Attitude.Kp, Roll+Pitch Attitude.Kp, Yaw Attitude.Kp, Roll Attitude.Ki, Pitch Attitude.Ki, Roll+Pitch Attitude.Ki, Yaw Attitude.Ki, - Roll Attitude.ILimit, Pitch Attitude.ILimit, Roll+Pitch Attitude.ILimit, Yaw Attitude.ILimit" + Roll Attitude.ILimit, Pitch Attitude.ILimit, Roll+Pitch Attitude.ILimit, Yaw Attitude.ILimit, + GyroTau" defaultvalue="Disabled"/> @@ -24,6 +25,6 @@ - + diff --git a/shared/uavobjectdefinition/velocityactual.xml b/shared/uavobjectdefinition/velocityactual.xml index 94ac75903..a4173b033 100644 --- a/shared/uavobjectdefinition/velocityactual.xml +++ b/shared/uavobjectdefinition/velocityactual.xml @@ -1,9 +1,9 @@ Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control - - - + + + diff --git a/shared/uavobjectdefinition/velocitydesired.xml b/shared/uavobjectdefinition/velocitydesired.xml index ae30659d8..02467a539 100644 --- a/shared/uavobjectdefinition/velocitydesired.xml +++ b/shared/uavobjectdefinition/velocitydesired.xml @@ -1,9 +1,9 @@ Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates). - - - + + +