1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-11-29 07:24:13 +01:00

Merge branch 'master' into bugfix-flight

Conflicts:
	flight/CopterControl/System/inc/pios_config.h
This commit is contained in:
James Cotton 2011-07-12 11:40:47 -05:00
commit 59798701a2
77 changed files with 7902 additions and 5109 deletions

View File

@ -27,6 +27,10 @@ N: Pedro Assuncao
E: pedro (dot) agda (plus) openpilot (at) gmail (dot) com
D: Initial GCS Settings Gadget work
N: Werner Backes
E: werner (at) bit-1 (dot) de
D: Port of CopterControl to PS3 Move Controller (MoveCopter)
N: Jose Barros
E: josembarros (at) hotmail (dot) com
D: Next-Gen OP Map Lib, Y-Modem Library, Uploader Plugin

View File

@ -117,11 +117,35 @@ C: Sami Korhonen (Sambas)
D: May 2011
V: http://vimeo.com/24258192
M: First CopterControl flip on a Flybarless Heli
M: First Y6 CopterControl flight
C: Michel Pet
D: June 2011
V: http://www.youtube.com/watch?v=QsE2MQELPZY
M: First MoveControl flight
C: Werner Backes
D: July 2011
V: http://vimeo.com/25983655
M: First Altitude Hold using Sonar
C:
D:
V:
M: First CopterControl Navigation on RC Ground Vechicle
C:
D:
V:
M: First CopterControl Navigation on RC Water Vechicle
C:
D:
V:
M: First CopterControl flip on a Flybarless Heli
C:
D:
V:
An incomplete list of some future Milestones is below:
@ -131,7 +155,6 @@ An incomplete list of some future Milestones is below:
* First successful flight using the GCS only and no RC TX
* First use of Magic Waypoint
* First Flybarless Helicopter flight with OpenPilot
* First flight with CopterControl
* First fixed wing navigation flight
* First Multirotor navigation flight
* First Helicopter navigation flight

View File

@ -71,6 +71,7 @@ help:
@echo " qt_sdk_install - Install the QT v4.6.2 tools"
@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
@echo " [Big Hammer]"
@echo " all - Generate UAVObjects, build openpilot firmware and gcs"
@ -92,21 +93,25 @@ help:
@echo " <board> - Build firmware for <board>"
@echo " supported boards are ($(ALL_BOARDS))"
@echo " fw_<board> - Build firmware for <board>"
@echo " supported boards are ($(FW_TARGETS))"
@echo " supported boards are ($(FW_BOARDS))"
@echo " fw_<board>_clean - Remove firmware for <board>"
@echo " fw_<board>_program - Use OpenOCD + JTAG to write firmware to <board>"
@echo
@echo " [Bootloader]"
@echo " bl_<board> - Build bootloader for <board>"
@echo " supported boards are ($(BL_TARGETS))"
@echo " supported boards are ($(BL_BOARDS))"
@echo " bl_<board>_clean - Remove bootloader for <board>"
@echo " bl_<board>_program - Use OpenOCD + JTAG to write bootloader to <board>"
@echo
@echo " [Bootloader Updater]"
@echo " bu_<board> - Build bootloader updater for <board>"
@echo " supported boards are ($(BU_TARGETS))"
@echo " supported boards are ($(BU_BOARDS))"
@echo " bu_<board>_clean - Remove bootloader updater for <board>"
@echo
@echo " [Unbrick a board]"
@echo " unbrick_<board> - Use the STM32's built in boot ROM to write a bootloader to <board>"
@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, ...)"
@ -226,6 +231,25 @@ openocd_install: openocd_clean
openocd_clean:
$(V1) [ ! -d "$(OPENOCD_DIR)" ] || $(RM) -r "$(OPENOCD_DIR)"
STM32FLASH_DIR := $(TOOLS_DIR)/stm32flash
.PHONY: stm32flash_install
stm32flash_install: STM32FLASH_URL := http://stm32flash.googlecode.com/svn/trunk
stm32flash_install: STM32FLASH_REV := 52
stm32flash_install: stm32flash_clean
# download the source
$(V0) @echo " DOWNLOAD $(STM32FLASH_URL) @ r$(STM32FLASH_REV)"
$(V1) svn export -q -r "$(STM32FLASH_REV)" "$(STM32FLASH_URL)" "$(STM32FLASH_DIR)"
# build
$(V0) @echo " BUILD $(STM32FLASH_DIR)"
$(V1) $(MAKE) --silent -C $(STM32FLASH_DIR) all
.PHONY: stm32flash_clean
stm32flash_clean:
$(V0) @echo " CLEAN $(STM32FLASH_DIR)"
$(V1) [ ! -d "$(STM32FLASH_DIR)" ] || $(RM) -r "$(STM32FLASH_DIR)"
##############################
#
# Set up paths to tools
@ -355,6 +379,20 @@ bl_$(1)_%:
REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \
$$*
.PHONY: unbrick_$(1)
unbrick_$(1): bl_$(1)_hex
$(if $(filter-out undefined,$(origin UNBRICK_TTY)),
$(V0) @echo " UNBRICK $(1) via $$(UNBRICK_TTY)"
$(V1) $(STM32FLASH_DIR)/stm32flash \
-w $(BUILD_DIR)/bl_$(1)/bl_$(1).hex \
-g 0x0 \
$$(UNBRICK_TTY)
,
$(V0) @echo
$(V0) @echo "ERROR: You must specify UNBRICK_TTY=<serial-device> to use for unbricking."
$(V0) @echo " eg. $$(MAKE) $$@ UNBRICK_TTY=/dev/ttyUSB0"
)
.PHONY: bl_$(1)_clean
bl_$(1)_clean:
$(V0) @echo " CLEAN $$@"
@ -403,14 +441,20 @@ pipxtreme_friendly := PipXtreme
ins_friendly := INS
ahrs_friendly := AHRS
FW_TARGETS := $(addprefix fw_, $(ALL_BOARDS))
BL_TARGETS := $(addprefix bl_, $(ALL_BOARDS))
BU_TARGETS := $(addprefix bu_, $(ALL_BOARDS))
# 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)
# FIXME: The INS build doesn't have a bootloader or bootloader
# updater yet so we need to filter them out to prevent errors.
BL_TARGETS := $(filter-out bl_ins, $(BL_TARGETS))
BU_TARGETS := $(filter-out bu_ins, $(BU_TARGETS))
BL_BOARDS := $(filter-out ins, $(ALL_BOARDS))
BU_BOARDS := $(filter-out ins, $(ALL_BOARDS))
# Generate the targets for whatever boards are left in each list
FW_TARGETS := $(addprefix fw_, $(FW_BOARDS))
BL_TARGETS := $(addprefix bl_, $(BL_BOARDS))
BU_TARGETS := $(addprefix bu_, $(BU_BOARDS))
.PHONY: all_fw all_fw_clean
all_fw: $(addsuffix _opfw, $(FW_TARGETS))
@ -428,6 +472,7 @@ all_bu_clean: $(addsuffix _clean, $(BU_TARGETS))
all_flight: all_fw all_bl all_bu
all_flight_clean: all_fw_clean all_bl_clean all_bu_clean
# Expand the groups of targets for each board
$(foreach board, $(ALL_BOARDS), $(eval $(call BOARD_PHONY_TEMPLATE,$(board))))
# Expand the bootloader updater rules

View File

@ -54,7 +54,7 @@ static const struct pios_spi_cfg pios_spi_op_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_SPI_op_irq_handler,
.handler = NULL,
.flags =
(DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 |
DMA1_FLAG_GL4),
@ -153,11 +153,11 @@ void PIOS_SPI_op_irq_handler(void)
extern void PIOS_ADC_handler(void);
void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler")));
// Remap the ADC DMA handler to this one
const struct pios_adc_cfg pios_adc_cfg = {
static const struct pios_adc_cfg pios_adc_cfg = {
.dma = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_ADC_DMA_Handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
.init = {
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
@ -205,17 +205,10 @@ void PIOS_ADC_handler() {
/*
* AUX USART
*/
void PIOS_USART_aux_irq_handler(void);
void USART3_IRQHandler()
__attribute__ ((alias("PIOS_USART_aux_irq_handler")));
const struct pios_usart_cfg pios_usart_aux_cfg = {
static const struct pios_usart_cfg pios_usart_aux_cfg = {
.regs = USART3,
.init = {
#if defined (PIOS_USART_BAUDRATE)
.USART_BaudRate = PIOS_USART_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_BaudRate = 230400,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
@ -224,7 +217,7 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_aux_irq_handler,
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -250,12 +243,6 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
},
};
static uint32_t pios_usart_aux_id;
void PIOS_USART_aux_irq_handler(void)
{
PIOS_USART_IRQ_Handler(pios_usart_aux_id);
}
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)
@ -279,7 +266,7 @@ void I2C1_EV_IRQHandler()
void I2C1_ER_IRQHandler()
__attribute__ ((alias("PIOS_I2C_main_adapter_er_irq_handler")));
const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
.regs = I2C1,
.init = {
.I2C_Mode = I2C_Mode_I2C,
@ -307,7 +294,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.event = {
.handler = PIOS_I2C_main_adapter_ev_irq_handler,
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_EV_IRQn,
@ -317,7 +304,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.error = {
.handler = PIOS_I2C_main_adapter_er_irq_handler,
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_ER_IRQn,
@ -388,6 +375,7 @@ void PIOS_Board_Init(void) {
/* 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);
}

View File

@ -55,7 +55,7 @@ static const struct pios_spi_cfg
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_SPI_op_irq_handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
.init = {
.NVIC_IRQChannel = DMA1_Channel4_IRQn,

View File

@ -60,7 +60,7 @@ const struct pios_spi_cfg
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_SPI_ahrs_irq_handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
.init = {
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
@ -143,9 +143,9 @@ void PIOS_SPI_ahrs_irq_handler(void) {
/*
* Telemetry USART
*/
void PIOS_USART_telem_irq_handler(void);
void USART2_IRQHandler() __attribute__ ((alias ("PIOS_USART_telem_irq_handler")));
const struct pios_usart_cfg pios_usart_telem_cfg = { .regs = USART2, .init = {
const struct pios_usart_cfg pios_usart_telem_cfg = {
.regs = USART2,
.init = {
#if defined (PIOS_COM_TELEM_BAUDRATE)
.USART_BaudRate = PIOS_COM_TELEM_BAUDRATE,
#else
@ -157,7 +157,7 @@ const struct pios_usart_cfg pios_usart_telem_cfg = { .regs = USART2, .init = {
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
}, .irq = {
.handler = PIOS_USART_telem_irq_handler,
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART2_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -180,11 +180,6 @@ const struct pios_usart_cfg pios_usart_telem_cfg = { .regs = USART2, .init = {
},
}, };
static uint32_t pios_usart_telem_rf_id;
void PIOS_USART_telem_irq_handler(void) {
PIOS_USART_IRQ_Handler(pios_usart_telem_rf_id);
}
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)
@ -218,6 +213,7 @@ void PIOS_Board_Init(void) {
/* 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);
}

View File

@ -45,7 +45,7 @@ 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_SPEKTRUM ?= NO
USE_GPS ?= NO
USE_I2C ?= NO
@ -166,6 +166,7 @@ SRC += $(OPUAVSYNTHDIR)/mixersettings.c
SRC += $(OPUAVSYNTHDIR)/mixerstatus.c
SRC += $(OPUAVSYNTHDIR)/firmwareiapobj.c
SRC += $(OPUAVSYNTHDIR)/attitudesettings.c
SRC += $(OPUAVSYNTHDIR)/hwsettings.c
#${wildcard ${OBJ}/$(shell echo $(VAR) | tr A-Z a-z)/*.c}
#SRC += ${foreach OBJ, ${UAVOBJECTS}, $(UAVOBJECTS)/$(OBJ).c}
# Cant use until i can automatically generate list of UAVObjects
@ -185,6 +186,7 @@ SRC += $(PIOSSTM32F10X)/pios_spi.c
SRC += $(PIOSSTM32F10X)/pios_ppm.c
SRC += $(PIOSSTM32F10X)/pios_pwm.c
SRC += $(PIOSSTM32F10X)/pios_spektrum.c
SRC += $(PIOSSTM32F10X)/pios_sbus.c
SRC += $(PIOSSTM32F10X)/pios_debug.c
SRC += $(PIOSSTM32F10X)/pios_gpio.c
SRC += $(PIOSSTM32F10X)/pios_exti.c
@ -207,6 +209,7 @@ SRC += $(PIOSCOMMON)/pios_com.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
## Libraries for flight calculations
SRC += $(FLIGHTLIB)/fifo_buffer.c
@ -379,15 +382,15 @@ endif
ifeq ($(ERASE_FLASH), YES)
CDEFS += -DERASE_FLASH
endif
ifeq ($(USE_SPEKTRUM), YES)
CDEFS += -DUSE_SPEKTRUM
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

View File

@ -29,7 +29,7 @@
#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 ) 128 )
#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 48 )
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 14 * 1024 ) )
#define configMAX_TASK_NAME_LEN ( 16 )
#define configUSE_TRACE_FACILITY 0

View File

@ -30,11 +30,9 @@
* 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
@ -45,14 +43,17 @@
#define PIOS_INCLUDE_IRQ
#define PIOS_INCLUDE_LED
#if defined(USE_SPEKTRUM)
#define PIOS_INCLUDE_RCVR
/* Supported receiver interfaces */
#define PIOS_INCLUDE_SPEKTRUM
#else
#define PIOS_INCLUDE_GPS
#define PIOS_INCLUDE_SBUS
//#define PIOS_INCLUDE_PPM
#define PIOS_INCLUDE_PWM
#endif
/* Supported USART-based PIOS modules */
#define PIOS_INCLUDE_TELEMETRY_RF
//#define PIOS_INCLUDE_GPS
#define PIOS_INCLUDE_SERVO
#define PIOS_INCLUDE_SPI
@ -85,9 +86,9 @@
#define AUXUART_BAUDRATE 19200
/* Alarm Thresholds */
#define HEAP_LIMIT_WARNING 156
#define HEAP_LIMIT_CRITICAL 130
#define CPULOAD_LIMIT_WARNING 80
#define HEAP_LIMIT_WARNING 220
#define HEAP_LIMIT_CRITICAL 40
#define CPULOAD_LIMIT_WARNING 85
#define CPULOAD_LIMIT_CRITICAL 95
/* Task stack sizes */

View File

@ -30,10 +30,11 @@
#include <pios.h>
#include <openpilot.h>
#include <uavobjectsinit.h>
#include <hwsettings.h>
#include <manualcontrolsettings.h>
#if defined(PIOS_INCLUDE_SPI)
#include <pios_spi_priv.h>
/* Flash/Accel Interface
@ -44,7 +45,7 @@
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")));
const struct pios_spi_cfg pios_spi_flash_accel_cfg = {
static const struct pios_spi_cfg pios_spi_flash_accel_cfg = {
.regs = SPI2,
.init = {
.SPI_Mode = SPI_Mode_Master,
@ -62,7 +63,7 @@ const struct pios_spi_cfg pios_spi_flash_accel_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_SPI_flash_accel_irq_handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
.init = {
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
@ -151,11 +152,11 @@ void PIOS_SPI_flash_accel_irq_handler(void)
extern void PIOS_ADC_handler(void);
void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler")));
// Remap the ADC DMA handler to this one
const struct pios_adc_cfg pios_adc_cfg = {
static const struct pios_adc_cfg pios_adc_cfg = {
.dma = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_ADC_DMA_Handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
.init = {
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
@ -200,19 +201,14 @@ void PIOS_ADC_handler() {
#include "pios_usart_priv.h"
#if defined(PIOS_INCLUDE_TELEMETRY_RF)
/*
* Telemetry USART
*/
void PIOS_USART_telem_irq_handler(void);
void USART1_IRQHandler() __attribute__ ((alias ("PIOS_USART_telem_irq_handler")));
const struct pios_usart_cfg pios_usart_telem_cfg = {
static const struct pios_usart_cfg pios_usart_telem_main_cfg = {
.regs = USART1,
.init = {
#if defined (PIOS_COM_TELEM_BAUDRATE)
.USART_BaudRate = PIOS_COM_TELEM_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
@ -220,7 +216,7 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_telem_irq_handler,
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -246,20 +242,10 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
},
};
#if defined(PIOS_INCLUDE_GPS)
/*
* GPS USART
*/
void PIOS_USART_gps_irq_handler(void);
void USART3_IRQHandler() __attribute__ ((alias ("PIOS_USART_gps_irq_handler")));
const struct pios_usart_cfg pios_usart_gps_cfg = {
static const struct pios_usart_cfg pios_usart_telem_flexi_cfg = {
.regs = USART3,
.init = {
#if defined (PIOS_COM_GPS_BAUDRATE)
.USART_BaudRate = PIOS_COM_GPS_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
@ -267,7 +253,7 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_gps_irq_handler,
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -292,33 +278,64 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
},
},
};
#endif
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
#if defined(PIOS_INCLUDE_SPEKTRUM)
#if defined(PIOS_INCLUDE_GPS)
/*
* SPEKTRUM USART
* GPS USART
*/
void PIOS_USART_spektrum_irq_handler(void);
void USART3_IRQHandler() __attribute__ ((alias ("PIOS_USART_spektrum_irq_handler")));
const struct pios_usart_cfg pios_usart_spektrum_cfg = {
.regs = USART3,
static const struct pios_usart_cfg pios_usart_gps_main_cfg = {
.regs = USART1,
.init = {
#if defined (PIOS_COM_SPEKTRUM_BAUDRATE)
.USART_BaudRate = PIOS_COM_SPEKTRUM_BAUDRATE,
#else
.USART_BaudRate = 115200,
#endif
.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 = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_spektrum_irq_handler,
.handler = NULL,
.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_gps_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 = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
@ -336,66 +353,177 @@ const struct pios_usart_cfg pios_usart_spektrum_cfg = {
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
};
#endif /* PIOS_INCLUDE_GPS */
#if defined(PIOS_INCLUDE_SPEKTRUM)
/*
* SPEKTRUM USART
*/
#include <pios_spektrum_priv.h>
static const struct pios_usart_cfg pios_usart_spektrum_main_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 = {
.handler = PIOS_SPEKTRUM_irq_handler,
.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 uint32_t pios_usart_spektrum_id;
void PIOS_USART_spektrum_irq_handler(void)
{
SPEKTRUM_IRQHandler(pios_usart_spektrum_id);
}
#include <pios_spektrum_priv.h>
void RTC_IRQHandler();
void RTC_IRQHandler() __attribute__ ((alias ("PIOS_SUPV_irq_handler")));
const struct pios_spektrum_cfg pios_spektrum_cfg = {
.pios_usart_spektrum_cfg = &pios_usart_spektrum_cfg,
.gpio_init = { //used for bind feature
.GPIO_Mode = GPIO_Mode_Out_PP,
static const struct pios_spektrum_cfg pios_spektrum_main_cfg = {
.bind = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_Out_PP,
},
},
.remap = 0,
.irq = {
.handler = RTC_IRQHandler,
};
static const struct pios_usart_cfg pios_usart_spektrum_flexi_cfg = {
.regs = USART3,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.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 = {
.handler = PIOS_SPEKTRUM_irq_handler,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.port = GPIOB,
.pin = GPIO_Pin_11,
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
void PIOS_SUPV_irq_handler() {
if (RTC_GetITStatus(RTC_IT_SEC))
{
/* Call the right handler */
PIOS_SPEKTRUM_irq_handler(pios_usart_spektrum_id);
static const struct pios_spektrum_cfg pios_spektrum_flexi_cfg = {
.bind = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_Out_PP,
},
},
.remap = 0,
};
/* Wait until last write operation on RTC registers has finished */
RTC_WaitForLastTask();
/* Clear the RTC Second interrupt */
RTC_ClearITPendingBit(RTC_IT_SEC);
}
}
#endif /* PIOS_INCLUDE_SPEKTRUM */
static uint32_t pios_usart_telem_rf_id;
void PIOS_USART_telem_irq_handler(void)
{
PIOS_USART_IRQ_Handler(pios_usart_telem_rf_id);
}
#if defined(PIOS_INCLUDE_SBUS)
/*
* SBUS USART
*/
#include <pios_sbus_priv.h>
#if defined(PIOS_INCLUDE_GPS)
static uint32_t pios_usart_gps_id;
void PIOS_USART_gps_irq_handler(void)
{
PIOS_USART_IRQ_Handler(pios_usart_gps_id);
}
#endif /* PIOS_INCLUDE_GPS */
static const struct pios_usart_cfg pios_usart_sbus_main_cfg = {
.regs = USART1,
.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 = {
.handler = PIOS_SBUS_irq_handler,
.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_sbus_cfg pios_sbus_cfg = {
/* Inverter configuration */
.inv = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_2,
.GPIO_Mode = GPIO_Mode_Out_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.gpio_clk_func = RCC_APB2PeriphClockCmd,
.gpio_clk_periph = RCC_APB2Periph_GPIOB,
.gpio_inv_enable = Bit_SET,
};
#endif /* PIOS_INCLUDE_SBUS */
#endif /* PIOS_INCLUDE_USART */
@ -405,11 +533,40 @@ void PIOS_USART_gps_irq_handler(void)
#endif /* PIOS_INCLUDE_COM */
#if defined(PIOS_INCLUDE_RTC)
/*
* Realtime Clock (RTC)
*/
#include <pios_rtc_priv.h>
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 = {
.handler = NULL,
.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
/*
* Servo outputs
*/
#include <pios_servo_priv.h>
const struct pios_servo_channel pios_servo_channels[] = {
static const struct pios_servo_channel pios_servo_channels[] = {
{
.timer = TIM4,
.port = GPIOB,
@ -475,13 +632,65 @@ const struct pios_servo_cfg pios_servo_cfg = {
.num_channels = NELEMENTS(pios_servo_channels),
};
#if defined(PIOS_INCLUDE_PWM) && defined(PIOS_INCLUDE_PPM)
#error Cannot define both PIOS_INCLUDE_PWM and PIOS_INCLUDE_PPM at the same time (yet)
#endif
/*
* PPM Inputs
*/
#if defined(PIOS_INCLUDE_PPM)
#include <pios_ppm_priv.h>
void TIM4_IRQHandler();
void TIM4_IRQHandler() __attribute__ ((alias ("PIOS_TIM4_irq_handler")));
const struct pios_ppm_cfg pios_ppm_cfg = {
.tim_base_init = {
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */
.TIM_ClockDivision = TIM_CKD_DIV1,
.TIM_CounterMode = TIM_CounterMode_Up,
.TIM_Period = 0xFFFF, /* shared timer, make sure init correctly in outputs */
.TIM_RepetitionCounter = 0x0000,
},
.tim_ic_init = {
.TIM_Channel = TIM_Channel_1,
.TIM_ICPolarity = TIM_ICPolarity_Rising,
.TIM_ICSelection = TIM_ICSelection_DirectTI,
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
.TIM_ICFilter = 0x0,
},
.gpio_init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Mode = GPIO_Mode_IPD,
.GPIO_Speed = GPIO_Speed_2MHz,
},
.remap = 0,
.irq = {
.handler = TIM4_IRQHandler,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.timer = TIM4,
.port = GPIOB,
.ccr = TIM_IT_CC1,
};
void PIOS_TIM4_irq_handler()
{
PIOS_PPM_irq_handler();
}
#endif /* PIOS_INCLUDE_PPM */
/*
* PWM Inputs
*/
#if defined(PIOS_INCLUDE_PWM)
#include <pios_pwm_priv.h>
const struct pios_pwm_channel pios_pwm_channels[] = {
static const struct pios_pwm_channel pios_pwm_channels[] = {
{
.timer = TIM4,
.port = GPIOB,
@ -552,7 +761,7 @@ const struct pios_pwm_cfg pios_pwm_cfg = {
},
.remap = 0,
.irq = {
.handler = TIM2_IRQHandler,
.handler = NULL,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
@ -589,7 +798,7 @@ 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")));
const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
.regs = I2C2,
.init = {
.I2C_Mode = I2C_Mode_I2C,
@ -617,7 +826,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.event = {
.handler = PIOS_I2C_main_adapter_ev_irq_handler,
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_EV_IRQn,
@ -627,7 +836,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.error = {
.handler = PIOS_I2C_main_adapter_er_irq_handler,
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_ER_IRQn,
@ -653,12 +862,18 @@ void PIOS_I2C_main_adapter_er_irq_handler(void)
#endif /* PIOS_INCLUDE_I2C */
#if defined(PIOS_INCLUDE_RCVR)
#include "pios_rcvr_priv.h"
uint32_t pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_DEVS];
uint32_t pios_rcvr_max_channel;
#endif /* PIOS_INCLUDE_RCVR */
extern const struct pios_com_driver pios_usb_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_spektrum_id;
/**
* PIOS_Board_Init()
@ -672,7 +887,7 @@ void PIOS_Board_Init(void) {
/* Set up the SPI interface to the serial flash */
if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg)) {
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
PIOS_Flash_W25X_Init(pios_spi_flash_accel_id);
@ -680,45 +895,208 @@ void PIOS_Board_Init(void) {
PIOS_FLASHFS_Init();
#if defined(PIOS_INCLUDE_SPEKTRUM)
/* SPEKTRUM init must come before comms */
PIOS_SPEKTRUM_Init();
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_spektrum_id, &pios_usart_com_driver, pios_usart_spektrum_id)) {
PIOS_DEBUG_Assert(0);
}
#endif
/* Initialize UAVObject libraries */
EventDispatcherInitialize();
UAVObjInitialize();
UAVObjectsInitializeAll();
#if defined(PIOS_INCLUDE_RTC)
/* Initialize the real-time clock and its associated tick */
PIOS_RTC_Init(&pios_rtc_main_cfg);
#endif
/* Initialize the alarms library */
AlarmsInitialize();
/* Initialize the task monitor library */
TaskMonitorInitialize();
/* Initialize the PiOS library */
#if defined(PIOS_INCLUDE_COM)
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) {
PIOS_DEBUG_Assert(0);
/* Configure the main IO port */
uint8_t hwsettings_cc_mainport;
HwSettingsCC_MainPortGet(&hwsettings_cc_mainport);
switch (hwsettings_cc_mainport) {
case HWSETTINGS_CC_MAINPORT_DISABLED:
break;
case HWSETTINGS_CC_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_main_cfg)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
break;
case HWSETTINGS_CC_MAINPORT_SBUS:
#if defined(PIOS_INCLUDE_SBUS)
{
PIOS_SBUS_Init(&pios_sbus_cfg);
uint32_t pios_usart_sbus_id;
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_main_cfg)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_SBUS */
break;
case HWSETTINGS_CC_MAINPORT_GPS:
#if defined(PIOS_INCLUDE_GPS)
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
PIOS_DEBUG_Assert(0);
{
uint32_t pios_usart_gps_id;
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_main_cfg)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_GPS */
#endif /* PIOS_INCLUDE_COM */
break;
case HWSETTINGS_CC_MAINPORT_SPEKTRUM:
#if defined(PIOS_INCLUDE_SPEKTRUM)
{
/* SPEKTRUM init must come before usart init since it may use Rx pin for bind */
PIOS_SPEKTRUM_Init(&pios_spektrum_main_cfg, false);
uint32_t pios_usart_spektrum_id;
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_main_cfg)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_SPEKTRUM */
break;
case HWSETTINGS_CC_MAINPORT_COMAUX:
break;
}
/* Configure the flexi port */
uint8_t hwsettings_cc_flexiport;
HwSettingsCC_FlexiPortGet(&hwsettings_cc_flexiport);
switch (hwsettings_cc_flexiport) {
case HWSETTINGS_CC_FLEXIPORT_DISABLED:
break;
case HWSETTINGS_CC_FLEXIPORT_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_flexi_cfg)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
break;
case HWSETTINGS_CC_FLEXIPORT_GPS:
#if defined(PIOS_INCLUDE_GPS)
{
uint32_t pios_usart_gps_id;
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_flexi_cfg)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_GPS */
break;
case HWSETTINGS_CC_FLEXIPORT_SPEKTRUM:
#if defined(PIOS_INCLUDE_SPEKTRUM)
{
/* SPEKTRUM init must come before usart init since it may use Rx pin for bind */
PIOS_SPEKTRUM_Init(&pios_spektrum_flexi_cfg, false);
uint32_t pios_usart_spektrum_id;
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_flexi_cfg)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_SPEKTRUM */
break;
case HWSETTINGS_CC_FLEXIPORT_COMAUX:
break;
case HWSETTINGS_CC_FLEXIPORT_I2C:
#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 */
break;
}
/* Configure the selected receiver */
uint8_t manualcontrolsettings_inputmode;
ManualControlSettingsInputModeGet(&manualcontrolsettings_inputmode);
switch (manualcontrolsettings_inputmode) {
case MANUALCONTROLSETTINGS_INPUTMODE_PWM:
#if defined(PIOS_INCLUDE_PWM)
PIOS_PWM_Init();
for (uint8_t i = 0; i < PIOS_PWM_NUM_INPUTS && i < PIOS_RCVR_MAX_DEVS; i++) {
if (!PIOS_RCVR_Init(&pios_rcvr_channel_to_id_map[pios_rcvr_max_channel],
&pios_pwm_rcvr_driver,
i)) {
pios_rcvr_max_channel++;
} else {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_PWM */
break;
case MANUALCONTROLSETTINGS_INPUTMODE_PPM:
#if defined(PIOS_INCLUDE_PPM)
PIOS_PPM_Init();
for (uint8_t i = 0; i < PIOS_PPM_NUM_INPUTS && i < PIOS_RCVR_MAX_DEVS; i++) {
if (!PIOS_RCVR_Init(&pios_rcvr_channel_to_id_map[pios_rcvr_max_channel],
&pios_ppm_rcvr_driver,
i)) {
pios_rcvr_max_channel++;
} else {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_PPM */
break;
case MANUALCONTROLSETTINGS_INPUTMODE_SPEKTRUM:
#if defined(PIOS_INCLUDE_SPEKTRUM)
if (hwsettings_cc_mainport == HWSETTINGS_CC_MAINPORT_SPEKTRUM ||
hwsettings_cc_flexiport == HWSETTINGS_CC_FLEXIPORT_SPEKTRUM) {
for (uint8_t i = 0; i < PIOS_SPEKTRUM_NUM_INPUTS && i < PIOS_RCVR_MAX_DEVS; i++) {
if (!PIOS_RCVR_Init(&pios_rcvr_channel_to_id_map[pios_rcvr_max_channel],
&pios_spektrum_rcvr_driver,
i)) {
pios_rcvr_max_channel++;
} else {
PIOS_Assert(0);
}
}
}
#endif /* PIOS_INCLUDE_SPEKTRUM */
break;
case MANUALCONTROLSETTINGS_INPUTMODE_SBUS:
#if defined(PIOS_INCLUDE_SBUS)
if (hwsettings_cc_mainport == HWSETTINGS_CC_MAINPORT_SBUS) {
for (uint8_t i = 0; i < SBUS_NUMBER_OF_CHANNELS && i < PIOS_RCVR_MAX_DEVS; i++) {
if (!PIOS_RCVR_Init(&pios_rcvr_channel_to_id_map[pios_rcvr_max_channel],
&pios_sbus_rcvr_driver,
i)) {
pios_rcvr_max_channel++;
} else {
PIOS_Assert(0);
}
}
}
#endif /* PIOS_INCLUDE_SBUS */
break;
}
/* Remap AFIO pin */
GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
@ -727,26 +1105,15 @@ void PIOS_Board_Init(void) {
PIOS_ADC_Init();
PIOS_GPIO_Init();
#if defined(PIOS_INCLUDE_PWM)
PIOS_PWM_Init();
#endif
#if defined(PIOS_INCLUDE_PPM)
PIOS_PPM_Init();
#endif
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif
#endif /* PIOS_INCLUDE_USB_HID */
#if defined(PIOS_INCLUDE_I2C)
if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) {
PIOS_DEBUG_Assert(0);
}
#endif /* PIOS_INCLUDE_I2C */
PIOS_IAP_Init();
PIOS_WDG_Init();
}

View File

@ -61,7 +61,7 @@ static const struct pios_spi_cfg pios_spi_op_mag_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_SPI_op_mag_irq_handler,
.handler = NULL,
.flags =
(DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 |
DMA1_FLAG_GL4),
@ -175,7 +175,7 @@ static const struct pios_spi_cfg pios_spi_accel_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_SPI_accel_irq_handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
.init = {
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
@ -265,17 +265,10 @@ void PIOS_SPI_accel_irq_handler(void)
/*
* GPS USART
*/
void PIOS_USART_gps_irq_handler(void);
void USART1_IRQHandler()
__attribute__ ((alias("PIOS_USART_gps_irq_handler")));
const struct pios_usart_cfg pios_usart_gps_cfg = {
static const struct pios_usart_cfg pios_usart_gps_cfg = {
.regs = USART1,
.init = {
#if defined (PIOS_USART_BAUDRATE)
.USART_BaudRate = PIOS_USART_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
@ -284,7 +277,7 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_gps_irq_handler,
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -310,29 +303,16 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
},
};
static uint32_t pios_usart_gps_id;
void PIOS_USART_gps_irq_handler(void)
{
PIOS_USART_IRQ_Handler(pios_usart_gps_id);
}
#endif /* PIOS_INCLUDE_GPS */
#ifdef PIOS_COM_AUX
/*
* AUX USART
*/
void PIOS_USART_aux_irq_handler(void);
void USART4_IRQHandler()
__attribute__ ((alias("PIOS_USART_aux_irq_handler")));
const struct pios_usart_cfg pios_usart_aux_cfg = {
static const struct pios_usart_cfg pios_usart_aux_cfg = {
.regs = USART4,
.init = {
#if defined (PIOS_USART_BAUDRATE)
.USART_BaudRate = PIOS_USART_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
@ -341,7 +321,7 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_aux_irq_handler,
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -367,12 +347,6 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
},
};
static uint32_t pios_usart_aux_id;
void PIOS_USART_aux_irq_handler(void)
{
PIOS_USART_IRQ_Handler(pios_usart_aux_id);
}
#endif /* PIOS_COM_AUX */
@ -391,7 +365,7 @@ void I2C1_EV_IRQHandler()
void I2C1_ER_IRQHandler()
__attribute__ ((alias("PIOS_I2C_pres_mag_adapter_er_irq_handler")));
const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
static const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
.regs = I2C1,
.init = {
.I2C_Mode = I2C_Mode_I2C,
@ -419,7 +393,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
},
},
.event = {
.handler = PIOS_I2C_pres_mag_adapter_ev_irq_handler,
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_EV_IRQn,
@ -429,7 +403,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
},
},
.error = {
.handler = PIOS_I2C_pres_mag_adapter_er_irq_handler,
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_ER_IRQn,
@ -459,7 +433,7 @@ void PIOS_I2C_gyro_adapter_er_irq_handler(void);
void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_gyro_adapter_ev_irq_handler")));
void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_gyro_adapter_er_irq_handler")));
const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
static const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
.regs = I2C2,
.init = {
.I2C_Mode = I2C_Mode_I2C,
@ -487,7 +461,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
},
},
.event = {
.handler = PIOS_I2C_gyro_adapter_ev_irq_handler,
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_EV_IRQn,
@ -497,7 +471,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
},
},
.error = {
.handler = PIOS_I2C_gyro_adapter_er_irq_handler,
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_ER_IRQn,
@ -547,6 +521,7 @@ void PIOS_Board_Init(void) {
#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);
}

View File

@ -209,17 +209,12 @@ static void manualControlTask(void *parameters)
if (!ManualControlCommandReadOnly(&cmd)) {
// Read channel values in us
// TODO: settings.InputMode is currently ignored because PIOS will not allow runtime
// selection of PWM and PPM. The configuration is currently done at compile time in
// the pios_config.h file.
for (int n = 0; n < MANUALCONTROLCOMMAND_CHANNEL_NUMELEM; ++n) {
#if defined(PIOS_INCLUDE_PWM)
cmd.Channel[n] = PIOS_PWM_Get(n);
#elif defined(PIOS_INCLUDE_PPM)
cmd.Channel[n] = PIOS_PPM_Get(n);
#elif defined(PIOS_INCLUDE_SPEKTRUM)
cmd.Channel[n] = PIOS_SPEKTRUM_Get(n);
#endif
if (pios_rcvr_channel_to_id_map[n]) {
cmd.Channel[n] = PIOS_RCVR_Read(pios_rcvr_channel_to_id_map[n]);
} else {
cmd.Channel[n] = -1;
}
scaledChannel[n] = scaleChannel(cmd.Channel[n], settings.ChannelMax[n], settings.ChannelMin[n], settings.ChannelNeutral[n]);
}

View File

@ -43,9 +43,6 @@ 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_SPEKTRUM ?= NO
# Set to YES when using Code Sourcery toolchain
CODE_SOURCERY ?= YES
@ -170,6 +167,7 @@ SRC += $(PIOSSTM32F10X)/pios_spi.c
SRC += $(PIOSSTM32F10X)/pios_ppm.c
SRC += $(PIOSSTM32F10X)/pios_pwm.c
SRC += $(PIOSSTM32F10X)/pios_spektrum.c
SRC += $(PIOSSTM32F10X)/pios_sbus.c
SRC += $(PIOSSTM32F10X)/pios_debug.c
SRC += $(PIOSSTM32F10X)/pios_gpio.c
SRC += $(PIOSSTM32F10X)/pios_exti.c
@ -194,6 +192,7 @@ 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
@ -363,11 +362,6 @@ ifeq ($(ENABLE_AUX_UART), YES)
CDEFS += -DPIOS_ENABLE_AUX_UART
endif
ifeq ($(USE_SPEKTRUM), YES)
CDEFS += -DUSE_SPEKTRUM
endif
# Place project-specific -D and/or -U options for
# Assembler with preprocessor here.
#ADEFS = -DUSE_IRQ_ASM_WRAPPER

View File

@ -42,12 +42,12 @@
#define PIOS_INCLUDE_IRQ
#define PIOS_INCLUDE_LED
#if defined(USE_SPEKTRUM)
#define PIOS_INCLUDE_RCVR
#define PIOS_INCLUDE_SPEKTRUM
#else
//#define PIOS_INCLUDE_PPM
//#define PIOS_INCLUDE_SBUS
#define PIOS_INCLUDE_PWM
#endif
//#define PIOS_INCLUDE_PPM
#define PIOS_INCLUDE_SERVO
#define PIOS_INCLUDE_SPI

View File

@ -153,6 +153,9 @@ static void TaskTesting(void *pvParameters)
#if defined(PIOS_INCLUDE_SPEKTRUM)
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_SPEKTRUM_Get(0), PIOS_SPEKTRUM_Get(1), PIOS_SPEKTRUM_Get(2), PIOS_SPEKTRUM_Get(3), PIOS_SPEKTRUM_Get(4), PIOS_SPEKTRUM_Get(5), PIOS_SPEKTRUM_Get(6), PIOS_SPEKTRUM_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

View File

@ -46,7 +46,7 @@
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")));
const struct pios_spi_cfg pios_spi_sdcard_cfg = {
static const struct pios_spi_cfg pios_spi_sdcard_cfg = {
.regs = SPI1,
.init = {
.SPI_Mode = SPI_Mode_Master,
@ -63,7 +63,7 @@ const struct pios_spi_cfg pios_spi_sdcard_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_SPI_sdcard_irq_handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
.init = {
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
@ -144,7 +144,7 @@ const struct pios_spi_cfg pios_spi_sdcard_cfg = {
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")));
const struct pios_spi_cfg pios_spi_ahrs_cfg = {
static const struct pios_spi_cfg pios_spi_ahrs_cfg = {
.regs = SPI2,
.init = {
.SPI_Mode = SPI_Mode_Master,
@ -162,7 +162,7 @@ const struct pios_spi_cfg pios_spi_ahrs_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_SPI_ahrs_irq_handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
.init = {
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
@ -258,11 +258,11 @@ void PIOS_SPI_ahrs_irq_handler(void)
extern void PIOS_ADC_handler(void);
void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler")));
// Remap the ADC DMA handler to this one
const struct pios_adc_cfg pios_adc_cfg = {
static const struct pios_adc_cfg pios_adc_cfg = {
.dma = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_ADC_DMA_Handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
.init = {
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
@ -310,16 +310,10 @@ void PIOS_ADC_handler() {
/*
* Telemetry USART
*/
void PIOS_USART_telem_irq_handler(void);
void USART2_IRQHandler() __attribute__ ((alias ("PIOS_USART_telem_irq_handler")));
const struct pios_usart_cfg pios_usart_telem_cfg = {
static const struct pios_usart_cfg pios_usart_telem_cfg = {
.regs = USART2,
.init = {
#if defined (PIOS_COM_TELEM_BAUDRATE)
.USART_BaudRate = PIOS_COM_TELEM_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
@ -327,7 +321,7 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_telem_irq_handler,
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART2_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -356,17 +350,11 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
/*
* GPS USART
*/
void PIOS_USART_gps_irq_handler(void);
void USART3_IRQHandler() __attribute__ ((alias ("PIOS_USART_gps_irq_handler")));
const struct pios_usart_cfg pios_usart_gps_cfg = {
static const struct pios_usart_cfg pios_usart_gps_cfg = {
.regs = USART3,
.remap = GPIO_PartialRemap_USART3,
.init = {
#if defined (PIOS_COM_GPS_BAUDRATE)
.USART_BaudRate = PIOS_COM_GPS_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
@ -374,7 +362,7 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_gps_irq_handler,
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -404,16 +392,9 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
/*
* AUX USART
*/
void PIOS_USART_aux_irq_handler(void);
void USART1_IRQHandler() __attribute__ ((alias ("PIOS_USART_aux_irq_handler")));
const struct pios_usart_cfg pios_usart_aux_cfg = {
static const struct pios_usart_cfg pios_usart_aux_cfg = {
.regs = USART1,
.init = {
#if defined (PIOS_COM_AUX_BAUDRATE)
.USART_BaudRate = PIOS_COM_AUX_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_BaudRate = 57600,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
@ -422,7 +403,7 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_aux_irq_handler,
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -450,20 +431,45 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
};
#endif
#if defined(PIOS_INCLUDE_RTC)
/*
* Realtime Clock (RTC)
*/
#include <pios_rtc_priv.h>
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 = {
.handler = NULL,
.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
#ifdef PIOS_COM_SPEKTRUM
/*
* SPEKTRUM USART
*/
void PIOS_USART_spektrum_irq_handler(void);
void USART1_IRQHandler() __attribute__ ((alias ("PIOS_USART_spektrum_irq_handler")));
const struct pios_usart_cfg pios_usart_spektrum_cfg = {
#include <pios_spektrum_priv.h>
static const struct pios_usart_cfg pios_usart_spektrum_cfg = {
.regs = USART1,
.init = {
#if defined (PIOS_COM_SPEKTRUM_BAUDRATE)
.USART_BaudRate = PIOS_COM_SPEKTRUM_BAUDRATE,
#else
.USART_BaudRate = 115200,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
@ -471,7 +477,7 @@ const struct pios_usart_cfg pios_usart_spektrum_cfg = {
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.handler = PIOS_USART_spektrum_irq_handler,
.handler = PIOS_SPEKTRUM_irq_handler,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -497,74 +503,30 @@ const struct pios_usart_cfg pios_usart_spektrum_cfg = {
},
};
#include <pios_spektrum_priv.h>
static uint32_t pios_usart_spektrum_id;
void PIOS_USART_spektrum_irq_handler(void)
{
SPEKTRUM_IRQHandler(pios_usart_spektrum_id);
PIOS_SPEKTRUM_irq_handler(pios_usart_spektrum_id);
}
#include <pios_spektrum_priv.h>
void RTC_IRQHandler();
void RTC_IRQHandler() __attribute__ ((alias ("PIOS_SUPV_irq_handler")));
const struct pios_spektrum_cfg pios_spektrum_cfg = {
.pios_usart_spektrum_cfg = &pios_usart_spektrum_cfg,
.gpio_init = { //used for bind feature
.GPIO_Mode = GPIO_Mode_Out_PP,
static const struct pios_spektrum_cfg pios_spektrum_cfg = {
.bind = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_Out_PP,
},
},
.remap = 0,
.irq = {
.handler = RTC_IRQHandler,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.port = GPIOA,
.pin = GPIO_Pin_10,
};
void PIOS_SUPV_irq_handler() {
if (RTC_GetITStatus(RTC_IT_SEC))
{
/* Call the right handler */
PIOS_SPEKTRUM_irq_handler(pios_usart_spektrum_id);
/* Wait until last write operation on RTC registers has finished */
RTC_WaitForLastTask();
/* Clear the RTC Second interrupt */
RTC_ClearITPendingBit(RTC_IT_SEC);
}
}
#endif /* PIOS_COM_SPEKTRUM */
static uint32_t pios_usart_telem_rf_id;
void PIOS_USART_telem_irq_handler(void)
{
PIOS_USART_IRQ_Handler(pios_usart_telem_rf_id);
}
static uint32_t pios_usart_gps_id;
void PIOS_USART_gps_irq_handler(void)
{
#ifdef USART_GPS_DEBUG_PIN
PIOS_DEBUG_PinHigh(USART_GPS_DEBUG_PIN);
#endif
PIOS_USART_IRQ_Handler(pios_usart_gps_id);
#ifdef USART_GPS_DEBUG_PIN
PIOS_DEBUG_PinLow(USART_GPS_DEBUG_PIN);
#endif
}
#ifdef PIOS_COM_AUX
static uint32_t pios_usart_aux_id;
void PIOS_USART_aux_irq_handler(void)
{
PIOS_USART_IRQ_Handler(pios_usart_aux_id);
}
#endif
#if defined(PIOS_INCLUDE_SBUS)
#error PIOS_INCLUDE_SBUS not implemented
#endif /* PIOS_INCLUDE_SBUS */
#endif /* PIOS_INCLUDE_USART */
@ -578,7 +540,7 @@ void PIOS_USART_aux_irq_handler(void)
* Pios servo configuration structures
*/
#include <pios_servo_priv.h>
const struct pios_servo_channel pios_servo_channels[] = {
static const struct pios_servo_channel pios_servo_channels[] = {
{
.timer = TIM4,
.port = GPIOB,
@ -662,7 +624,7 @@ const struct pios_servo_cfg pios_servo_cfg = {
*/
#if defined(PIOS_INCLUDE_PWM)
#include <pios_pwm_priv.h>
const struct pios_pwm_channel pios_pwm_channels[] = {
static const struct pios_pwm_channel pios_pwm_channels[] = {
{
.timer = TIM1,
.port = GPIOA,
@ -747,7 +709,7 @@ const struct pios_pwm_cfg pios_pwm_cfg = {
},
.remap = GPIO_PartialRemap_TIM3,
.irq = {
.handler = TIM1_CC_IRQHandler,
.handler = NULL,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
@ -778,7 +740,7 @@ void PIOS_TIM5_irq_handler()
#include <pios_ppm_priv.h>
void TIM6_IRQHandler();
void TIM6_IRQHandler() __attribute__ ((alias ("PIOS_TIM6_irq_handler")));
const struct pios_ppmsv_cfg pios_ppmsv_cfg = {
static const struct pios_ppmsv_cfg pios_ppmsv_cfg = {
.tim_base_init = {
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */
.TIM_ClockDivision = TIM_CKD_DIV1,
@ -787,7 +749,7 @@ const struct pios_ppmsv_cfg pios_ppmsv_cfg = {
.TIM_RepetitionCounter = 0x0000,
},
.irq = {
.handler = TIM6_IRQHandler,
.handler = NULL,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
@ -798,14 +760,14 @@ const struct pios_ppmsv_cfg pios_ppmsv_cfg = {
.ccr = TIM_IT_Update,
};
void PIOS_TIM6_irq_handler()
void PIOS_TIM6_irq_handler(void)
{
PIOS_PPMSV_irq_handler();
}
void TIM1_CC_IRQHandler();
void TIM1_CC_IRQHandler() __attribute__ ((alias ("PIOS_TIM1_CC_irq_handler")));
const struct pios_ppm_cfg pios_ppm_cfg = {
static const struct pios_ppm_cfg pios_ppm_cfg = {
.tim_base_init = {
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */
.TIM_ClockDivision = TIM_CKD_DIV1,
@ -827,7 +789,7 @@ const struct pios_ppm_cfg pios_ppm_cfg = {
},
.remap = 0,
.irq = {
.handler = TIM1_CC_IRQHandler,
.handler = NULL,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
@ -840,7 +802,7 @@ const struct pios_ppm_cfg pios_ppm_cfg = {
.ccr = TIM_IT_CC2,
};
void PIOS_TIM1_CC_irq_handler()
void PIOS_TIM1_CC_irq_handler(void)
{
PIOS_PPM_irq_handler();
}
@ -860,7 +822,7 @@ 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")));
const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
.regs = I2C2,
.init = {
.I2C_Mode = I2C_Mode_I2C,
@ -888,7 +850,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.event = {
.handler = PIOS_I2C_main_adapter_ev_irq_handler,
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_EV_IRQn,
@ -898,7 +860,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.error = {
.handler = PIOS_I2C_main_adapter_er_irq_handler,
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_ER_IRQn,
@ -1009,6 +971,13 @@ static const struct stm32_gpio pios_debug_pins[] = {
#endif /* PIOS_ENABLE_DEBUG_PINS */
#if defined(PIOS_INCLUDE_RCVR)
#include "pios_rcvr_priv.h"
uint32_t pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_DEVS];
uint32_t pios_rcvr_max_channel;
#endif /* PIOS_INCLUDE_RCVR */
extern const struct pios_com_driver pios_usb_com_driver;
uint32_t pios_com_telem_rf_id;
@ -1038,7 +1007,7 @@ void PIOS_Board_Init(void) {
#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_DEBUG_Assert(0);
PIOS_Assert(0);
}
/* Enable and mount the SDCard */
@ -1046,23 +1015,16 @@ void PIOS_Board_Init(void) {
PIOS_SDCARD_MountFS(0);
#endif /* PIOS_INCLUDE_SPI */
#if defined(PIOS_INCLUDE_SPEKTRUM)
/* SPEKTRUM init must come before comms */
PIOS_RTC_Init(); // Spektrum uses RTC to check for frame failures
PIOS_SPEKTRUM_Init();
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_spektrum_id, &pios_usart_com_driver, pios_usart_spektrum_id)) {
PIOS_DEBUG_Assert(0);
}
#endif
/* Initialize UAVObject libraries */
EventDispatcherInitialize();
UAVObjInitialize();
UAVObjectsInitializeAll();
#if defined(PIOS_INCLUDE_RTC)
/* Initialize the real-time clock and its associated tick */
PIOS_RTC_Init(&pios_rtc_main_cfg);
#endif
/* Initialize the alarms library */
AlarmsInitialize();
@ -1074,7 +1036,7 @@ void PIOS_Board_Init(void) {
/* Set up the SPI interface to the AHRS */
if (PIOS_SPI_Init(&pios_spi_ahrs_id, &pios_spi_ahrs_cfg)) {
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
/* Bind the AHRS comms layer to the AHRS SPI link */
@ -1082,43 +1044,95 @@ void PIOS_Board_Init(void) {
/* Initialize the PiOS library */
#if defined(PIOS_INCLUDE_COM)
#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_DEBUG_Assert(0);
PIOS_Assert(0);
}
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
#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);
PIOS_Assert(0);
}
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_GPS */
#endif
PIOS_Servo_Init();
PIOS_ADC_Init();
PIOS_GPIO_Init();
#if defined(PIOS_INCLUDE_SPEKTRUM)
#if (PIOS_SPEKTRUM_NUM_INPUTS > PIOS_RCVR_MAX_DEVS)
#error More receiver inputs than available devices
#endif
/* SPEKTRUM init must come before comms */
PIOS_SPEKTRUM_Init(&pios_spektrum_cfg, false);
uint32_t pios_usart_spektrum_id;
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_cfg)) {
PIOS_Assert(0);
}
for (uint8_t i = 0; i < PIOS_SPEKTRUM_NUM_INPUTS && i < PIOS_RCVR_MAX_DEVS; i++) {
if (!PIOS_RCVR_Init(&pios_rcvr_channel_to_id_map[pios_rcvr_max_channel],
&pios_spektrum_rcvr_driver,
i)) {
pios_rcvr_max_channel++;
} else {
PIOS_Assert(0);
}
}
#endif
#if defined(PIOS_INCLUDE_PWM)
#if (PIOS_PWM_NUM_INPUTS > PIOS_RCVR_MAX_DEVS)
#error More receiver inputs than available devices
#endif
PIOS_PWM_Init();
for (uint8_t i = 0; i < PIOS_PWM_NUM_INPUTS && i < PIOS_RCVR_MAX_DEVS; i++) {
if (!PIOS_RCVR_Init(&pios_rcvr_channel_to_id_map[pios_rcvr_max_channel],
&pios_pwm_rcvr_driver,
i)) {
pios_rcvr_max_channel++;
} else {
PIOS_Assert(0);
}
}
#endif
#if defined(PIOS_INCLUDE_PPM)
#if (PIOS_PPM_NUM_INPUTS > PIOS_RCVR_MAX_DEVS)
#error More receiver inputs than available devices
#endif
PIOS_PPM_Init();
for (uint8_t i = 0; i < PIOS_PPM_NUM_INPUTS && i < PIOS_RCVR_MAX_DEVS; i++) {
if (!PIOS_RCVR_Init(&pios_rcvr_channel_to_id_map[pios_rcvr_max_channel],
&pios_ppm_rcvr_driver,
i)) {
pios_rcvr_max_channel++;
} else {
PIOS_Assert(0);
}
}
#endif
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif /* PIOS_INCLUDE_USB_HID */
#if defined(PIOS_INCLUDE_I2C)
if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) {
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_I2C */
PIOS_IAP_Init();

View File

@ -120,7 +120,6 @@ extern uint32_t pios_i2c_main_adapter_id;
#define PIOS_USART_MAX_DEVS 2
#define PIOS_USART_RX_BUFFER_SIZE 256
#define PIOS_USART_TX_BUFFER_SIZE 256
#define PIOS_USART_BAUDRATE 230400
//-------------------------
// PIOS_COM

View File

@ -141,13 +141,11 @@ extern uint32_t pios_i2c_main_adapter_id;
//-------------------------
#define PIOS_COM_MAX_DEVS 4
#define PIOS_COM_TELEM_BAUDRATE 57600
extern uint32_t pios_com_telem_rf_id;
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
#define PIOS_COM_DEBUG PIOS_COM_TELEM_RF
#if defined(PIOS_INCLUDE_GPS)
#define PIOS_COM_GPS_BAUDRATE 57600
extern uint32_t pios_com_gps_id;
#define PIOS_COM_GPS (pios_com_gps_id)
#endif /* PIOS_INCLUDE_GPS */
@ -156,11 +154,15 @@ extern uint32_t pios_com_telem_usb_id;
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#ifdef PIOS_INCLUDE_SPEKTRUM
#define PIOS_COM_SPEKTRUM_BAUDRATE 115200
extern uint32_t pios_com_spektrum_id;
#define PIOS_COM_SPEKTRUM (pios_com_spektrum_id)
#endif
#ifdef PIOS_INCLUDE_SBUS
extern uint32_t pios_com_sbus_id;
#define PIOS_COM_SBUS (pios_com_sbus_id)
#endif
//-------------------------
// ADC
// PIOS_ADC_PinGet(0) = Gyro Z
@ -219,10 +221,26 @@ extern uint32_t pios_com_spektrum_id;
#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
//------------------------
// PIOS_RCVR
// See also pios_board.c
//------------------------
#define PIOS_RCVR_MAX_DEVS 12
//-------------------------
// Receiver PWM inputs
// Receiver PPM input
//-------------------------
#define PIOS_PWM_MAX_INPUTS 6
#define PIOS_PPM_NUM_INPUTS 6 //Could be more if needed
//-------------------------
// Receiver PWM input
//-------------------------
#define PIOS_PWM_NUM_INPUTS 6
//-------------------------
// Receiver SPEKTRUM input
//-------------------------
#define PIOS_SPEKTRUM_NUM_INPUTS 12
//-------------------------
// Servo outputs

View File

@ -135,12 +135,10 @@ extern uint32_t pios_i2c_gyro_adapter_id;
//-------------------------
#define PIOS_COM_MAX_DEVS 2
#define PIOS_COM_GPS_BAUDRATE 57600
extern uint32_t pios_com_gps_id;
#define PIOS_COM_GPS (pios_com_gps_id)
#ifdef PIOS_ENABLE_AUX_UART
#define PIOS_COM_AUX_BAUDRATE 57600
extern uint32_t pios_com_aux_id;
#define PIOS_COM_AUX (pios_com_aux_id)
#define PIOS_COM_DEBUG PIOS_COM_AUX

View File

@ -149,11 +149,9 @@ extern uint32_t pios_i2c_main_adapter_id;
//-------------------------
#define PIOS_COM_MAX_DEVS 4
#define PIOS_COM_TELEM_BAUDRATE 57600
extern uint32_t pios_com_telem_rf_id;
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
#define PIOS_COM_GPS_BAUDRATE 57600
extern uint32_t pios_com_gps_id;
#define PIOS_COM_GPS (pios_com_gps_id)
@ -161,18 +159,21 @@ extern uint32_t pios_com_telem_usb_id;
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#ifdef PIOS_ENABLE_AUX_UART
#define PIOS_COM_AUX_BAUDRATE 57600
extern uint32_t pios_com_aux_id;
#define PIOS_COM_AUX (pios_com_aux_id)
#define PIOS_COM_DEBUG PIOS_COM_AUX
#endif
#ifdef PIOS_INCLUDE_SPEKTRUM
#define PIOS_COM_SPEKTRUM_BAUDRATE 115200
extern uint32_t pios_com_spektrum_id;
#define PIOS_COM_SPEKTRUM (pios_com_spektrum_id)
#endif
#ifdef PIOS_INCLUDE_SBUS
extern uint32_t pios_com_sbus_id;
#define PIOS_COM_SBUS (pios_com_sbus_id)
#endif
//-------------------------
// Delay Timer
//-------------------------
@ -193,37 +194,33 @@ extern uint32_t pios_com_spektrum_id;
#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc...
#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc...
//-------------------------
// Receiver PWM inputs
//-------------------------
/*#define PIOS_PWM_SUPV_ENABLED 1
#define PIOS_PWM_SUPV_TIMER TIM6
#define PIOS_PWM_SUPV_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE)
#define PIOS_PWM_SUPV_HZ 25
#define PIOS_PWM_SUPV_IRQ_CHANNEL TIM6_IRQn
#define PIOS_PWM_SUPV_IRQ_FUNC void TIM6_IRQHandler(void)*/
//------------------------
// PIOS_RCVR
// See also pios_board.c
//------------------------
#define PIOS_RCVR_MAX_DEVS 12
//-------------------------
// Receiver PPM input
//-------------------------
#define PIOS_PPM_NUM_INPUTS 8 //Could be more if needed
#define PIOS_PPM_SUPV_ENABLED 1
//-------------------------
// SPEKTRUM input
// Receiver PWM input
//-------------------------
//#define PIOS_SPEKTRUM_SUPV_ENABLED 1
//#define PIOS_SPEKTRUM_SUPV_TIMER TIM6
//#define PIOS_SPEKTRUM_SUPV_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE)
//#define PIOS_SPEKTRUM_SUPV_HZ 60 // 1/22ms
//#define PIOS_SPEKTRUM_SUPV_IRQ_CHANNEL TIM6_IRQn
//#define PIOS_SPEKTRUM_SUPV_IRQ_FUNC void TIM6_IRQHandler(void)
#define PIOS_PWM_NUM_INPUTS 8
//-------------------------
// Receiver SPEKTRUM input
//-------------------------
#define PIOS_SPEKTRUM_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_PWM_MAX_INPUTS 8
//-------------------------
// ADC

View File

@ -38,7 +38,7 @@
static bool PIOS_COM_validate(struct pios_com_dev * com_dev)
{
return (com_dev->magic == PIOS_COM_DEV_MAGIC);
return (com_dev && (com_dev->magic == PIOS_COM_DEV_MAGIC));
}
#if defined(PIOS_INCLUDE_FREERTOS) && 0
@ -298,7 +298,9 @@ int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id)
if (!PIOS_COM_validate(com_dev)) {
/* Undefined COM port for this board (see pios_board.c) */
PIOS_DEBUG_Assert(0);
/* This is commented out so com_id=NULL can be used to disable telemetry */
//PIOS_DEBUG_Assert(0);
return 0;
}
if (!com_dev->driver->rx_avail) {

View File

@ -32,8 +32,8 @@
#include "pios.h"
#if defined(PIOS_INCLUDE_HCSR04)
#if !defined(PIOS_INCLUDE_SPEKTRUM)
#error Only supported with spektrum interface!
#if !(defined(PIOS_INCLUDE_SPEKTRUM) || defined(PIOS_INCLUDE_SBUS))
#error Only supported with Spektrum or S.Bus interface!
#endif
/* Local Variables */

View File

@ -0,0 +1,88 @@
/* Project Includes */
#include "pios.h"
#if defined(PIOS_INCLUDE_RCVR)
#include <pios_rcvr_priv.h>
static bool PIOS_RCVR_validate(struct pios_rcvr_dev * rcvr_dev)
{
return (rcvr_dev->magic == PIOS_RCVR_DEV_MAGIC);
}
#if defined(PIOS_INCLUDE_FREERTOS) && 0
static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
{
struct pios_rcvr_dev * rcvr_dev;
rcvr_dev = (struct pios_rcvr_dev *)malloc(sizeof(*rcvr_dev));
if (!rcvr_dev) return (NULL);
rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
return(rcvr_dev);
}
#else
static struct pios_rcvr_dev pios_rcvr_devs[PIOS_RCVR_MAX_DEVS];
static uint8_t pios_rcvr_num_devs;
static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
{
struct pios_rcvr_dev * rcvr_dev;
if (pios_rcvr_num_devs >= PIOS_RCVR_MAX_DEVS) {
return (NULL);
}
rcvr_dev = &pios_rcvr_devs[pios_rcvr_num_devs++];
rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
return (rcvr_dev);
}
#endif
/**
* Initialises RCVR layer
* \param[out] handle
* \param[in] driver
* \param[in] id
* \return < 0 if initialisation failed
*/
int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id)
{
PIOS_DEBUG_Assert(rcvr_id);
PIOS_DEBUG_Assert(driver);
struct pios_rcvr_dev * rcvr_dev;
rcvr_dev = (struct pios_rcvr_dev *) PIOS_RCVR_alloc();
if (!rcvr_dev) goto out_fail;
rcvr_dev->driver = driver;
rcvr_dev->id = lower_id;
*rcvr_id = (uint32_t)rcvr_dev;
return(0);
out_fail:
return(-1);
}
int32_t PIOS_RCVR_Read(uint32_t rcvr_id)
{
struct pios_rcvr_dev * rcvr_dev = (struct pios_rcvr_dev *)rcvr_id;
if (!PIOS_RCVR_validate(rcvr_dev)) {
/* Undefined RCVR port for this board (see pios_board.c) */
PIOS_DEBUG_Assert(0);
}
PIOS_DEBUG_Assert(rcvr_dev->driver->read);
return rcvr_dev->driver->read(rcvr_dev->id);
}
#endif
/**
* @}
* @}
*/

View File

@ -34,22 +34,29 @@
#if defined(PIOS_INCLUDE_PPM)
/* Local Variables */
/* Provide a RCVR driver */
static int32_t PIOS_PPM_Get(uint32_t chan_id);
const struct pios_rcvr_driver pios_ppm_rcvr_driver = {
.read = PIOS_PPM_Get,
};
/* Local Variables */
static TIM_ICInitTypeDef TIM_ICInitStructure;
static uint8_t PulseIndex;
static uint32_t PreviousValue;
static uint32_t CurrentValue;
static uint32_t CapturedValue;
static uint32_t CaptureValue[PIOS_PPM_NUM_INPUTS];
static uint8_t SupervisorState = 0;
static uint32_t CapCounter[PIOS_PPM_NUM_INPUTS];
static uint16_t TimerCounter;
static uint8_t supv_timer = 0;
static uint8_t SupervisorState = 0;
static uint32_t CapCounterPrev[PIOS_PPM_NUM_INPUTS];
/**
* Initialises all the LED's
*/
static void PIOS_PPM_Supervisor(uint32_t ppm_id);
void PIOS_PPM_Init(void)
{
/* Flush counter variables */
@ -59,6 +66,7 @@ void PIOS_PPM_Init(void)
PreviousValue = 0;
CurrentValue = 0;
CapturedValue = 0;
TimerCounter = 0;
for (i = 0; i < PIOS_PPM_NUM_INPUTS; i++) {
CaptureValue[i] = 0;
@ -121,13 +129,12 @@ void PIOS_PPM_Init(void)
TIM_TimeBaseInit(pios_ppm_cfg.timer, &TIM_TimeBaseStructure);
/* Enable the Capture Compare Interrupt Request */
TIM_ITConfig(pios_ppm_cfg.timer, pios_ppm_cfg.ccr, ENABLE);
TIM_ITConfig(pios_ppm_cfg.timer, pios_ppm_cfg.ccr | TIM_IT_Update, ENABLE);
/* Enable timers */
TIM_Cmd(pios_ppm_cfg.timer, ENABLE);
/* Supervisor Setup */
#if (PIOS_PPM_SUPV_ENABLED)
/* Flush counter variables */
for (i = 0; i < PIOS_PPM_NUM_INPUTS; i++) {
CapCounter[i] = 0;
@ -136,70 +143,15 @@ void PIOS_PPM_Init(void)
CapCounterPrev[i] = 0;
}
NVIC_InitStructure = pios_ppmsv_cfg.irq.init;
/* Enable appropriate clock to timer module */
switch((int32_t) pios_ppmsv_cfg.timer) {
case (int32_t)TIM1:
NVIC_InitStructure.NVIC_IRQChannel = TIM1_CC_IRQn;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
break;
case (int32_t)TIM2:
NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
break;
case (int32_t)TIM3:
NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
break;
case (int32_t)TIM4:
NVIC_InitStructure.NVIC_IRQChannel = TIM4_IRQn;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE);
break;
#ifdef STM32F10X_HD
case (int32_t)TIM5:
NVIC_InitStructure.NVIC_IRQChannel = TIM5_IRQn;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE);
break;
case (int32_t)TIM6:
NVIC_InitStructure.NVIC_IRQChannel = TIM6_IRQn;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE);
break;
case (int32_t)TIM7:
NVIC_InitStructure.NVIC_IRQChannel = TIM7_IRQn;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE);
break;
case (int32_t)TIM8:
NVIC_InitStructure.NVIC_IRQChannel = TIM8_CC_IRQn;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE);
break;
#endif
}
/* Configure interrupts */
NVIC_Init(&NVIC_InitStructure);
/* Time base configuration */
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
TIM_TimeBaseStructure = pios_ppmsv_cfg.tim_base_init;
TIM_TimeBaseInit(pios_ppmsv_cfg.timer, &TIM_TimeBaseStructure);
/* Enable the CCx Interrupt Request */
TIM_ITConfig(pios_ppmsv_cfg.timer, pios_ppmsv_cfg.ccr, ENABLE);
/* Clear update pending flag */
TIM_ClearFlag(pios_ppmsv_cfg.timer, TIM_FLAG_Update);
/* Enable counter */
TIM_Cmd(pios_ppmsv_cfg.timer, ENABLE);
#endif
/* 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, 0)) {
PIOS_DEBUG_Assert(0);
}
}
/**
@ -208,13 +160,13 @@ void PIOS_PPM_Init(void)
* \output -1 Channel not available
* \output >0 Channel value
*/
int32_t PIOS_PPM_Get(int8_t Channel)
static int32_t PIOS_PPM_Get(uint32_t chan_id)
{
/* Return error if channel not available */
if (Channel >= PIOS_PPM_NUM_INPUTS) {
if (chan_id >= PIOS_PPM_NUM_INPUTS) {
return -1;
}
return CaptureValue[Channel];
return CaptureValue[chan_id];
}
/**
@ -224,6 +176,15 @@ int32_t PIOS_PPM_Get(int8_t Channel)
*/
void PIOS_PPM_irq_handler(void)
{
if (TIM_GetITStatus(pios_ppm_cfg.timer, TIM_IT_Update) == SET) {
TimerCounter+=pios_ppm_cfg.timer->ARR;
TIM_ClearITPendingBit(pios_ppm_cfg.timer, TIM_IT_Update);
if (TIM_GetITStatus(pios_ppm_cfg.timer, pios_ppm_cfg.ccr) != SET) {
return;
}
}
/* Do this as it's more efficient */
if (TIM_GetITStatus(pios_ppm_cfg.timer, pios_ppm_cfg.ccr) == SET) {
PreviousValue = CurrentValue;
@ -241,6 +202,9 @@ void PIOS_PPM_irq_handler(void)
CurrentValue = TIM_GetCapture4(pios_ppm_cfg.timer);
break;
}
CurrentValue+=TimerCounter;
if(CurrentValue > 0xFFFF) {
CurrentValue-=0xFFFF;
}
/* Clear TIMx Capture compare interrupt pending bit */
@ -265,13 +229,17 @@ void PIOS_PPM_irq_handler(void)
}
}
}
}
/**
* This function handles TIM3 global interrupt request.
static void PIOS_PPM_Supervisor(uint32_t ppm_id) {
/*
* RTC runs at 625Hz so divide down the base rate so
* that this loop runs at 25Hz.
*/
void PIOS_PPMSV_irq_handler(void) {
/* Clear timer interrupt pending bit */
TIM_ClearITPendingBit(pios_ppmsv_cfg.timer, pios_ppmsv_cfg.ccr);
if(++supv_timer < 25) {
return;
}
supv_timer = 0;
/* Simple state machine */
if (SupervisorState == 0) {

View File

@ -34,15 +34,20 @@
#if defined(PIOS_INCLUDE_PWM)
/* Local Variables */
static uint8_t CaptureState[PIOS_PWM_MAX_INPUTS];
static uint16_t RiseValue[PIOS_PWM_MAX_INPUTS];
static uint16_t FallValue[PIOS_PWM_MAX_INPUTS];
static uint32_t CaptureValue[PIOS_PWM_MAX_INPUTS];
/* Provide a RCVR driver */
static int32_t PIOS_PWM_Get(uint32_t chan_id);
//static uint8_t SupervisorState = 0;
static uint32_t CapCounter[PIOS_PWM_MAX_INPUTS];
//static uint32_t CapCounterPrev[MAX_CHANNELS];
const struct pios_rcvr_driver pios_pwm_rcvr_driver = {
.read = PIOS_PWM_Get,
};
/* Local Variables */
static uint8_t CaptureState[PIOS_PWM_NUM_INPUTS];
static uint16_t RiseValue[PIOS_PWM_NUM_INPUTS];
static uint16_t FallValue[PIOS_PWM_NUM_INPUTS];
static uint32_t CaptureValue[PIOS_PWM_NUM_INPUTS];
static uint32_t CapCounter[PIOS_PWM_NUM_INPUTS];
/**
* Initialises all the pins
@ -127,52 +132,6 @@ void PIOS_PWM_Init(void)
/* Warning, I don't think this will work for multiple remaps at once */
GPIO_PinRemapConfig(pios_pwm_cfg.remap, ENABLE);
}
#if 0
/* Supervisor Setup */
#if (PIOS_PWM_SUPV_ENABLED)
/* Flush counter variables */
for (i = 0; i < PIOS_PWM_NUM_INPUTS; i++) {
CapCounter[i] = 0;
}
for (i = 0; i < PIOS_PWM_NUM_INPUTS; i++) {
CapCounterPrev[i] = 0;
}
/* Enable timer clock */
PIOS_PWM_SUPV_TIMER_RCC_FUNC;
/* Configure interrupts */
NVIC_InitStructure.NVIC_IRQChannel = PIOS_PWM_SUPV_IRQ_CHANNEL;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
/* Time base configuration */
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
TIM_TimeBaseStructure.TIM_Period = ((1000000 / PIOS_PWM_SUPV_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(PIOS_PWM_SUPV_TIMER, &TIM_TimeBaseStructure);
/* Enable the CC2 Interrupt Request */
TIM_ITConfig(PIOS_PWM_SUPV_TIMER, TIM_IT_Update, ENABLE);
/* Clear update pending flag */
TIM_ClearFlag(TIM2, TIM_FLAG_Update);
/* Enable counter */
TIM_Cmd(PIOS_PWM_SUPV_TIMER, ENABLE);
#endif
/* 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;
#endif
}
/**
@ -181,13 +140,13 @@ void PIOS_PWM_Init(void)
* \output -1 Channel not available
* \output >0 Channel value
*/
int32_t PIOS_PWM_Get(int8_t Channel)
static int32_t PIOS_PWM_Get(uint32_t chan_id)
{
/* Return error if channel not available */
if (Channel >= pios_pwm_cfg.num_channels) {
if (chan_id >= pios_pwm_cfg.num_channels) {
return -1;
}
return CaptureValue[Channel];
return CaptureValue[chan_id];
}
void PIOS_PWM_irq_handler(TIM_TypeDef * timer)
@ -254,84 +213,6 @@ void PIOS_PWM_irq_handler(TIM_TypeDef * timer)
}
}
#if 0
/**
* Handle TIM5 global interrupt request
*/
void TIM5_IRQHandler(void)
{
/* Do this as it's more efficient */
if (TIM_GetITStatus(PIOS_PWM_TIM_PORT[2], PIOS_PWM_TIM_CCR[2]) == SET) {
if (CaptureState[2] == 0) {
RiseValue[2] = TIM_GetCapture1(PIOS_PWM_TIM_PORT[2]);
} else {
FallValue[2] = TIM_GetCapture1(PIOS_PWM_TIM_PORT[2]);
}
/* Clear TIM3 Capture compare interrupt pending bit */
TIM_ClearITPendingBit(PIOS_PWM_TIM_PORT[2], PIOS_PWM_TIM_CCR[2]);
/* Simple rise or fall state machine */
if (CaptureState[2] == 0) {
/* Switch states */
CaptureState[2] = 1;
/* Switch polarity of input capture */
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling;
TIM_ICInitStructure.TIM_Channel = PIOS_PWM_TIM_CHANNEL[2];
TIM_ICInit(PIOS_PWM_TIM_PORT[2], &TIM_ICInitStructure);
} else {
/* Capture computation */
if (FallValue[2] > RiseValue[2]) {
CaptureValue[2] = (FallValue[2] - RiseValue[2]);
} else {
CaptureValue[2] = ((0xFFFF - RiseValue[2]) + FallValue[2]);
}
/* Switch states */
CaptureState[2] = 0;
/* Increase supervisor counter */
CapCounter[2]++;
/* Switch polarity of input capture */
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
TIM_ICInitStructure.TIM_Channel = PIOS_PWM_TIM_CHANNEL[2];
TIM_ICInit(PIOS_PWM_TIM_PORT[2], &TIM_ICInitStructure);
}
}
}
/**
* This function handles TIM3 global interrupt request.
*/
PIOS_PWM_SUPV_IRQ_FUNC {
/* Clear timer interrupt pending bit */
TIM_ClearITPendingBit(PIOS_PWM_SUPV_TIMER, TIM_IT_Update);
/* Simple state machine */
if (SupervisorState == 0) {
/* Save this states values */
for (int32_t i = 0; i < PIOS_PWM_NUM_INPUTS; i++) {
CapCounterPrev[i] = CapCounter[i];
}
/* Move to next state */
SupervisorState = 1;
} else {
/* See what channels have been updated */
for (int32_t i = 0; i < PIOS_PWM_NUM_INPUTS; i++) {
if (CapCounter[i] == CapCounterPrev[i]) {
CaptureValue[i] = 0;
}
}
/* Move to next state */
SupervisorState = 0;
}
}
#endif
#endif
/**

View File

@ -32,30 +32,39 @@
#include "pios.h"
#if defined(PIOS_INCLUDE_RTC)
#include <pios_rtc_priv.h>
#ifndef PIOS_RTC_PRESCALAR
#define PIOS_RTC_PRESCALAR 100
#ifndef PIOS_RTC_PRESCALER
#define PIOS_RTC_PRESCALER 100
#endif
void PIOS_RTC_Init()
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_APB1PeriphClockCmd(RCC_APB1Periph_BKP | RCC_APB1Periph_PWR,
ENABLE);
PWR_BackupAccessCmd(ENABLE);
RCC_RTCCLKConfig(RCC_RTCCLKSource_HSE_Div128);
RCC_RTCCLKConfig(cfg->clksrc);
RCC_RTCCLKCmd(ENABLE);
RTC_WaitForLastTask();
RTC_WaitForSynchro();
RTC_WaitForLastTask();
#if defined(PIOS_INCLUDE_SPEKTRUM)
/* Enable the RTC Second interrupt */
/* Configure and enable the RTC Second interrupt */
NVIC_Init(&cfg->irq.init);
RTC_ITConfig( RTC_IT_SEC, ENABLE );
/* Wait until last write operation on RTC registers has finished */
RTC_WaitForLastTask();
#endif
RTC_SetPrescaler(PIOS_RTC_PRESCALAR); // counting at 8e6 / 128
RTC_SetPrescaler(cfg->prescaler);
RTC_WaitForLastTask();
RTC_SetCounter(0);
RTC_WaitForLastTask();
@ -66,9 +75,12 @@ uint32_t PIOS_RTC_Counter()
return RTC_GetCounter();
}
/* 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_PRESCALAR);
return (float) (8e6 / 128) / (1 + PIOS_RTC_PRESCALER);
}
float PIOS_RTC_MsPerTick()
@ -76,6 +88,39 @@ 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_SEC))
{
/* 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);
}
}
/* Wait until last write operation on RTC registers has finished */
RTC_WaitForLastTask();
/* Clear the RTC Second interrupt */
RTC_ClearITPendingBit(RTC_IT_SEC);
}
}
#endif
/**

View File

@ -0,0 +1,227 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_SBUS Futaba S.Bus receiver functions
* @brief Code to read Futaba S.Bus input
* @{
*
* @file pios_sbus.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief USART commands. Inits USARTs, controls USARTs & Interrupt 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
*/
/* Project Includes */
#include "pios.h"
#include "pios_sbus_priv.h"
#if defined(PIOS_INCLUDE_SBUS)
/* Global Variables */
/* Provide a RCVR driver */
static int32_t PIOS_SBUS_Get(uint32_t chan_id);
const struct pios_rcvr_driver pios_sbus_rcvr_driver = {
.read = PIOS_SBUS_Get,
};
/* Local Variables */
static uint16_t channel_data[SBUS_NUMBER_OF_CHANNELS];
static uint8_t received_data[SBUS_FRAME_LENGTH - 2];
static uint8_t receive_timer;
static uint8_t failsafe_timer;
static uint8_t frame_found;
static void PIOS_SBUS_Supervisor(uint32_t sbus_id);
/**
* reset_channels() function clears all channel data in case of
* lost signal or explicit failsafe flag from the S.Bus data stream
*/
static void reset_channels(void)
{
for (int i = 0; i < SBUS_NUMBER_OF_CHANNELS; i++) {
channel_data[i] = 0;
}
}
/**
* unroll_channels() function computes channel_data[] from received_data[]
* For efficiency it unrolls first 8 channels without loops. If other
* 8 channels are needed they can be unrolled using the same code
* starting from s[11] instead of s[0]. Two extra digital channels are
* accessible using (s[22] & SBUS_FLAG_DGx) logical expressions.
*/
static void unroll_channels(void)
{
uint8_t *s = received_data;
uint16_t *d = channel_data;
#if (SBUS_NUMBER_OF_CHANNELS != 8)
#error Current S.Bus code unrolls only first 8 channels
#endif
#define F(v,s) ((v) >> s) & 0x7ff
*d++ = F(s[0] | s[1] << 8, 0);
*d++ = F(s[1] | s[2] << 8, 3);
*d++ = F(s[2] | s[3] << 8 | s[4] << 16, 6);
*d++ = F(s[4] | s[5] << 8, 1);
*d++ = F(s[5] | s[6] << 8, 4);
*d++ = F(s[6] | s[7] << 8 | s[8] << 16, 7);
*d++ = F(s[8] | s[9] << 8, 2);
*d++ = F(s[9] | s[10] << 8, 5);
}
/**
* process_byte() function processes incoming byte from S.Bus stream
*/
static void process_byte(uint8_t b)
{
static uint8_t byte_count;
if (frame_found == 0) {
/* no frame found yet, waiting for start byte */
if (b == SBUS_SOF_BYTE) {
byte_count = 0;
frame_found = 1;
}
} else {
/* do not store start and end of frame bytes */
if (byte_count < SBUS_FRAME_LENGTH - 2) {
/* store next byte */
received_data[byte_count++] = b;
} else {
if (b == SBUS_EOF_BYTE) {
/* full frame received */
uint8_t flags = received_data[SBUS_FRAME_LENGTH - 3];
if (flags & SBUS_FLAG_FL) {
/* frame lost, do not update */
} else if (flags & SBUS_FLAG_FS) {
/* failsafe flag active */
reset_channels();
} else {
/* data looking good */
unroll_channels();
failsafe_timer = 0;
}
} else {
/* discard whole frame */
}
/* prepare for the next frame */
frame_found = 0;
}
}
}
/**
* Initialise S.Bus receiver interface
*/
void PIOS_SBUS_Init(const struct pios_sbus_cfg *cfg)
{
/* Enable inverter clock and enable the inverter */
(*cfg->gpio_clk_func)(cfg->gpio_clk_periph, ENABLE);
GPIO_Init(cfg->inv.gpio, &cfg->inv.init);
GPIO_WriteBit(cfg->inv.gpio,
cfg->inv.init.GPIO_Pin,
cfg->gpio_inv_enable);
if (!PIOS_RTC_RegisterTickCallback(PIOS_SBUS_Supervisor, 0)) {
PIOS_Assert(0);
}
}
/**
* Get the value of an input channel
* \param[in] channel Number of the channel desired (zero based)
* \output -1 channel not available
* \output >0 channel value
*/
static int32_t PIOS_SBUS_Get(uint32_t chan_id)
{
/* return error if channel is not available */
if (chan_id >= SBUS_NUMBER_OF_CHANNELS) {
return -1;
}
return channel_data[chan_id];
}
/**
* Interrupt handler for USART
*/
void PIOS_SBUS_irq_handler(uint32_t usart_id)
{
/* Grab the config for this device from the underlying USART device */
const struct pios_usart_cfg * cfg;
cfg = PIOS_USART_GetConfig(usart_id);
PIOS_Assert(cfg);
/* by always reading DR after SR make sure to clear any error interrupts */
volatile uint16_t sr = cfg->regs->SR;
volatile uint8_t b = cfg->regs->DR;
/* process received byte if one has arrived */
if (sr & USART_SR_RXNE) {
/* process byte and clear receive timer */
process_byte(b);
receive_timer = 0;
}
/* ignore TXE interrupts */
if (sr & USART_SR_TXE) {
/* disable TXE interrupt (TXEIE=0) */
USART_ITConfig(cfg->regs, USART_IT_TXE, DISABLE);
}
}
/**
* Input data supervisor is called periodically and provides
* two functions: frame syncing and failsafe triggering.
*
* S.Bus frames come at 7ms (HS) or 14ms (FS) rate at 100000bps. RTC
* timer is running at 625Hz (1.6ms). So with divider 2 it gives
* 3.2ms pause between frames which is good for both S.Bus data 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_SBUS_Supervisor(uint32_t sbus_id)
{
/* waiting for new frame if no bytes were received in 3.2ms */
if (++receive_timer > 2) {
receive_timer = 0;
frame_found = 0;
}
/* activate failsafe if no frames have arrived in 102.4ms */
if (++failsafe_timer > 64) {
reset_channels();
failsafe_timer = 0;
}
}
#endif
/**
* @}
* @}
*/

View File

@ -34,12 +34,6 @@
#include "pios_spektrum_priv.h"
#if defined(PIOS_INCLUDE_SPEKTRUM)
#if defined(PIOS_INCLUDE_PWM)
#error "Both PWM and SPEKTRUM input defined, choose only one"
#endif
#if defined(PIOS_COM_AUX)
#error "AUX com cannot be used with SPEKTRUM"
#endif
/**
* @Note Framesyncing:
@ -51,31 +45,35 @@
/* Global Variables */
/* Provide a RCVR driver */
static int32_t PIOS_SPEKTRUM_Get(uint32_t chan_id);
const struct pios_rcvr_driver pios_spektrum_rcvr_driver = {
.read = PIOS_SPEKTRUM_Get,
};
/* Local Variables */
static uint16_t CaptureValue[12],CaptureValueTemp[12];
static uint16_t CaptureValue[PIOS_SPEKTRUM_NUM_INPUTS],CaptureValueTemp[PIOS_SPEKTRUM_NUM_INPUTS];
static uint8_t prev_byte = 0xFF, sync = 0, bytecount = 0, datalength=0, frame_error=0, byte_array[20] = { 0 };
uint8_t sync_of = 0;
uint16_t supv_timer=0;
static void PIOS_SPEKTRUM_Supervisor(uint32_t spektrum_id);
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg);
/**
* Bind and Initialise Spektrum satellite receiver
*/
void PIOS_SPEKTRUM_Init(void)
void PIOS_SPEKTRUM_Init(const struct pios_spektrum_cfg * cfg, bool bind)
{
// TODO: need setting flag for bind on next powerup
if (0) {
PIOS_SPEKTRUM_Bind();
if (bind) {
PIOS_SPEKTRUM_Bind(cfg);
}
/* Init RTC supervisor timer interrupt */
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = RTC_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
/* Init RTC clock */
PIOS_RTC_Init();
if (!PIOS_RTC_RegisterTickCallback(PIOS_SPEKTRUM_Supervisor, 0)) {
PIOS_DEBUG_Assert(0);
}
}
/**
@ -84,59 +82,56 @@ void PIOS_SPEKTRUM_Init(void)
* \output -1 Channel not available
* \output >0 Channel value
*/
int16_t PIOS_SPEKTRUM_Get(int8_t Channel)
static int32_t PIOS_SPEKTRUM_Get(uint32_t chan_id)
{
/* Return error if channel not available */
if (Channel >= 12) {
if (chan_id >= PIOS_SPEKTRUM_NUM_INPUTS) {
return -1;
}
return CaptureValue[Channel];
return CaptureValue[chan_id];
}
/**
* Spektrum bind function
* \output 1 Successful bind
* \output 0 Bind failed
* \note Applications shouldn't call these functions directly
* \output true Successful bind
* \output false Bind failed
*/
uint8_t PIOS_SPEKTRUM_Bind(void)
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg)
{
GPIO_InitTypeDef GPIO_InitStructure = pios_spektrum_cfg.gpio_init;
GPIO_InitStructure.GPIO_Pin = pios_spektrum_cfg.pin;
GPIO_Init(pios_spektrum_cfg.port, &GPIO_InitStructure);
GPIO_Init(cfg->bind.gpio, &cfg->bind.init);
pios_spektrum_cfg.port->BRR = pios_spektrum_cfg.pin;
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
//PIOS_DELAY_WaitmS(75);
/* RX line, drive high for 10us */
pios_spektrum_cfg.port->BSRR = pios_spektrum_cfg.pin;
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(10);
/* RX line, drive low for 120us */
pios_spektrum_cfg.port->BRR = pios_spektrum_cfg.pin;
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
/* RX line, drive high for 120us */
pios_spektrum_cfg.port->BSRR = pios_spektrum_cfg.pin;
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
/* RX line, drive low for 120us */
pios_spektrum_cfg.port->BRR = pios_spektrum_cfg.pin;
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
/* RX line, drive high for 120us */
pios_spektrum_cfg.port->BSRR = pios_spektrum_cfg.pin;
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
/* RX line, drive low for 120us */
pios_spektrum_cfg.port->BRR = pios_spektrum_cfg.pin;
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
/* RX line, drive high for 120us */
pios_spektrum_cfg.port->BSRR = pios_spektrum_cfg.pin;
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
/* RX line, drive low for 120us */
pios_spektrum_cfg.port->BRR = pios_spektrum_cfg.pin;
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
/* RX line, drive high for 120us */
pios_spektrum_cfg.port->BSRR = pios_spektrum_cfg.pin;
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
/* RX line, set input and wait for data, PIOS_SPEKTRUM_Init */
return 1;
return true;
}
/**
@ -147,7 +142,7 @@ uint8_t PIOS_SPEKTRUM_Bind(void)
* \return -2 if buffer full (retry)
* \note Applications shouldn't call these functions directly
*/
int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
static int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
{
static uint16_t channel = 0; /*, sync_word = 0;*/
uint8_t channeln = 0, frame = 0;
@ -201,7 +196,7 @@ int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
{
frame_error=1;
}
if (channeln < 12 && !frame_error)
if (channeln < PIOS_SPEKTRUM_NUM_INPUTS && !frame_error)
CaptureValueTemp[channeln] = data;
}
}
@ -212,7 +207,7 @@ int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
sync_of = 0;
if (!frame_error)
{
for(int i=0;i<12;i++)
for(int i=0;i<PIOS_SPEKTRUM_NUM_INPUTS;i++)
{
CaptureValue[i] = CaptureValueTemp[i];
}
@ -223,11 +218,16 @@ int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
return 0;
}
/* Interrupt handler for USART */
void SPEKTRUM_IRQHandler(uint32_t usart_id) {
/* Custom interrupt handler for USART */
void PIOS_SPEKTRUM_irq_handler(uint32_t usart_id) {
/* Grab the config for this device from the underlying USART device */
const struct pios_usart_cfg * cfg;
cfg = PIOS_USART_GetConfig(usart_id);
PIOS_Assert(cfg);
/* by always reading DR after SR make sure to clear any error interrupts */
volatile uint16_t sr = pios_spektrum_cfg.pios_usart_spektrum_cfg->regs->SR;
volatile uint8_t b = pios_spektrum_cfg.pios_usart_spektrum_cfg->regs->DR;
volatile uint16_t sr = cfg->regs->SR;
volatile uint8_t b = cfg->regs->DR;
/* check if RXNE flag is set */
if (sr & USART_SR_RXNE) {
@ -238,7 +238,7 @@ void SPEKTRUM_IRQHandler(uint32_t usart_id) {
if (sr & USART_SR_TXE) { // check if TXE flag is set
/* Disable TXE interrupt (TXEIE=0) */
USART_ITConfig(pios_spektrum_cfg.pios_usart_spektrum_cfg->regs, USART_IT_TXE, DISABLE);
USART_ITConfig(cfg->regs, USART_IT_TXE, DISABLE);
}
/* byte arrived so clear "watchdog" timer */
supv_timer=0;
@ -248,7 +248,7 @@ void SPEKTRUM_IRQHandler(uint32_t usart_id) {
*@brief This function is called between frames and when a spektrum word hasnt been decoded for too long
*@brief clears the channel values
*/
void PIOS_SPEKTRUM_irq_handler() {
static void PIOS_SPEKTRUM_Supervisor(uint32_t spektrum_id) {
/* 125hz */
supv_timer++;
if(supv_timer > 5) {
@ -262,7 +262,7 @@ void PIOS_SPEKTRUM_irq_handler() {
if (sync_of > 12) {
/* signal lost */
sync_of = 0;
for (int i = 0; i < 12; i++) {
for (int i = 0; i < PIOS_SPEKTRUM_NUM_INPUTS; i++) {
CaptureValue[i] = 0;
CaptureValueTemp[i] = 0;
}

View File

@ -51,6 +51,23 @@ const struct pios_com_driver pios_usart_com_driver = {
.rx_avail = PIOS_USART_RxBufferUsed,
};
enum pios_usart_dev_magic {
PIOS_USART_DEV_MAGIC = 0x11223344,
};
struct pios_usart_dev {
enum pios_usart_dev_magic magic;
const struct pios_usart_cfg * cfg;
// align to 32-bit to try and provide speed improvement;
uint8_t rx_buffer[PIOS_USART_RX_BUFFER_SIZE] __attribute__ ((aligned(4)));
t_fifo_buffer rx;
// align to 32-bit to try and provide speed improvement;
uint8_t tx_buffer[PIOS_USART_TX_BUFFER_SIZE] __attribute__ ((aligned(4)));
t_fifo_buffer tx;
};
static bool PIOS_USART_validate(struct pios_usart_dev * usart_dev)
{
return (usart_dev->magic == PIOS_USART_DEV_MAGIC);
@ -85,6 +102,34 @@ static struct pios_usart_dev * PIOS_USART_alloc(void)
}
#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);
}
/**
* Initialise a single USART device
@ -134,6 +179,11 @@ int32_t PIOS_USART_Init(uint32_t * usart_id, const struct pios_usart_cfg * cfg)
*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;
case (uint32_t)USART2: PIOS_USART_2_id = (uint32_t)usart_dev;
case (uint32_t)USART3: PIOS_USART_3_id = (uint32_t)usart_dev;
}
NVIC_Init(&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);
@ -147,6 +197,19 @@ out_fail:
return(-1);
}
const struct pios_usart_cfg * PIOS_USART_GetConfig(uint32_t usart_id)
{
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
if (!valid) {
return (NULL);
}
return usart_dev->cfg;
}
/**
* Changes the baud rate of the USART peripheral without re-initialising.
* \param[in] usart_id USART name (GPS, TELEM, AUX)
@ -157,7 +220,7 @@ 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)
PIOS_Assert(valid);
USART_InitTypeDef USART_InitStructure;
@ -337,12 +400,20 @@ static int32_t PIOS_USART_TxBufferPutMore(uint32_t usart_id, const uint8_t *buff
return rc;
}
void PIOS_USART_IRQ_Handler(uint32_t usart_id)
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)
PIOS_Assert(valid);
/* Call any user provided callback function instead of processing
* the interrupt ourselves.
*/
if (usart_dev->cfg->irq.handler) {
(usart_dev->cfg->irq.handler)(usart_id);
return;
}
/* Force read of dr after sr to make sure to clear error flags */
volatile uint16_t sr = usart_dev->cfg->regs->SR;

View File

@ -30,8 +30,4 @@
#ifndef PIOS_PPM_H
#define PIOS_PPM_H
/* Public Functions */
extern void PIOS_PPM_Init(void);
extern int32_t PIOS_PPM_Get(int8_t Channel);
#endif /* PIOS_PPM_H */

View File

@ -34,13 +34,6 @@
#include <pios.h>
#include <pios_stm32.h>
struct pios_ppmsv_cfg {
TIM_TimeBaseInitTypeDef tim_base_init;
struct stm32_irq irq;
TIM_TypeDef * timer;
uint16_t ccr;
};
struct pios_ppm_cfg {
TIM_TimeBaseInitTypeDef tim_base_init;
TIM_ICInitTypeDef tim_ic_init;
@ -53,11 +46,13 @@ struct pios_ppm_cfg {
};
extern void PIOS_PPM_irq_handler();
extern void PIOS_PPMSV_irq_handler();
extern uint8_t pios_ppm_num_channels;
extern const struct pios_ppm_cfg pios_ppm_cfg;
extern const struct pios_ppmsv_cfg pios_ppmsv_cfg;
extern const struct pios_rcvr_driver pios_ppm_rcvr_driver;
extern void PIOS_PPM_Init(void);
#endif /* PIOS_PPM_PRIV_H */

View File

@ -30,9 +30,4 @@
#ifndef PIOS_PWM_H
#define PIOS_PWM_H
/* Public Functions */
extern void PIOS_PWM_Init(void);
extern int32_t PIOS_PWM_Get(int8_t Channel);
//extern void PIOS_PWM_irq_handler(TIM_TypeDef * timer);
#endif /* PIOS_PWM_H */

View File

@ -57,6 +57,10 @@ extern void PIOS_PWM_irq_handler(TIM_TypeDef * timer);
extern uint8_t pios_pwm_num_channels;
extern const struct pios_pwm_cfg pios_pwm_cfg;
extern const struct pios_rcvr_driver pios_pwm_rcvr_driver;
extern void PIOS_PWM_Init(void);
#endif /* PIOS_PWM_PRIV_H */
/**

View File

@ -0,0 +1,49 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_RCVR RCVR layer functions
* @brief Hardware communication layer
* @{
*
* @file pios_rcvr.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief RCVR layer 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_RCVR_H
#define PIOS_RCVR_H
extern uint32_t pios_rcvr_channel_to_id_map[];
struct pios_rcvr_driver {
void (*init)(uint32_t id);
int32_t (*read)(uint32_t id);
};
/* Public Functions */
extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id);
#endif /* PIOS_RCVR_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,58 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_RCVR RCVR Functions
* @brief PIOS interface for RCVR drivers
* @{
*
* @file pios_rcvr_priv.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Thorsten Klose (tk@midibox.org)
* @brief USART private 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
*/
#ifndef PIOS_RCVR_PRIV_H
#define PIOS_RCVR_PRIV_H
#include <pios.h>
extern uint32_t pios_rcvr_max_channel;
enum pios_rcvr_dev_magic {
PIOS_RCVR_DEV_MAGIC = 0x99aabbcc,
};
struct pios_rcvr_dev {
enum pios_rcvr_dev_magic magic;
uint32_t id;
const struct pios_rcvr_driver * driver;
};
extern int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id);
extern void PIOS_RCVR_IRQ_Handler(uint32_t rcvr_id);
#endif /* PIOS_RCVR_PRIV_H */
/**
* @}
* @}
*/

View File

@ -30,13 +30,15 @@
#ifndef PIOS_RTC_H
#define PIOS_RTC_H
#include <stdbool.h>
/* Public Functions */
extern void PIOS_RTC_Init();
extern uint32_t PIOS_RTC_Counter();
extern float PIOS_RTC_Rate();
extern float PIOS_RTC_MsPerTick();
extern bool PIOS_RTC_RegisterTickCallback(void (*fn)(uint32_t id), uint32_t data);
#endif /* PIOS_SERVO_H */
#endif /* PIOS_RTC_H */
/**
* @}

View File

@ -0,0 +1,52 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_RTC RTC Functions
* @brief PIOS interface for RTC tick
* @{
*
* @file pios_rtc_priv.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief ADC private 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
*/
#ifndef PIOS_RTC_PRIV_H
#define PIOS_RTC_PRIV_H
#include <pios.h>
#include <pios_stm32.h>
struct pios_rtc_cfg {
uint32_t clksrc;
uint32_t prescaler;
struct stm32_irq irq;
};
extern void PIOS_RTC_Init(const struct pios_rtc_cfg * cfg);
extern void PIOS_RTC_irq_handler(void);
#endif /* PIOS_RTC_PRIV_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,42 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_SBUS Futaba S.Bus receiver functions
* @{
*
* @file pios_sbus.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief Futaba S.Bus 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_SBUS_H
#define PIOS_SBUS_H
/* Global Types */
/* Public Functions */
#endif /* PIOS_SBUS_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,89 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_SBUS S.Bus Functions
* @brief PIOS interface to read and write from Futaba S.Bus port
* @{
*
* @file pios_sbus_priv.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief Futaba S.Bus Private structures.
* @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_SBUS_PRIV_H
#define PIOS_SBUS_PRIV_H
#include <pios.h>
#include <pios_stm32.h>
#include <pios_usart_priv.h>
/*
* S.Bus serial port settings:
* 100000bps inverted serial stream, 8 bits, even parity, 2 stop bits
* frame period is 7ms (HS) or 14ms (FS)
*
* Frame structure:
* 1 byte - 0x0f (start of frame byte)
* 22 bytes - channel data (11 bit/channel, 16 channels, LSB first)
* 1 byte - bit flags:
* 0x01 - digital channel 1,
* 0x02 - digital channel 2,
* 0x04 - lost frame flag,
* 0x08 - failsafe flag,
* 0xf0 - reserved
* 1 byte - 0x00 (end of frame byte)
*/
#define SBUS_FRAME_LENGTH (1+22+1+1)
#define SBUS_SOF_BYTE 0x0f
#define SBUS_EOF_BYTE 0x00
#define SBUS_FLAG_DG1 0x01
#define SBUS_FLAG_DG2 0x02
#define SBUS_FLAG_FL 0x04
#define SBUS_FLAG_FS 0x08
/*
* S.Bus protocol provides up to 16 analog and 2 digital channels.
* Only 8 channels are currently supported by the OpenPilot.
*/
#define SBUS_NUMBER_OF_CHANNELS 8
/*
* S.Bus configuration programmable invertor
*/
struct pios_sbus_cfg {
struct stm32_gpio inv;
void (*gpio_clk_func)(uint32_t periph, FunctionalState state);
uint32_t gpio_clk_periph;
BitAction gpio_inv_enable;
};
extern void PIOS_SBUS_irq_handler();
extern const struct pios_rcvr_driver pios_sbus_rcvr_driver;
extern void PIOS_SBUS_Init(const struct pios_sbus_cfg * cfg);
#endif /* PIOS_SBUS_PRIV_H */
/**
* @}
* @}
*/

View File

@ -34,11 +34,6 @@
/* Global Types */
/* Public Functions */
extern void PIOS_SPEKTRUM_Init(void);
extern uint8_t PIOS_SPEKTRUM_Bind(void);
extern int32_t PIOS_SPEKTRUM_Decode(uint8_t b);
extern int16_t PIOS_SPEKTRUM_Get(int8_t Channel);
extern void SPEKTRUM_IRQHandler(uint32_t usart_id);
#endif /* PIOS_SPEKTRUM_H */

View File

@ -36,18 +36,15 @@
#include <pios_usart_priv.h>
struct pios_spektrum_cfg {
const struct pios_usart_cfg * pios_usart_spektrum_cfg;
GPIO_InitTypeDef gpio_init;
struct stm32_gpio bind;
uint32_t remap; /* GPIO_Remap_* */
struct stm32_irq irq;
GPIO_TypeDef * port;
uint16_t pin;
};
extern void PIOS_SPEKTRUM_irq_handler();
extern uint8_t pios_spektrum_num_channels;
extern const struct pios_spektrum_cfg pios_spektrum_cfg;
extern const struct pios_rcvr_driver pios_spektrum_rcvr_driver;
extern void PIOS_SPEKTRUM_Init(const struct pios_spektrum_cfg * cfg, bool bind);
#endif /* PIOS_PWM_PRIV_H */

View File

@ -32,7 +32,7 @@
#define PIOS_STM32_H
struct stm32_irq {
void (*handler) (void);
void (*handler) (uint32_t);
uint32_t flags;
NVIC_InitTypeDef init;
};

View File

@ -48,26 +48,8 @@ struct pios_usart_cfg {
struct stm32_irq irq;
};
enum pios_usart_dev_magic {
PIOS_USART_DEV_MAGIC = 0x11223344,
};
struct pios_usart_dev {
enum pios_usart_dev_magic magic;
const struct pios_usart_cfg * cfg;
// align to 32-bit to try and provide speed improvement;
uint8_t rx_buffer[PIOS_USART_RX_BUFFER_SIZE] __attribute__ ((aligned(4)));
t_fifo_buffer rx;
// align to 32-bit to try and provide speed improvement;
uint8_t tx_buffer[PIOS_USART_TX_BUFFER_SIZE] __attribute__ ((aligned(4)));
t_fifo_buffer tx;
};
extern int32_t PIOS_USART_Init(uint32_t * usart_id, const struct pios_usart_cfg * cfg);
extern void PIOS_USART_IRQ_Handler(uint32_t usart_id);
extern const struct pios_usart_cfg * PIOS_USART_GetConfig(uint32_t usart_id);
#endif /* PIOS_USART_PRIV_H */

View File

@ -78,7 +78,9 @@
#include <pios_spi.h>
#include <pios_ppm.h>
#include <pios_pwm.h>
#include <pios_rcvr.h>
#include <pios_spektrum.h>
#include <pios_sbus.h>
#include <pios_usb_hid.h>
#include <pios_debug.h>
#include <pios_gpio.h>

View File

@ -90,7 +90,7 @@ static const struct pios_spi_cfg pios_spi_port_cfg =
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq =
{
.handler = PIOS_SPI_port_irq_handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
.init = {
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
@ -189,11 +189,11 @@ void PIOS_SPI_port_irq_handler(void)
extern void PIOS_ADC_handler(void);
void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler")));
// Remap the ADC DMA handler to this one
const struct pios_adc_cfg pios_adc_cfg = {
static const struct pios_adc_cfg pios_adc_cfg = {
.dma = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_ADC_DMA_Handler,
.handler = NULL,
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
.init = {
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
@ -245,10 +245,7 @@ void PIOS_ADC_handler() {
/*
* SERIAL USART
*/
void PIOS_USART_serial_irq_handler(void);
void USART1_IRQHandler() __attribute__ ((alias ("PIOS_USART_serial_irq_handler")));
const struct pios_usart_cfg pios_usart_serial_cfg =
static const struct pios_usart_cfg pios_usart_serial_cfg =
{
.regs = USART1,
.init =
@ -262,7 +259,7 @@ const struct pios_usart_cfg pios_usart_serial_cfg =
},
.irq =
{
.handler = PIOS_USART_serial_irq_handler,
.handler = NULL,
.init =
{
.NVIC_IRQChannel = USART1_IRQn,
@ -293,12 +290,6 @@ const struct pios_usart_cfg pios_usart_serial_cfg =
},
};
static uint32_t pios_usart_serial_id;
void PIOS_USART_serial_irq_handler(void)
{
PIOS_USART_IRQ_Handler(pios_usart_serial_id);
}
#endif /* PIOS_INCLUDE_USART */
// ***********************************************************************************
@ -334,6 +325,7 @@ void PIOS_Board_Init(void) {
// 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);
}

View File

@ -28,7 +28,7 @@
// Private constants
#define MAX_QUEUE_SIZE 20
#define STACK_SIZE configMINIMAL_STACK_SIZE
#define STACK_SIZE 96
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3)
#define MAX_UPDATE_PERIOD_MS 1000

View File

@ -70,7 +70,7 @@
</property>
<property name="minimumSize">
<size>
<width>400</width>
<width>300</width>
<height>300</height>
</size>
</property>
@ -82,14 +82,23 @@
<string>Basic settings</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_6">
<property name="margin">
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="spacing">
<number>3</number>
</property>
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout_6" stretch="1,1,1,0">
<layout class="QVBoxLayout" name="ccpmSettingsBox" stretch="0,1,1,0,0">
<item>
<widget class="QGroupBox" name="SwashplateBox_2">
<property name="sizePolicy">
@ -98,6 +107,17 @@
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>190</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>11</pointsize>
</font>
</property>
<property name="title">
<string>Outputs</string>
</property>
@ -114,7 +134,7 @@
<item row="2" column="1">
<widget class="QComboBox" name="ccpmTailChannel">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
@ -127,16 +147,21 @@
</property>
<property name="maximumSize">
<size>
<width>85</width>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>11</pointsize>
</font>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="ccpmEngineChannel">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
@ -149,10 +174,15 @@
</property>
<property name="maximumSize">
<size>
<width>85</width>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>11</pointsize>
</font>
</property>
</widget>
</item>
<item row="2" column="0">
@ -211,11 +241,22 @@
<item>
<widget class="QGroupBox" name="SwashplateBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Maximum">
<sizepolicy hsizetype="Maximum" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>190</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>11</pointsize>
</font>
</property>
<property name="title">
<string>Swashplate Outputs</string>
</property>
@ -263,7 +304,7 @@
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
@ -276,7 +317,7 @@
</property>
<property name="maximumSize">
<size>
<width>85</width>
<width>100</width>
<height>16777215</height>
</size>
</property>
@ -298,7 +339,7 @@
</property>
<property name="maximumSize">
<size>
<width>85</width>
<width>100</width>
<height>16777215</height>
</size>
</property>
@ -310,7 +351,7 @@
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
@ -323,7 +364,7 @@
</property>
<property name="maximumSize">
<size>
<width>85</width>
<width>100</width>
<height>16777215</height>
</size>
</property>
@ -357,7 +398,7 @@
<item row="5" column="1">
<widget class="QComboBox" name="ccpmSingleServo">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
@ -370,7 +411,7 @@
</property>
<property name="maximumSize">
<size>
<width>85</width>
<width>100</width>
<height>16777215</height>
</size>
</property>
@ -417,7 +458,7 @@
</size>
</property>
<property name="text">
<string>Single Servo</string>
<string>1st Servo</string>
</property>
</widget>
</item>
@ -437,7 +478,7 @@
</property>
<property name="maximumSize">
<size>
<width>85</width>
<width>100</width>
<height>16777215</height>
</size>
</property>
@ -513,6 +554,17 @@
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>190</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>11</pointsize>
</font>
</property>
<property name="title">
<string>Swashplate Servo Angles</string>
</property>
@ -689,6 +741,9 @@
<property name="text">
<string>Correction Angle</string>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="1">
@ -822,27 +877,326 @@
</widget>
</item>
<item>
<spacer name="verticalSpacer_5">
<widget class="QGroupBox" name="SwashplateBox_4">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>190</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>11</pointsize>
</font>
</property>
<property name="title">
<string>CCPM Options</string>
</property>
<layout class="QGridLayout" name="gridLayout_21">
<property name="horizontalSpacing">
<number>3</number>
</property>
<property name="verticalSpacing">
<number>2</number>
</property>
<property name="margin">
<number>3</number>
</property>
<item row="1" column="0">
<widget class="QCheckBox" name="ccpmCollectivePassthrough">
<property name="text">
<string>Collective Pass through</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QCheckBox" name="ccpmLinkRoll">
<property name="text">
<string>Link Roll/Pitch</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QCheckBox" name="ccpmLinkCyclic">
<property name="text">
<string>Link Cyclic/Collective</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="0">
<layout class="QHBoxLayout" name="ccpmCollectiveChannelBox">
<property name="sizeConstraint">
<enum>QLayout::SetNoConstraint</enum>
</property>
<item>
<widget class="QLabel" name="ccpmCollectiveChLabel">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>80</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>11</pointsize>
</font>
</property>
<property name="layoutDirection">
<enum>Qt::LeftToRight</enum>
</property>
<property name="text">
<string>Collective Ch</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="ccpmCollectiveChannel">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>90</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>0</height>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item row="0" column="1">
<item row="0" column="10">
<layout class="QVBoxLayout" name="ccpmSwashImageBox_2">
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<item>
<widget class="QGroupBox" name="ccpmSwashImageBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>1</horstretch>
<verstretch>1</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>600</width>
<height>600</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="baseSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
<property name="font">
<font>
<pointsize>11</pointsize>
</font>
</property>
<property name="title">
<string>Swashplate Layout</string>
</property>
<property name="alignment">
<set>Qt::AlignHCenter|Qt::AlignTop</set>
</property>
<property name="flat">
<bool>false</bool>
</property>
<property name="checkable">
<bool>false</bool>
</property>
<layout class="QGridLayout" name="gridLayout_10">
<property name="horizontalSpacing">
<number>3</number>
</property>
<property name="margin">
<number>3</number>
</property>
<item row="0" column="0">
<widget class="QSplitter" name="splitter_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<widget class="QGraphicsView" name="SwashplateImage">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>1</horstretch>
<verstretch>1</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>1000</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="baseSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
<property name="frameShape">
<enum>QFrame::Box</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="verticalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
<property name="horizontalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
<property name="backgroundBrush">
<brush brushstyle="DiagCrossPattern">
<color alpha="50">
<red>112</red>
<green>184</green>
<blue>138</blue>
</color>
</brush>
</property>
<property name="foregroundBrush">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>127</red>
<green>127</green>
<blue>127</blue>
</color>
</brush>
</property>
<property name="sceneRect">
<rectf>
<x>0.000000000000000</x>
<y>0.000000000000000</y>
<width>400.000000000000000</width>
<height>400.000000000000000</height>
</rectf>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="resizeAnchor">
<enum>QGraphicsView::AnchorViewCenter</enum>
</property>
</widget>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item row="0" column="3">
<layout class="QHBoxLayout" name="horizontalLayout_10">
<property name="sizeConstraint">
<enum>QLayout::SetNoConstraint</enum>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<item>
<widget class="QGroupBox" name="ccpmRevoMixingBox">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
@ -862,6 +1216,11 @@
<height>600</height>
</size>
</property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="title">
<string>REVO</string>
</property>
@ -908,7 +1267,7 @@
<item>
<widget class="QSlider" name="ccpmRevoSlider">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
@ -972,7 +1331,7 @@
</layout>
</widget>
</item>
<item row="0" column="2">
<item>
<widget class="QGroupBox" name="ccpmPitchMixingBox">
<property name="enabled">
<bool>true</bool>
@ -1129,143 +1488,476 @@
</layout>
</widget>
</item>
<item row="0" column="3">
<layout class="QVBoxLayout" name="verticalLayout_9">
<item>
<widget class="QGroupBox" name="ccpmSwashImageBox">
<widget class="QGroupBox" name="ccpmCollectiveScalingBox">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>1</horstretch>
<verstretch>1</verstretch>
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>200</width>
<height>200</height>
<width>50</width>
<height>100</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>600</width>
<width>50</width>
<height>600</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="baseSize">
<size>
<width>200</width>
<height>200</height>
</size>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="title">
<string>Swashplate Layout</string>
</property>
<property name="alignment">
<set>Qt::AlignHCenter|Qt::AlignTop</set>
</property>
<property name="flat">
<bool>false</bool>
</property>
<property name="checkable">
<bool>false</bool>
</property>
<layout class="QGridLayout" name="gridLayout_10">
<property name="horizontalSpacing">
<number>3</number>
</property>
<property name="margin">
<number>3</number>
</property>
<item row="0" column="0">
<widget class="QSplitter" name="splitter_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<widget class="QGraphicsView" name="SwashplateImage">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>1</horstretch>
<verstretch>1</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>500</width>
<height>500</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="baseSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
<property name="frameShape">
<enum>QFrame::Box</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="verticalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
<property name="horizontalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
<property name="backgroundBrush">
<brush brushstyle="DiagCrossPattern">
<color alpha="50">
<red>112</red>
<green>184</green>
<blue>138</blue>
</color>
</brush>
</property>
<property name="foregroundBrush">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>127</red>
<green>127</green>
<blue>127</blue>
</color>
</brush>
</property>
<property name="sceneRect">
<rectf>
<x>0.000000000000000</x>
<y>0.000000000000000</y>
<width>400.000000000000000</width>
<height>400.000000000000000</height>
</rectf>
<string>Collective</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="resizeAnchor">
<enum>QGraphicsView::AnchorViewCenter</enum>
<layout class="QVBoxLayout" name="verticalLayout_12">
<property name="spacing">
<number>0</number>
</property>
<property name="margin">
<number>3</number>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_11">
<item>
<spacer name="horizontalSpacer_15">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>25</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QSlider" name="ccpmCollectiveScale">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>5</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_16">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>25</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QSpinBox" name="ccpmCollectiveScaleBox">
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>5</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="ccpmCyclicScalingBox">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>100</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>50</width>
<height>600</height>
</size>
</property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="title">
<string>Cyclic</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="checkable">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_7">
<property name="spacing">
<number>0</number>
</property>
<property name="margin">
<number>3</number>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_7">
<item>
<spacer name="horizontalSpacer_9">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>25</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QSlider" name="ccpmCyclicScale">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>5</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_10">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>25</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QSpinBox" name="ccpmCyclicScaleBox">
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>5</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="ccpmPitchScalingBox">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>100</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>50</width>
<height>600</height>
</size>
</property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="title">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<layout class="QVBoxLayout" name="verticalLayout_13">
<property name="spacing">
<number>0</number>
</property>
<property name="margin">
<number>3</number>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_12">
<item>
<spacer name="horizontalSpacer_17">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>25</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QSlider" name="ccpmPitchScale">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>5</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_18">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>25</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QSpinBox" name="ccpmPitchScaleBox">
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>5</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="ccpmRollScalingBox">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>100</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>50</width>
<height>600</height>
</size>
</property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="title">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<layout class="QVBoxLayout" name="verticalLayout_10">
<property name="spacing">
<number>0</number>
</property>
<property name="margin">
<number>3</number>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_8">
<item>
<spacer name="horizontalSpacer_11">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>25</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QSlider" name="ccpmRollScale">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>5</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_12">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>25</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QSpinBox" name="ccpmRollScaleBox">
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>5</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
</layout>
@ -1777,14 +2469,14 @@
</property>
<property name="minimumSize">
<size>
<width>200</width>
<height>200</height>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>500</width>
<height>500</height>
<width>1000</width>
<height>1000</height>
</size>
</property>
<property name="sizeIncrement">
@ -3047,12 +3739,12 @@
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>283</x>
<y>400</y>
<x>261</x>
<y>496</y>
</hint>
<hint type="destinationlabel">
<x>294</x>
<y>550</y>
<x>269</x>
<y>546</y>
</hint>
</hints>
</connection>
@ -3063,12 +3755,12 @@
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>294</x>
<y>550</y>
<x>269</x>
<y>546</y>
</hint>
<hint type="destinationlabel">
<x>283</x>
<y>482</y>
<x>261</x>
<y>511</y>
</hint>
</hints>
</connection>
@ -3079,12 +3771,12 @@
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>241</x>
<y>550</y>
<x>216</x>
<y>546</y>
</hint>
<hint type="destinationlabel">
<x>230</x>
<y>484</y>
<x>208</x>
<y>511</y>
</hint>
</hints>
</connection>
@ -3095,12 +3787,12 @@
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>230</x>
<y>313</y>
<x>208</x>
<y>412</y>
</hint>
<hint type="destinationlabel">
<x>241</x>
<y>550</y>
<x>216</x>
<y>546</y>
</hint>
</hints>
</connection>
@ -3127,8 +3819,8 @@
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>257</x>
<y>535</y>
<x>301</x>
<y>546</y>
</hint>
<hint type="destinationlabel">
<x>277</x>
@ -3136,5 +3828,133 @@
</hint>
</hints>
</connection>
<connection>
<sender>ccpmCollectiveScaleBox</sender>
<signal>valueChanged(int)</signal>
<receiver>ccpmCollectiveScale</receiver>
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>296</x>
<y>534</y>
</hint>
<hint type="destinationlabel">
<x>306</x>
<y>480</y>
</hint>
</hints>
</connection>
<connection>
<sender>ccpmCollectiveScale</sender>
<signal>sliderMoved(int)</signal>
<receiver>ccpmCollectiveScaleBox</receiver>
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>308</x>
<y>328</y>
</hint>
<hint type="destinationlabel">
<x>292</x>
<y>534</y>
</hint>
</hints>
</connection>
<connection>
<sender>ccpmCyclicScale</sender>
<signal>sliderMoved(int)</signal>
<receiver>ccpmCyclicScaleBox</receiver>
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>358</x>
<y>306</y>
</hint>
<hint type="destinationlabel">
<x>355</x>
<y>538</y>
</hint>
</hints>
</connection>
<connection>
<sender>ccpmCyclicScaleBox</sender>
<signal>valueChanged(int)</signal>
<receiver>ccpmCyclicScale</receiver>
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>341</x>
<y>538</y>
</hint>
<hint type="destinationlabel">
<x>351</x>
<y>376</y>
</hint>
</hints>
</connection>
<connection>
<sender>ccpmPitchScale</sender>
<signal>sliderMoved(int)</signal>
<receiver>ccpmPitchScaleBox</receiver>
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>417</x>
<y>306</y>
</hint>
<hint type="destinationlabel">
<x>406</x>
<y>531</y>
</hint>
</hints>
</connection>
<connection>
<sender>ccpmPitchScaleBox</sender>
<signal>valueChanged(int)</signal>
<receiver>ccpmPitchScale</receiver>
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>394</x>
<y>531</y>
</hint>
<hint type="destinationlabel">
<x>408</x>
<y>302</y>
</hint>
</hints>
</connection>
<connection>
<sender>ccpmRollScaleBox</sender>
<signal>valueChanged(int)</signal>
<receiver>ccpmRollScale</receiver>
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>455</x>
<y>529</y>
</hint>
<hint type="destinationlabel">
<x>458</x>
<y>466</y>
</hint>
</hints>
</connection>
<connection>
<sender>ccpmRollScale</sender>
<signal>sliderMoved(int)</signal>
<receiver>ccpmRollScaleBox</receiver>
<slot>setValue(int)</slot>
<hints>
<hint type="sourcelabel">
<x>461</x>
<y>388</y>
</hint>
<hint type="destinationlabel">
<x>474</x>
<y>533</y>
</hint>
</hints>
</connection>
</connections>
</ui>

View File

@ -374,7 +374,7 @@ void ConfigAirframeWidget::resetFwMixer()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve1"));
resetMixer(m_aircraft->fixedWingThrottle, field->getNumElements());
resetMixer(m_aircraft->fixedWingThrottle, field->getNumElements(),1);
}
/**
@ -384,7 +384,7 @@ void ConfigAirframeWidget::resetMrMixer()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve1"));
resetMixer(m_aircraft->multiThrottleCurve, field->getNumElements());
resetMixer(m_aircraft->multiThrottleCurve, field->getNumElements(),0.9);
}
/**
@ -394,7 +394,7 @@ void ConfigAirframeWidget::resetCt1Mixer()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve1"));
resetMixer(m_aircraft->customThrottle1Curve, field->getNumElements());
resetMixer(m_aircraft->customThrottle1Curve, field->getNumElements(),1);
}
/**
@ -404,21 +404,17 @@ void ConfigAirframeWidget::resetCt2Mixer()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve2"));
resetMixer(m_aircraft->customThrottle2Curve, field->getNumElements());
resetMixer(m_aircraft->customThrottle2Curve, field->getNumElements(),1);
}
/**
Resets a mixer curve
*/
void ConfigAirframeWidget::resetMixer(MixerCurveWidget *mixer, int numElements)
void ConfigAirframeWidget::resetMixer(MixerCurveWidget *mixer, int numElements, double maxvalue)
{
QList<double> curveValues;
for (double i=0; i<numElements; i++) {
curveValues.append(i/(numElements-1));
}
// Setup all Throttle1 curves for all types of airframes
mixer->initCurve(curveValues);
mixer->initLinearCurve((quint32)numElements,maxvalue);
}
/**
@ -484,18 +480,29 @@ void ConfigAirframeWidget::refreshValues()
// 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) {
for (double i=0; i<field->getNumElements(); i++) {
curveValues.append(i/(field->getNumElements()-1));
m_aircraft->multiThrottleCurve->initLinearCurve(field->getNumElements(),(double)1);
m_aircraft->fixedWingThrottle->initLinearCurve(field->getNumElements(),(double)1);
}
} else {
else {
double temp=0;
double value;
for (unsigned int i=0; i < field->getNumElements(); i++) {
curveValues.append(field->getValue(i).toDouble());
value=field->getValue(i).toDouble();
temp+=value;
curveValues.append(value);
}
if(temp==0)
{
m_aircraft->multiThrottleCurve->initLinearCurve(field->getNumElements(),0.9);;
m_aircraft->fixedWingThrottle->initLinearCurve(field->getNumElements(),(double)1);
}
else
{
m_aircraft->multiThrottleCurve->initCurve(curveValues);
m_aircraft->fixedWingThrottle->initCurve(curveValues);
}
}
// Setup all Throttle1 curves for all types of airframes
m_aircraft->fixedWingThrottle->initCurve(curveValues);
m_aircraft->multiThrottleCurve->initCurve(curveValues);
// Load the Settings for fixed wing frames:
if (frameType.startsWith("FixedWing")) {
// Then retrieve how channels are setup
@ -1754,31 +1761,32 @@ void ConfigAirframeWidget::updateCustomAirframeUI()
// 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) {
for (double i=0; i<field->getNumElements(); i++) {
curveValues.append(i/(field->getNumElements()-1));
}
m_aircraft->customThrottle1Curve->initLinearCurve(field->getNumElements(),(double)1);
} else {
double temp=0;
double value;
for (unsigned int i=0; i < field->getNumElements(); i++) {
curveValues.append(field->getValue(i).toDouble());
}
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);
}
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) {
for (double i=0; i<field->getNumElements(); i++) {
curveValues.append(i/(field->getNumElements()-1));
}
m_aircraft->customThrottle2Curve->initLinearCurve(field->getNumElements(),(double)1);
} else {
for (unsigned int i=0; i < field->getNumElements(); i++) {
curveValues.append(field->getValue(i).toDouble());
}
}
m_aircraft->customThrottle2Curve->initCurve(curveValues);
}
// Retrieve Feed Forward:
field = obj->getField(QString("FeedForward"));
m_aircraft->customFFSlider->setValue(field->getDouble()*100);

View File

@ -61,7 +61,7 @@ private:
virtual void enableControls(bool enable);
void resetField(UAVObjectField * field);
void resetMixer (MixerCurveWidget *mixer, int numElements);
void resetMixer (MixerCurveWidget *mixer, int numElements, double maxvalue);
void resetActuators();
//void setMixerChannel(int channelNumber, bool channelIsMotor, QList<double> vector);
void setupQuadMotor(int channel, double roll, double pitch, double yaw);

View File

@ -25,6 +25,7 @@
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "configccpmwidget.h"
#include "mixersettings.h"
#include <QDebug>
#include <QStringList>
@ -32,6 +33,7 @@
#include <QtGui/QTextEdit>
#include <QtGui/QVBoxLayout>
#include <QtGui/QPushButton>
#include <QBrush>
#include <math.h>
#include <QMessageBox>
@ -41,11 +43,14 @@
ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(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();
@ -55,12 +60,12 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
m_ccpm->SwashplateImage->setScene(new QGraphicsScene(this));
m_ccpm->SwashLvlSwashplateImage->setScene(m_ccpm->SwashplateImage->scene());
m_ccpm->SwashLvlSwashplateImage->setSceneRect(-50,-30,500,500);
m_ccpm->SwashLvlSwashplateImage->scale(.85,.85);
m_ccpm->SwashLvlSwashplateImage->setSceneRect(-50,-50,500,500);
//m_ccpm->SwashLvlSwashplateImage->scale(.85,.85);
//m_ccpm->SwashplateImage->setSceneRect(SwashplateImg->boundingRect());
m_ccpm->SwashplateImage->setSceneRect(-50,-30,500,500);
m_ccpm->SwashplateImage->scale(.85,.85);
//m_ccpm->SwashplateImage->scale(.85,.85);
@ -72,9 +77,10 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
SwashplateImg->setSharedRenderer(renderer);
SwashplateImg->setElementId("Swashplate");
SwashplateImg->setObjectName("Swashplate");
//SwashplateImg->setScale(0.75);
m_ccpm->SwashplateImage->scene()->addItem(SwashplateImg);
QFont serifFont("Times", 16, QFont::Bold);
QFont serifFont("Times", 24, QFont::Bold);
QPen pen; // creates a default pen
pen.setStyle(Qt::DotLine);
@ -83,6 +89,19 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
pen.setCapStyle(Qt::RoundCap);
pen.setJoinStyle(Qt::RoundJoin);
QBrush brush(Qt::darkBlue);
QPen pen2; // creates a default pen
//pen2.setStyle(Qt::DotLine);
pen2.setWidth(1);
pen2.setBrush(Qt::blue);
//pen2.setCapStyle(Qt::RoundCap);
//pen2.setJoinStyle(Qt::RoundJoin);
//brush.setStyle(Qt::RadialGradientPattern);
QList<QString> ServoNames;
ServoNames << "ServoW" << "ServoX" << "ServoY" << "ServoZ" ;
@ -96,12 +115,18 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
m_ccpm->SwashplateImage->scene()->addItem(Servos[i]);
ServosText[i] = new QGraphicsTextItem();
ServosText[i]->setDefaultTextColor(Qt::red);
ServosText[i]->setDefaultTextColor(Qt::yellow);
ServosText[i]->setPlainText(QString("-"));
ServosText[i]->setFont(serifFont);
ServosTextCircles[i] = new QGraphicsEllipseItem(1,1,30,30);
ServosTextCircles[i]->setBrush(brush);
ServosTextCircles[i]->setPen(pen2);
m_ccpm->SwashplateImage->scene()->addItem(ServosTextCircles[i]);
m_ccpm->SwashplateImage->scene()->addItem(ServosText[i]);
SwashLvlSpinBoxes[i] = new QSpinBox(m_ccpm->SwashLvlSwashplateImage); // use QGraphicsView
m_ccpm->SwashLvlSwashplateImage->scene()->addWidget(SwashLvlSpinBoxes[i]);
//SwashLvlSpinBoxes[i]->move(i*50+50,20);
@ -172,7 +197,10 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
QStringList channels;
channels << "Channel1" << "Channel2" <<
"Channel3" << "Channel4" << "Channel5" << "Channel6" << "Channel7" << "Channel8" << "None" ;
"Channel3" << "Channel4" << "Channel5" << "Channel6" << "Channel7" << "Channel8" ;
m_ccpm->ccpmCollectiveChannel->addItems(channels);
m_ccpm->ccpmCollectiveChannel->setCurrentIndex(8);
channels << "None" ;
m_ccpm->ccpmEngineChannel->addItems(channels);
m_ccpm->ccpmEngineChannel->setCurrentIndex(8);
m_ccpm->ccpmTailChannel->addItems(channels);
@ -187,7 +215,7 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
QStringList Types;
Types << "CCPM 2 Servo 90º" << "CCPM 3 Servo 120º" << "CCPM 3 Servo 140º" << "FP 2 Servo 90º" << "Custom - User Angles" << "Custom - Advanced Settings" ;
Types << "CCPM 2 Servo 90º" << "CCPM 3 Servo 90º" << "CCPM 4 Servo 90º" << "CCPM 3 Servo 120º" << "CCPM 3 Servo 140º" << "FP 2 Servo 90º" << "Custom - User Angles" << "Custom - Advanced Settings" ;
m_ccpm->ccpmType->addItems(Types);
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - 1);
requestccpmUpdate();
@ -197,6 +225,8 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
//disable changing number of points in curves until UAVObjects have more than 5
m_ccpm->NumCurvePoints->setEnabled(0);
UpdateType();
//connect(m_ccpm->saveccpmToSD, SIGNAL(clicked()), this, SLOT(saveccpmUpdate()));
@ -237,7 +267,13 @@ 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()));
ccpmSwashplateRedraw();
// connect(parent, SIGNAL(autopilotConnected()),this, SLOT(requestccpmUpdate()));
}
@ -249,10 +285,12 @@ ConfigccpmWidget::~ConfigccpmWidget()
void ConfigccpmWidget::UpdateType()
{
int TypeInt,SingleServoIndex;
int TypeInt,SingleServoIndex,NumServosDefined;
QString TypeText;
double AdjustmentAngle=0;
UpdatCCPMOptionsFromUI();
SetUIComponentVisibilities();
TypeInt = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1;
TypeText = m_ccpm->ccpmType->currentText();
@ -266,7 +304,7 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmAngleX->setEnabled(TypeInt==1);
m_ccpm->ccpmAngleY->setEnabled(TypeInt==1);
m_ccpm->ccpmAngleZ->setEnabled(TypeInt==1);
m_ccpm->ccpmCorrectionAngle->setEnabled(TypeInt==1);
m_ccpm->ccpmCorrectionAngle->setEnabled(TypeInt!=0);
m_ccpm->ccpmServoWChannel->setEnabled(TypeInt>0);
m_ccpm->ccpmServoXChannel->setEnabled(TypeInt>0);
@ -289,6 +327,7 @@ void ConfigccpmWidget::UpdateType()
//m_ccpm->customThrottleCurve2Value->setVisible(1);
//m_ccpm->label_41->setVisible(1);
NumServosDefined=4;
//set values for pre defined heli types
if (TypeText.compare(QString("CCPM 2 Servo 90º"), Qt::CaseInsensitive)==0)
{
@ -302,7 +341,33 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
m_ccpm->ccpmServoYChannel->setEnabled(0);
m_ccpm->ccpmServoZChannel->setEnabled(0);
m_ccpm->ccpmCorrectionAngle->setValue(0);
//m_ccpm->ccpmCorrectionAngle->setValue(0);
NumServosDefined=2;
}
if (TypeText.compare(QString("CCPM 3 Servo 90º"), Qt::CaseInsensitive)==0)
{
m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0);
m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360));
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->setEnabled(0);
//m_ccpm->ccpmCorrectionAngle->setValue(0);
NumServosDefined=3;
}
if (TypeText.compare(QString("CCPM 4 Servo 90º"), Qt::CaseInsensitive)==0)
{
m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0);
m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360));
m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 180,360));
m_ccpm->ccpmAngleZ->setValue(fmod(AdjustmentAngle + 270,360));
//m_ccpm->ccpmCorrectionAngle->setValue(0);
m_ccpm->ccpmSingleServo->setEnabled(0);
m_ccpm->ccpmSingleServo->setCurrentIndex(0);
NumServosDefined=4;
}
if (TypeText.compare(QString("CCPM 3 Servo 120º"), Qt::CaseInsensitive)==0)
@ -314,7 +379,8 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmAngleZ->setEnabled(0);
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
m_ccpm->ccpmServoZChannel->setEnabled(0);
m_ccpm->ccpmCorrectionAngle->setValue(0);
//m_ccpm->ccpmCorrectionAngle->setValue(0);
NumServosDefined=3;
}
if (TypeText.compare(QString("CCPM 3 Servo 140º"), Qt::CaseInsensitive)==0)
@ -326,7 +392,8 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmAngleZ->setEnabled(0);
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
m_ccpm->ccpmServoZChannel->setEnabled(0);
m_ccpm->ccpmCorrectionAngle->setValue(0);
//m_ccpm->ccpmCorrectionAngle->setValue(0);
NumServosDefined=3;
}
if (TypeText.compare(QString("FP 2 Servo 90º"), Qt::CaseInsensitive)==0)
@ -341,7 +408,7 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
m_ccpm->ccpmServoYChannel->setEnabled(0);
m_ccpm->ccpmServoZChannel->setEnabled(0);
m_ccpm->ccpmCorrectionAngle->setValue(0);
//m_ccpm->ccpmCorrectionAngle->setValue(0);
m_ccpm->ccpmCollectivespinBox->setEnabled(0);
m_ccpm->ccpmCollectiveSlider->setEnabled(0);
@ -353,8 +420,29 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->PitchCurve->setVisible(0);
//m_ccpm->customThrottleCurve2Value->setVisible(0);
//m_ccpm->label_41->setVisible(0);
NumServosDefined=2;
}
//set the visibility of the swashplate servo selection boxes
m_ccpm->ccpmServoWLabel->setVisible(NumServosDefined>=1);
m_ccpm->ccpmServoXLabel->setVisible(NumServosDefined>=2);
m_ccpm->ccpmServoYLabel->setVisible(NumServosDefined>=3);
m_ccpm->ccpmServoZLabel->setVisible(NumServosDefined>=4);
m_ccpm->ccpmServoWChannel->setVisible(NumServosDefined>=1);
m_ccpm->ccpmServoXChannel->setVisible(NumServosDefined>=2);
m_ccpm->ccpmServoYChannel->setVisible(NumServosDefined>=3);
m_ccpm->ccpmServoZChannel->setVisible(NumServosDefined>=4);
//set the visibility of the swashplate angle selection boxes
m_ccpm->ccpmServoWLabel_2->setVisible(NumServosDefined>=1);
m_ccpm->ccpmServoXLabel_2->setVisible(NumServosDefined>=2);
m_ccpm->ccpmServoYLabel_2->setVisible(NumServosDefined>=3);
m_ccpm->ccpmServoZLabel_2->setVisible(NumServosDefined>=4);
m_ccpm->ccpmAngleW->setVisible(NumServosDefined>=1);
m_ccpm->ccpmAngleX->setVisible(NumServosDefined>=2);
m_ccpm->ccpmAngleY->setVisible(NumServosDefined>=3);
m_ccpm->ccpmAngleZ->setVisible(NumServosDefined>=4);
m_ccpm->ccpmAdvancedSettingsTable->resizeColumnsToContents();
for (int i=0;i<6;i++) {
@ -362,6 +450,9 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmAdvancedSettingsTable->verticalHeader()->width())/6);
}
//update UI
ccpmSwashplateUpdate();
@ -372,12 +463,7 @@ void ConfigccpmWidget::UpdateType()
*/
void ConfigccpmWidget::resetMixer(MixerCurveWidget *mixer, int numElements)
{
QList<double> curveValues;
for (double i=0; i<numElements; i++) {
curveValues.append(i/(numElements-1));
}
// Setup all Throttle1 curves for all types of airframes
mixer->initCurve(curveValues);
mixer->initLinearCurve(numElements,(double)1);
}
void ConfigccpmWidget::UpdateCurveWidgets()
@ -660,17 +746,43 @@ void ConfigccpmWidget::GenerateCurve()
void ConfigccpmWidget::ccpmSwashplateRedraw()
{
double angle[CCPM_MAX_SWASH_SERVOS],CorrectionAngle,x,y,w,h,radius,CenterX,CenterY;
int used[CCPM_MAX_SWASH_SERVOS],i;
int used[CCPM_MAX_SWASH_SERVOS],defined[CCPM_MAX_SWASH_SERVOS],i;
QRectF bounds;
QRect size;
double scale,xscale,yscale;
size = m_ccpm->SwashplateImage->rect();
xscale=size.width();
yscale=size.height();
scale=xscale;
if (yscale<scale)scale=yscale;
scale/=460.00;
m_ccpm->SwashplateImage->resetTransform ();
m_ccpm->SwashplateImage->scale(scale,scale);
size = m_ccpm->SwashLvlSwashplateImage->rect();
xscale=size.width();
yscale=size.height();
scale=xscale;
if (yscale<scale)scale=yscale;
scale/=590.00;
m_ccpm->SwashLvlSwashplateImage->resetTransform ();
m_ccpm->SwashLvlSwashplateImage->scale(scale,scale);
CorrectionAngle=m_ccpm->ccpmCorrectionAngle->value();
//CenterX=m_ccpm->SwashplateImage->scene()->sceneRect().center().x();
// CenterY=m_ccpm->SwashplateImage->scene()->sceneRect().center().y();
CenterX=200;
CenterY=220;
CenterY=200;
SwashplateImg->setPos(CenterX-200,CenterY-200);
bounds=SwashplateImg->boundingRect();
SwashplateImg->setPos(CenterX-bounds.width()/2,CenterY-bounds.height()/2);
defined[0]=(m_ccpm->ccpmServoWChannel->isEnabled());
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()));
@ -689,12 +801,29 @@ void ConfigccpmWidget::ccpmSwashplateRedraw()
Servos[i]->setPos(x, y);
Servos[i]->setVisible(used[i]!=0);
radius=170;
x=CenterX-(radius*sin(angle[i]))-10.00;
y=CenterY+(radius*cos(angle[i]))-10.00;
radius=150;
bounds=ServosText[i]->boundingRect();
x=CenterX-(radius*sin(angle[i]))-bounds.width()/2;
y=CenterY+(radius*cos(angle[i]))-bounds.height()/2;
ServosText[i]->setPos(x, y);
ServosText[i]->setVisible(used[i]!=0);
if (bounds.width()>bounds.height())
{
bounds.setHeight(bounds.width());
}
else
{
bounds.setWidth(bounds.height());
}
x=CenterX-(radius*sin(angle[i]))-bounds.width()/2;
y=CenterY+(radius*cos(angle[i]))-bounds.height()/2;
ServosTextCircles[i]->setRect(bounds);
ServosTextCircles[i]->setPos(x, y);
ServosTextCircles[i]->setVisible(used[i]!=0);
w=SwashLvlSpinBoxes[i]->width()/2;
h=SwashLvlSpinBoxes[i]->height()/2;
radius = (215.00+w+h);
@ -707,7 +836,7 @@ void ConfigccpmWidget::ccpmSwashplateRedraw()
x=CenterX-(radius*sin(angle[i]));
y=CenterY+(radius*cos(angle[i]));
ServoLines[i]->setLine(CenterX,CenterY,x,y);
ServoLines[i]->setVisible(used[i]!=0);
ServoLines[i]->setVisible(defined[i]!=0);
}
//m_ccpm->SwashplateImage->centerOn (CenterX, CenterY);
@ -718,22 +847,104 @@ void ConfigccpmWidget::ccpmSwashplateRedraw()
void ConfigccpmWidget::ccpmSwashplateUpdate()
{
ccpmSwashplateRedraw();
SetUIComponentVisibilities();
UpdateMixer();
}
void ConfigccpmWidget::ccpmChannelCheck()
{
if((m_ccpm->ccpmServoWChannel->currentIndex()==8)&&(m_ccpm->ccpmServoWChannel->isEnabled()))
{
m_ccpm->ccpmServoWLabel->setText("<font color=red>Servo W</font>");
}
else
{
m_ccpm->ccpmServoWLabel->setText("<font color=black>Servo W</font>");
}
if((m_ccpm->ccpmServoXChannel->currentIndex()==8)&&(m_ccpm->ccpmServoXChannel->isEnabled()))
{
m_ccpm->ccpmServoXLabel->setText("<font color=red>Servo X</font>");
}
else
{
m_ccpm->ccpmServoXLabel->setText("<font color=black>Servo X</font>");
}
if((m_ccpm->ccpmServoYChannel->currentIndex()==8)&&(m_ccpm->ccpmServoYChannel->isEnabled()))
{
m_ccpm->ccpmServoYLabel->setText("<font color=red>Servo Y</font>");
}
else
{
m_ccpm->ccpmServoYLabel->setText("<font color=black>Servo Y</font>");
}
if((m_ccpm->ccpmServoZChannel->currentIndex()==8)&&(m_ccpm->ccpmServoZChannel->isEnabled()))
{
m_ccpm->ccpmServoZLabel->setText("<font color=red>Servo Z</font>");
}
else
{
m_ccpm->ccpmServoZLabel->setText("<font color=black>Servo Z</font>");
}
if((m_ccpm->ccpmEngineChannel->currentIndex()==8)&&(m_ccpm->ccpmEngineChannel->isEnabled()))
{
m_ccpm->ccpmEngineLabel->setText("<font color=red>Engine</font>");
}
else
{
m_ccpm->ccpmEngineLabel->setText("<font color=black>Engine</font>");
}
if((m_ccpm->ccpmTailChannel->currentIndex()==8)&&(m_ccpm->ccpmTailChannel->isEnabled()))
{
m_ccpm->ccpmTailLabel->setText("<font color=red>Tail Rotor</font>");
}
else
{
m_ccpm->ccpmTailLabel->setText("<font color=black>Tail Rotor</font>");
}
}
void ConfigccpmWidget::UpdateMixer()
{
int i,j,Type,ThisEnable[6];
float CollectiveConstant,CorrectionAngle,ThisAngle[6];
bool useCCPM;
bool useCyclic;
int i,j,ThisEnable[6];
float CollectiveConstant,PitchConstant,RollConstant,ThisAngle[6];
//QTableWidgetItem *newItem;// = new QTableWidgetItem();
QString Channel;
Type = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1;
CollectiveConstant=m_ccpm->ccpmCollectiveSlider->value()/100.0;
CorrectionAngle=m_ccpm->ccpmCorrectionAngle->value();
ccpmChannelCheck();
//Type = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1;
//CollectiveConstant=m_ccpm->ccpmCollectiveSlider->value()/100.0;
//CorrectionAngle=m_ccpm->ccpmCorrectionAngle->value();
UpdatCCPMOptionsFromUI();
useCCPM = !(GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState);
useCyclic = GUIConfigData.heli.ccpmLinkRollState;
if (Type>0)
CollectiveConstant = (float)GUIConfigData.heli.SliderValue0 / 100.00;
if (useCCPM)
{//cyclic = 1 - collective
PitchConstant = 1-CollectiveConstant;
RollConstant = PitchConstant;
}
else
{
PitchConstant = (float)GUIConfigData.heli.SliderValue1 / 100.00;;
if (useCyclic)
{
RollConstant = PitchConstant;
}
else
{
RollConstant = (float)GUIConfigData.heli.SliderValue2 / 100.00;;
}
}
if (GUIConfigData.heli.SwasplateType>0)
{//not advanced settings
//get the channel data from the ui
MixerChannelData[0] = m_ccpm->ccpmEngineChannel->currentIndex();
@ -797,8 +1008,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*(1-CollectiveConstant)*sin((180+CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Roll
m_ccpm->ccpmAdvancedSettingsTable->item(i,4)->setText(QString("%1").arg((int)(127.0*(1-CollectiveConstant)*cos((CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Pitch
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,5)->setText(QString("%1").arg(0));//Yaw
}
@ -827,6 +1038,140 @@ 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::UpdatCCPMOptionsFromUI()
{
bool useCCPM;
bool useCyclic;
if (updatingFromHardware) return;
//get the user options
//swashplate config
GUIConfigData.heli.SwasplateType = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1;
GUIConfigData.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;
//correction angle
GUIConfigData.heli.CorrectionAngle = m_ccpm->ccpmCorrectionAngle->value();
//CollectiveChannel
GUIConfigData.heli.CollectiveChannel = m_ccpm->ccpmCollectiveChannel->currentIndex();
//update sliders
if (useCCPM)
{
GUIConfigData.heli.SliderValue0 = m_ccpm->ccpmCollectiveSlider->value();
}
else
{
GUIConfigData.heli.SliderValue0 = m_ccpm->ccpmCollectiveScale->value();
}
if (useCyclic)
{
GUIConfigData.heli.SliderValue1 = m_ccpm->ccpmCyclicScale->value();
}
else
{
GUIConfigData.heli.SliderValue1 = m_ccpm->ccpmPitchScale->value();
}
GUIConfigData.heli.SliderValue2 = m_ccpm->ccpmRollScale->value();
//GUIConfigData.heli.RevoSlider = m_ccpm->ccpmREVOScale->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();
}
void ConfigccpmWidget::UpdatCCPMUIFromOptions()
{
//swashplate config
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - (GUIConfigData.heli.SwasplateType +1));
m_ccpm->ccpmSingleServo->setCurrentIndex(GUIConfigData.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);
//correction angle
m_ccpm->ccpmCorrectionAngle->setValue(GUIConfigData.heli.CorrectionAngle);
//CollectiveChannel
m_ccpm->ccpmCollectiveChannel->setCurrentIndex(GUIConfigData.heli.CollectiveChannel);
//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->ccpmREVOScale->setValue(GUIConfigData.heli.RevoSlider);
//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);
}
void ConfigccpmWidget::SetUIComponentVisibilities()
{
UpdatCCPMOptionsFromUI();
//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->ccpmCollectiveChLabel->setVisible(GUIConfigData.heli.ccpmCollectivePassthroughState);
m_ccpm->ccpmCollectiveChannel->setVisible(GUIConfigData.heli.ccpmCollectivePassthroughState);
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->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->ccpmLinkRoll->setVisible(1);
}
}
/**
Request the current value of the SystemSettings which holds the ccpm type
*/
@ -843,12 +1188,22 @@ void ConfigccpmWidget::requestccpmUpdate()
int isCCPM=0;
if (SwashLvlConfigurationInProgress)return;
if (updatingToHardware)return;
updatingFromHardware=TRUE;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
int i,j;
UAVObjectField *field;
UAVDataObject* obj;
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
field = obj->getField(QString("GUIConfigData"));
GUIConfigData.UAVObject[0]=field->getValue(0).toUInt();
GUIConfigData.UAVObject[1]=field->getValue(1).toUInt();
UpdatCCPMUIFromOptions();
obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
@ -933,6 +1288,7 @@ void ConfigccpmWidget::requestccpmUpdate()
//just call it user angles for now....
/*
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("Custom - User Angles"));
if (NumServos>1)
@ -965,6 +1321,8 @@ void ConfigccpmWidget::requestccpmUpdate()
}
HeadRotation=0;
HeadRotation=m_ccpm->ccpmSingleServo->currentIndex();
//calculate the angles
for(j=0;j<NumServos;j++)
{
@ -981,7 +1339,7 @@ void ConfigccpmWidget::requestccpmUpdate()
}
//set the head rotation
m_ccpm->ccpmSingleServo->setCurrentIndex(HeadRotation);
//m_ccpm->ccpmSingleServo->setCurrentIndex(HeadRotation);
//calculate the un rotated angles
for(j=0;j<NumServos;j++)
@ -1001,15 +1359,19 @@ void ConfigccpmWidget::requestccpmUpdate()
}
m_ccpm->ccpmAngleW->setValue(ServoAngles[SortAngles[0]]);
m_ccpm->ccpmAngleX->setValue(ServoAngles[SortAngles[1]]);
m_ccpm->ccpmAngleY->setValue(ServoAngles[SortAngles[2]]);
m_ccpm->ccpmAngleZ->setValue(ServoAngles[SortAngles[3]]);
//m_ccpm->ccpmAngleW->setValue(ServoAngles[SortAngles[0]]);
//m_ccpm->ccpmAngleX->setValue(ServoAngles[SortAngles[1]]);
//m_ccpm->ccpmAngleY->setValue(ServoAngles[SortAngles[2]]);
//m_ccpm->ccpmAngleZ->setValue(ServoAngles[SortAngles[3]]);
m_ccpm->ccpmServoWChannel->setCurrentIndex(ServoChannels[SortAngles[0]]);
m_ccpm->ccpmServoXChannel->setCurrentIndex(ServoChannels[SortAngles[1]]);
m_ccpm->ccpmServoYChannel->setCurrentIndex(ServoChannels[SortAngles[2]]);
m_ccpm->ccpmServoZChannel->setCurrentIndex(ServoChannels[SortAngles[3]]);
//m_ccpm->ccpmServoWChannel->setCurrentIndex(ServoChannels[SortAngles[0]]);
//m_ccpm->ccpmServoXChannel->setCurrentIndex(ServoChannels[SortAngles[1]]);
//m_ccpm->ccpmServoYChannel->setCurrentIndex(ServoChannels[SortAngles[2]]);
//m_ccpm->ccpmServoZChannel->setCurrentIndex(ServoChannels[SortAngles[3]]);
m_ccpm->ccpmServoWChannel->setCurrentIndex(ServoChannels[0]);
m_ccpm->ccpmServoXChannel->setCurrentIndex(ServoChannels[1]);
m_ccpm->ccpmServoYChannel->setCurrentIndex(ServoChannels[2]);
m_ccpm->ccpmServoZChannel->setCurrentIndex(ServoChannels[3]);
//Types << "CCPM 2 Servo 90º" << "CCPM 3 Servo 120º" << "CCPM 3 Servo 140º" << "FP 2 Servo 90º" << "Custom - User Angles" << "Custom - Advanced Settings" ;
@ -1075,7 +1437,7 @@ void ConfigccpmWidget::requestccpmUpdate()
{
}
*/
@ -1096,7 +1458,8 @@ void ConfigccpmWidget::requestccpmUpdate()
updatingFromHardware=FALSE;
UpdatCCPMUIFromOptions();
ccpmSwashplateUpdate();
}
@ -1112,10 +1475,22 @@ void ConfigccpmWidget::sendccpmUpdate()
UAVDataObject* obj;
if (SwashLvlConfigurationInProgress)return;
ShowDisclaimer(1);
updatingToHardware=TRUE;
//ShowDisclaimer(1);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
UpdatCCPMOptionsFromUI();
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
field = obj->getField(QString("GUIConfigData"));
field->setValue(GUIConfigData.UAVObject[0],0);
field->setValue(GUIConfigData.UAVObject[1],1);
obj->updated();
obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
@ -1183,6 +1558,30 @@ void ConfigccpmWidget::sendccpmUpdate()
obj->updated();
field = obj->getField(QString("Curve2Source"));
//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)
{// input channel
field->setValue("Accessory0");
obj->updated();
obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("ManualControlSettings")));
Q_ASSERT(obj);
field = obj->getField(QString("Accessory0"));
field->setValue(tr( "Channel%1" ).arg(GUIConfigData.heli.CollectiveChannel+1));
}
else
{// throttle
field->setValue("Throttle");
}
obj->updated();
updatingToHardware=FALSE;
}
@ -1220,6 +1619,7 @@ void ConfigccpmWidget::showEvent(QShowEvent *event)
m_ccpm->ccpmAdvancedSettingsTable->setColumnWidth(i,(m_ccpm->ccpmAdvancedSettingsTable->width()-
m_ccpm->ccpmAdvancedSettingsTable->verticalHeader()->width())/6);
}
ccpmSwashplateRedraw();
}

View File

@ -34,6 +34,7 @@
#include "uavobject.h"
#include <QtSvg/QSvgRenderer>
#include <QtSvg/QGraphicsSvgItem>
#include <QGraphicsEllipseItem>
#include <QtGui/QWidget>
#include <QList>
@ -49,6 +50,30 @@ 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 CollectiveChannel:3;//20bits
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
{
Q_OBJECT
@ -72,6 +97,7 @@ private:
QGraphicsSvgItem *Servos[CCPM_MAX_SWASH_SERVOS];
QGraphicsTextItem *ServosText[CCPM_MAX_SWASH_SERVOS];
QGraphicsLineItem *ServoLines[CCPM_MAX_SWASH_SERVOS];
QGraphicsEllipseItem *ServosTextCircles[CCPM_MAX_SWASH_SERVOS];
QSpinBox *SwashLvlSpinBoxes[CCPM_MAX_SWASH_SERVOS];
bool SwashLvlConfigurationInProgress;
@ -82,11 +108,15 @@ 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
bool updatingFromHardware;
bool updatingToHardware;
private slots:
void ccpmSwashplateUpdate();
void ccpmSwashplateRedraw();
@ -104,6 +134,12 @@ private:
void SwashLvlCancelButtonPressed();
void SwashLvlFinishButtonPressed();
void UpdatCCPMOptionsFromUI();
void UpdatCCPMUIFromOptions();
void SetUIComponentVisibilities();
void ccpmChannelCheck();
void enableSwashplateLevellingControl(bool state);
void setSwashplateLevel(int percent);
void SwashLvlSpinBoxChanged(int value);

View File

@ -538,7 +538,7 @@ void ConfigInputWidget::updateChannels(UAVObject* controlCommand)
obj->setMetadata(mdata);
// Set some slider values to better defaults
// Find what channel we used for throttle, set it 2% about min:
// Find some channels first
int throttleChannel = -1;
int fmChannel = -1;
for (int i=0; i < inChannelAssign.length(); i++) {
@ -558,18 +558,11 @@ void ConfigInputWidget::updateChannels(UAVObject* controlCommand)
// Throttle neutral defaults to 2% of range
if (throttleChannel > -1) {
if (inRevCheckboxes[throttleChannel]->isChecked()) {
inSliders.at(throttleChannel)->setValue(
inSliders.at(throttleChannel)->maximum() -
(inSliders.at(throttleChannel)->maximum()-
inSliders.at(throttleChannel)->minimum())*0.02);
} else {
inSliders.at(throttleChannel)->setValue(
inSliders.at(throttleChannel)->minimum() +
(inSliders.at(throttleChannel)->maximum()-
inSliders.at(throttleChannel)->minimum())*0.02);
}
}
// Flight mode at 50% of range:
if (fmChannel > -1) {

View File

@ -147,7 +147,17 @@ QList<double> MixerCurveWidget::getCurve() {
return list;
}
/**
Sets a linear graph
*/
void MixerCurveWidget::initLinearCurve(quint32 numPoints, double maxValue)
{
QList<double> points;
for (double i=0; i<numPoints;i++) {
points.append(maxValue*(i/(numPoints-1)));
}
initCurve(points);
}
/**
Setd the current curve settings
*/

View File

@ -45,6 +45,7 @@ public:
void itemMoved(double itemValue); // Callback when a point is moved, to be updated
void initCurve (QList<double> points);
QList<double> getCurve();
void initLinearCurve(quint32 numPoints, double maxValue);
void setCurve(QList<double>);
void setMin(double value);
void setMax(double value);

View File

@ -68,6 +68,7 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \
$$UAVOBJECT_SYNTHETICS/nedaccel.h \
$$UAVOBJECT_SYNTHETICS/sonaraltitude.h \
$$UAVOBJECT_SYNTHETICS/flightstatus.h \
$$UAVOBJECT_SYNTHETICS/hwsettings.h \
$$UAVOBJECT_SYNTHETICS/attitudesettings.h
SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
@ -116,4 +117,5 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
$$UAVOBJECT_SYNTHETICS/sonaraltitude.cpp \
$$UAVOBJECT_SYNTHETICS/uavobjectsinit.cpp \
$$UAVOBJECT_SYNTHETICS/flightstatus.cpp \
$$UAVOBJECT_SYNTHETICS/hwsettings.cpp \
$$UAVOBJECT_SYNTHETICS/attitudesettings.cpp

View File

@ -261,18 +261,45 @@ QByteArray UAVObjectUtilManager::getBoardCPUSerial()
loop.exec();
UAVObjectField* cpuField = obj->getField("CPUSerial");
for (int i = 0; i < cpuField->getNumElements(); ++i) {
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<UAVObjectManager>();
if (!om)
return 0;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(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;
}
/**
* Get the UAV Board Description, for anyone interested.
*/
QString UAVObjectUtilManager::getBoardDescription()
QByteArray UAVObjectUtilManager::getBoardDescription()
{
QString description;
QByteArray ret;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm)
return 0;
@ -291,10 +318,10 @@ QString UAVObjectUtilManager::getBoardDescription()
UAVObjectField* descriptionField = obj->getField("Description");
// Description starts with an offset of
for (int i = 14; i < descriptionField->getNumElements(); ++i) {
description.append(descriptionField->getValue(i).toChar());
for (uint i = 0; i < descriptionField->getNumElements(); ++i) {
ret.append(descriptionField->getValue(i).toInt());
}
return description;
return ret;
}

View File

@ -63,7 +63,8 @@ public:
int getBoardModel();
QByteArray getBoardCPUSerial();
QString getBoardDescription();
quint32 getFirmwareCRC();
QByteArray getBoardDescription();
UAVObjectManager* getObjectManager();
void saveObjectToSD(UAVObject *obj);

View File

@ -0,0 +1,5 @@
#include "devicedescriptorstruct.h"
deviceDescriptorStruct::deviceDescriptorStruct()
{
}

View File

@ -0,0 +1,36 @@
#ifndef DEVICEDESCRIPTORSTRUCT_H
#define DEVICEDESCRIPTORSTRUCT_H
#include <QString>
struct deviceDescriptorStruct
{
public:
QString gitTag;
QString buildDate;
QString description;
int boardType;
int boardRevision;
static QString idToBoardName(int id)
{
switch (id | 0x0011) {
case 0x0111://MB
return QString("Board name: OpenPilot MainBoard");
break;
case 0x0311://PipX
return QString("Board name: PipXtreame");
break;
case 0x0411://Coptercontrol
return QString("Board name: CopterControl");
break;
case 0x0211://INS
return QString("Board name: OpenPilot INS");
break;
default:
return QString("");
break;
}
}
deviceDescriptorStruct();
};
#endif // DEVICEDESCRIPTORSTRUCT_H

View File

@ -34,16 +34,18 @@ deviceWidget::deviceWidget(QWidget *parent) :
devicePic = NULL; // Initialize pointer to null
// Initialization of the Device icon display
myDevice->devicePicture->setScene(new QGraphicsScene(this));
connect(myDevice->verifyButton, SIGNAL(clicked()), this, SLOT(verifyFirmware()));
myDevice->verticalGroupBox_loaded->setVisible(false);
myDevice->groupCustom->setVisible(false);
myDevice->youdont->setVisible(false);
myDevice->gVDevice->setScene(new QGraphicsScene(this));
connect(myDevice->retrieveButton, SIGNAL(clicked()), this, SLOT(downloadFirmware()));
connect(myDevice->updateButton, SIGNAL(clicked()), this, SLOT(uploadFirmware()));
connect(myDevice->pbLoad, SIGNAL(clicked()), this, SLOT(loadFirmware()));
connect(myDevice->youdont, SIGNAL(stateChanged(int)), this, SLOT(confirmCB(int)));
QPixmap pix = QPixmap(QString(":uploader/images/view-refresh.svg"));
myDevice->statusIcon->setPixmap(pix);
myDevice->certifiedFW->setText("");
myDevice->lblCertified->setText("");
}
@ -54,14 +56,16 @@ void deviceWidget::showEvent(QShowEvent *event)
// widget is shown, otherwise it cannot compute its values and
// the result is usually a ahrsbargraph that is way too small.
if (devicePic)
myDevice->devicePicture->fitInView(devicePic,Qt::KeepAspectRatio);
{
myDevice->gVDevice->fitInView(devicePic,Qt::KeepAspectRatio);
}
}
void deviceWidget::resizeEvent(QResizeEvent* event)
{
Q_UNUSED(event);
if (devicePic)
myDevice->devicePicture->fitInView(devicePic, Qt::KeepAspectRatio);
myDevice->gVDevice->fitInView(devicePic, Qt::KeepAspectRatio);
}
@ -74,21 +78,43 @@ void deviceWidget::setDfu(DFUObject *dfu)
m_dfu = dfu;
}
QString deviceWidget::idToBoardName(int id)
{
switch (id | 0x0011) {
case 0x0111://MB
return QString("Board name: OpenPilot MainBoard");
break;
case 0x0311://PipX
return QString("Board name: PipXtreame");
break;
case 0x0411://Coptercontrol
return QString("Board name: CopterControl");
break;
case 0x0211://INS
return QString("Board name: OpenPilot INS");
break;
default:
return QString("");
break;
}
}
/**
Fills the various fields for the device
*/
void deviceWidget::populate()
{
int id = m_dfu->devices[deviceID].ID;
myDevice->deviceID->setText(QString("Device ID: ") + QString::number(id, 16));
myDevice->lbldevID->setText(QString("Device ID: ") + QString::number(id, 16));
// DeviceID tells us what sort of HW we have detected:
// display a nice icon:
myDevice->devicePicture->scene()->clear();
if (devicePic)
delete devicePic;
myDevice->gVDevice->scene()->clear();
myDevice->lblDevName->setText(deviceDescriptorStruct::idToBoardName(id));
myDevice->lblHWRev->setText(QString(tr("HW Revision: "))+QString::number(id & 0x0011, 16));
devicePic = new QGraphicsSvgItem();
devicePic->setSharedRenderer(new QSvgRenderer());
switch (id) {
case 0x0101:
devicePic->renderer()->load(QString(":/uploader/images/deviceID-0101.svg"));
@ -106,35 +132,35 @@ void deviceWidget::populate()
break;
}
devicePic->setElementId("device");
myDevice->devicePicture->scene()->addItem(devicePic);
myDevice->devicePicture->setSceneRect(devicePic->boundingRect());
myDevice->devicePicture->fitInView(devicePic,Qt::KeepAspectRatio);
myDevice->gVDevice->scene()->addItem(devicePic);
myDevice->gVDevice->setSceneRect(devicePic->boundingRect());
myDevice->gVDevice->fitInView(devicePic,Qt::KeepAspectRatio);
bool r = m_dfu->devices[deviceID].Readable;
bool w = m_dfu->devices[deviceID].Writable;
myDevice->deviceACL->setText(QString("Access: ") + QString(r ? "R" : "-") + QString(w ? "W" : "-"));
myDevice->maxCodeSize->setText(QString("Max code size: ") +QString::number(m_dfu->devices[deviceID].SizeOfCode));
myDevice->fwCRC->setText(QString("FW CRC: ") + QString::number(m_dfu->devices[deviceID].FW_CRC));
myDevice->BLVersion->setText(QString("BL Version: ") + QString::number(m_dfu->devices[deviceID].BL_Version));
myDevice->lblAccess->setText(QString("Flash access: ") + QString(r ? "R" : "-") + QString(w ? "W" : "-"));
myDevice->lblMaxCode->setText(QString("Max code size: ") +QString::number(m_dfu->devices[deviceID].SizeOfCode));
myDevice->lblCRC->setText(QString("Firmware CRC: ") + QString::number(m_dfu->devices[deviceID].FW_CRC));
myDevice->lblBLVer->setText(QString("BL version: ") + QString::number(m_dfu->devices[deviceID].BL_Version));
int size=((OP_DFU::device)m_dfu->devices[deviceID]).SizeOfDesc;
m_dfu->enterDFU(deviceID);
QByteArray desc = m_dfu->DownloadDescriptionAsBA(size);
if (! populateStructuredDescription(desc)) {
if (! populateBoardStructuredDescription(desc)) {
//TODO
// desc was not a structured description
QString str = m_dfu->DownloadDescription(size);
myDevice->description->setMaxLength(size);
myDevice->description->setText(str.left(str.indexOf(QChar(255))));
QPixmap pix = QPixmap(QString(":uploader/images/gtk-info.svg"));
myDevice->certifiedFW->setPixmap(pix);
myDevice->certifiedFW->setToolTip(tr("Custom Firmware Build"));
myDevice->buildDate->setText("Warning: development firmware");
myDevice->commitTag->setText("");
myDevice->lblDescription->setText(QString("Firmware custom description: ")+str.left(str.indexOf(QChar(255))));
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
myDevice->lblCertified->setPixmap(pix);
myDevice->lblCertified->setToolTip(tr("Custom Firmware Build"));
myDevice->lblBuildDate->setText("Warning: development firmware");
myDevice->lblGitTag->setText("");
myDevice->lblBrdName->setText("");
}
status("Ready...", STATUSICON_INFO);
}
/**
@ -145,59 +171,73 @@ void deviceWidget::freeze()
{
myDevice->description->setEnabled(false);
myDevice->updateButton->setEnabled(false);
myDevice->verifyButton->setEnabled(false);
myDevice->retrieveButton->setEnabled(false);
}
/**
Populates the widget field with the description in case
it is structured properly
*/
bool deviceWidget::populateStructuredDescription(QByteArray desc)
bool deviceWidget::populateBoardStructuredDescription(QByteArray desc)
{
if (desc.startsWith("OpFw")) {
// This looks like a binary with a description at the end
/*
# 4 bytes: header: "OpFw"
# 4 bytes: GIT commit tag (short version of SHA1)
# 4 bytes: Unix timestamp of compile time
# 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.
*/
// Note: the ARM binary is big-endian:
quint32 gitCommitTag = desc.at(7)&0xFF;
for (int i=1;i<4;i++) {
gitCommitTag = gitCommitTag<<8;
gitCommitTag += desc.at(7-i) & 0xFF;
}
myDevice->commitTag->setText("GIT tag 0x" + QString::number(gitCommitTag,16));
quint32 buildDate = desc.at(11)&0xFF;
for (int i=1;i<4;i++) {
buildDate = buildDate<<8;
buildDate += desc.at(11-i) & 0xFF;
}
myDevice->buildDate->setText(QString("Build time: ") + QDateTime::fromTime_t(buildDate).toString());
QByteArray targetPlatform = desc.mid(12,2);
// TODO: check platform compatibility
QString dscText = QString(desc.mid(14,26));
myDevice->description->setText(dscText);
if(UploaderGadgetWidget::descriptionToStructure(desc,&onBoardDescrition))
{
myDevice->lblGitTag->setText("Git commit tag: "+onBoardDescrition.gitTag);
myDevice->lblBuildDate->setText(QString("Firmware date: ") + onBoardDescrition.buildDate);
if(onBoardDescrition.description.startsWith("release",Qt::CaseInsensitive))
{
myDevice->lblDescription->setText(QString("Firmware tag: ")+onBoardDescrition.description);
QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg"));
myDevice->certifiedFW->setPixmap(pix);
myDevice->certifiedFW->setToolTip(tr("Official Firmware Build"));
myDevice->lblCertified->setPixmap(pix);
myDevice->lblCertified->setToolTip(tr("Official Firmware Build"));
}
else
{
myDevice->lblDescription->setText(QString("Firmware tag: ")+onBoardDescrition.description+QString(" (beta or custom build)"));
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
myDevice->lblCertified->setPixmap(pix);
myDevice->lblCertified->setToolTip(tr("Custom Firmware Build"));
}
myDevice->lblBrdName->setText(idToBoardName(onBoardDescrition.boardType<<8));
return true;
}
return false;
}
bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc)
{
if(UploaderGadgetWidget::descriptionToStructure(desc,&LoadedDescrition))
{
myDevice->lblGitTagL->setText("Git commit tag: "+LoadedDescrition.gitTag);
myDevice->lblBuildDateL->setText(QString("Firmware date: ") + LoadedDescrition.buildDate);
if(LoadedDescrition.description.startsWith("release",Qt::CaseInsensitive))
{
myDevice->lblDescritpionL->setText(QString("Firmware tag: ")+LoadedDescrition.description);
myDevice->description->setText(LoadedDescrition.description);
QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg"));
myDevice->lblCertifiedL->setPixmap(pix);
myDevice->lblCertifiedL->setToolTip(tr("Official Firmware Build"));
}
else
{
myDevice->lblDescritpionL->setText(QString("Firmware tag: ")+LoadedDescrition.description+QString(" (beta or custom build)"));
myDevice->description->setText(LoadedDescrition.description);
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
myDevice->lblCertifiedL->setPixmap(pix);
myDevice->lblCertifiedL->setToolTip(tr("Custom Firmware Build"));
}
myDevice->lblBrdNameL->setText(deviceDescriptorStruct::idToBoardName(LoadedDescrition.boardType<<8));
return true;
}
return false;
}
/**
Updates status message for messages coming from DFU
*/
@ -206,6 +246,16 @@ void deviceWidget::dfuStatus(QString str)
status(str, STATUSICON_RUNNING);
}
void deviceWidget::confirmCB(int value)
{
if(value==Qt::Checked)
{
myDevice->updateButton->setEnabled(true);
}
else
myDevice->updateButton->setEnabled(false);
}
/**
Updates status message
*/
@ -229,11 +279,74 @@ void deviceWidget::status(QString str, StatusIcon ic)
myDevice->statusIcon->setPixmap(px);
}
/**
Verifies the firmware CRC
*/
void deviceWidget::verifyFirmware()
void deviceWidget::loadFirmware()
{
myDevice->verticalGroupBox_loaded->setVisible(false);
myDevice->groupCustom->setVisible(false);
filename = setOpenFileName();
if (filename.isEmpty()) {
status("Empty filename", STATUSICON_FAIL);
return;
}
QFile file(filename);
if (!file.open(QIODevice::ReadOnly)) {
status("Can't open file", STATUSICON_FAIL);
return;
}
loadedFW = file.readAll();
myDevice->youdont->setVisible(false);
myDevice->youdont->setChecked(false);
QByteArray desc = loadedFW.right(100);
QPixmap px;
myDevice->lblCRCL->setText(QString("FW CRC: ") + QString::number(DFUObject::CRCFromQBArray(loadedFW,m_dfu->devices[deviceID].SizeOfCode)));
myDevice->lblFirmwareSizeL->setText(QString("Firmware size: ")+QVariant(loadedFW.length()).toString()+ QString(" bytes"));
if (populateLoadedStructuredDescription(desc))
{
myDevice->youdont->setChecked(true);
myDevice->verticalGroupBox_loaded->setVisible(true);
myDevice->groupCustom->setVisible(false);
if(myDevice->lblCRC->text()==myDevice->lblCRCL->text())
{
myDevice->statusLabel->setText(tr("The loaded firmware maches the firmware on the board. You shouldn't upload it"));
px.load(QString(":/uploader/images/warning.svg"));
}
else if(myDevice->lblDevName->text()!=myDevice->lblBrdNameL->text())
{
myDevice->statusLabel->setText(tr("The loaded firmware is not suited for the HW connected. You shouldn't upload it"));
px.load(QString(":/uploader/images/warning.svg"));
}
else if(QDateTime::fromString(onBoardDescrition.buildDate)>QDateTime::fromString(LoadedDescrition.buildDate))
{
myDevice->statusLabel->setText(tr("The loaded firmware is older then the firmware on the board. You shouldn't upload it"));
px.load(QString(":/uploader/images/warning.svg"));
}
else if(!LoadedDescrition.description.startsWith("release",Qt::CaseInsensitive))
{
myDevice->statusLabel->setText(tr("The loaded firmware is not an oficial OpenPilot release. You should upload it only if you know what you are doing"));
px.load(QString(":/uploader/images/warning.svg"));
}
else
{
myDevice->statusLabel->setText(tr("Everything seems OK. You should upload the loaded firmware by pressing 'upload'"));
px.load(QString(":/uploader/images/gtk-info.svg"));
}
}
else
{
myDevice->statusLabel->setText(tr("The loaded firmware was not packaged with a compatible format. You shouldn't' upload it, if you know what you are doing and still want to upload it confirm it by checking the checkbox bellow"));
px.load(QString(":/uploader/images/warning.svg"));
myDevice->youdont->setChecked(false);
myDevice->youdont->setVisible(true);
myDevice->verticalGroupBox_loaded->setVisible(false);
myDevice->groupCustom->setVisible(true);
}
myDevice->statusIcon->setPixmap(px);
//myDevice->updateButton->setEnabled(true);
}
@ -253,22 +366,8 @@ void deviceWidget::uploadFirmware()
verify = true;
*/
QString filename = setOpenFileName();
if (filename.isEmpty()) {
status("Empty filename", STATUSICON_FAIL);
return;
}
QFile file(filename);
if (!file.open(QIODevice::ReadOnly)) {
status("Can't open file", STATUSICON_FAIL);
return;
}
QByteArray arr = file.readAll();
QByteArray desc = arr.right(100);
if (populateStructuredDescription(desc)) {
QByteArray desc = loadedFW.right(100);
if (desc.startsWith("OpFw")) {
descriptionArray = desc;
// Now do sanity checking:
// - Check whether board type matches firmware:
@ -280,7 +379,7 @@ void deviceWidget::uploadFirmware()
}
// Check the firmware embedded in the file:
QByteArray firmwareHash = desc.mid(40,20);
QByteArray fileHash = QCryptographicHash::hash(arr.left(arr.length()-100), QCryptographicHash::Sha1);
QByteArray fileHash = QCryptographicHash::hash(loadedFW.left(loadedFW.length()-100), QCryptographicHash::Sha1);
if (firmwareHash != fileHash) {
status("Error: firmware file corrupt", STATUSICON_FAIL);
return;
@ -390,7 +489,7 @@ void deviceWidget::uploadFinished(OP_DFU::Status retstatus)
return;
}
}
populate();
status("Upload successful", STATUSICON_OK);
}

View File

@ -38,9 +38,9 @@
#include <QtSvg/QGraphicsSvgItem>
#include <QtSvg/QSvgRenderer>
#include <QCryptographicHash>
#include "uavobjectutilmanager.h"
#include "devicedescriptorstruct.h"
using namespace OP_DFU;
class deviceWidget : public QWidget
{
Q_OBJECT
@ -54,6 +54,10 @@ public:
QString setOpenFileName();
QString setSaveFileName();
private:
deviceDescriptorStruct onBoardDescrition;
deviceDescriptorStruct LoadedDescrition;
QByteArray loadedFW;
QString idToBoardName(int id);
Ui_deviceWidget *myDevice;
int deviceID;
DFUObject *m_dfu;
@ -62,19 +66,20 @@ private:
QGraphicsSvgItem *devicePic;
QByteArray descriptionArray;
void status(QString str, StatusIcon ic);
bool populateStructuredDescription(QByteArray arr);
bool populateBoardStructuredDescription(QByteArray arr);
bool populateLoadedStructuredDescription(QByteArray arr);
signals:
public slots:
void verifyFirmware();
void uploadFirmware();
void loadFirmware();
void downloadFirmware();
void setProgress(int);
void downloadFinished();
void uploadFinished(OP_DFU::Status);
void dfuStatus(QString);
void confirmCB(int);
protected:
void showEvent(QShowEvent *event);

View File

@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>516</width>
<height>253</height>
<height>582</height>
</rect>
</property>
<property name="windowTitle">
@ -15,37 +15,15 @@
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="2" column="0" colspan="3">
<widget class="QLineEdit" name="description">
<property name="readOnly">
<bool>true</bool>
<widget class="QGroupBox" name="verticalGroupBox_4">
<property name="title">
<string>Device Information</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="deviceID">
<property name="text">
<string>DeviceID</string>
</property>
</widget>
</item>
<item row="8" column="0" colspan="2">
<widget class="QProgressBar" name="progressBar">
<property name="value">
<number>0</number>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QLabel" name="deviceACL">
<property name="text">
<string>ReadWrite</string>
</property>
</widget>
</item>
<item row="3" column="2" rowspan="3">
<widget class="QGraphicsView" name="devicePicture">
<layout class="QVBoxLayout" name="verticalLayout_7">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<item>
<widget class="QGraphicsView" name="gVDevice">
<property name="maximumSize">
<size>
<width>160</width>
@ -55,32 +33,80 @@
<property name="styleSheet">
<string notr="true">background: transparent</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<widget class="QLabel" name="lblDevName">
<property name="text">
<string>lblDevName</string>
</property>
</widget>
</item>
<item row="6" column="2">
<widget class="QPushButton" name="verifyButton">
<item>
<widget class="QLabel" name="lbldevID">
<property name="text">
<string>DeviceID</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblHWRev">
<property name="text">
<string>lblHWRev</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblAccess">
<property name="text">
<string>RW</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblBLVer">
<property name="text">
<string>BL Version</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblMaxCode">
<property name="text">
<string>MaxCodeSize</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_6">
<item>
<widget class="QPushButton" name="pbLoad">
<property name="toolTip">
<string>Loads the firmware</string>
</property>
<property name="text">
<string>Open</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="updateButton">
<property name="enabled">
<bool>false</bool>
</property>
<property name="text">
<string>Verify...</string>
</property>
</widget>
</item>
<item row="7" column="2">
<widget class="QPushButton" name="updateButton">
<property name="toolTip">
<string>Update the firmware on this board.</string>
</property>
<property name="text">
<string>Update...</string>
<string>Flash</string>
</property>
</widget>
</item>
<item row="8" column="2">
<item>
<widget class="QPushButton" name="retrieveButton">
<property name="toolTip">
<string>Download the current board firmware to your computer</string>
@ -90,28 +116,18 @@
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QLabel" name="BLVersion">
<property name="text">
<string>BootLoaderVersion</string>
</layout>
</item>
</layout>
</item>
<item>
<widget class="QProgressBar" name="progressBar">
<property name="value">
<number>0</number>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="fwCRC">
<property name="text">
<string>fwCRC</string>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QLabel" name="maxCodeSize">
<property name="text">
<string>MaxCodeSize</string>
</property>
</widget>
</item>
<item row="7" column="0" colspan="2">
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="statusIcon">
@ -137,42 +153,172 @@
<property name="text">
<string>Status</string>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item row="6" column="0">
<widget class="QLabel" name="commitTag">
<item>
<widget class="QCheckBox" name="youdont">
<property name="text">
<string>Commit tag</string>
<string>I know what I'm doing</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
<item row="3" column="0" colspan="2">
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="verticalGroupBox_3">
<property name="title">
<string>Firmware currently on the device</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_5">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<layout class="QVBoxLayout" name="verticalLayout_8">
<item>
<widget class="QLabel" name="lblBrdName">
<property name="text">
<string>lblBrdName</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblDescription">
<property name="text">
<string>lblDescription</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblBuildDate">
<property name="text">
<string>lblBuildDate</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblGitTag">
<property name="text">
<string>lblGitTag</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblCRC">
<property name="text">
<string>lblCRC</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="lblCertified">
<property name="text">
<string>lblCertified</string>
</property>
<property name="scaledContents">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="verticalGroupBox_loaded">
<property name="enabled">
<bool>true</bool>
</property>
<property name="title">
<string>Loaded Firmware</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QLabel" name="certifiedFW">
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QLabel" name="lblBrdNameL">
<property name="text">
<string>certified</string>
<string>lblBrdName</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="buildDate">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<widget class="QLabel" name="lblDescritpionL">
<property name="text">
<string>buildDate</string>
<string>lblDescritpionL</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblBuildDateL">
<property name="text">
<string>lblBuildDate</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblGitTagL">
<property name="text">
<string>lblGitTag</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblCRCL">
<property name="text">
<string>lblCRC</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblFirmwareSizeL">
<property name="text">
<string>lblFirmwareSizeL</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="lblCertifiedL">
<property name="text">
<string>lblCertifiedL</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupCustom">
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QLabel" name="lblX">
<property name="text">
<string>Custom description:</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="description"/>
</item>
</layout>
</widget>
</item>
</layout>
</widget>

View File

@ -0,0 +1,102 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Generator: Adobe Illustrator 15.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
version="1.1"
id="Layer_1"
x="0px"
y="0px"
width="51.537998"
height="46.021885"
viewBox="0 0 51.538001 46.021886"
enable-background="new 0 0 514.475 473.977"
xml:space="preserve"
inkscape:version="0.48.1 "
sodipodi:docname="warning_s.svg"><metadata
id="metadata3095"><rdf:RDF><cc:Work
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title /></cc:Work></rdf:RDF></metadata><defs
id="defs3093" /><sodipodi:namedview
pagecolor="#ffffff"
bordercolor="#666666"
borderopacity="1"
objecttolerance="10"
gridtolerance="10"
guidetolerance="10"
inkscape:pageopacity="0"
inkscape:pageshadow="2"
inkscape:window-width="1280"
inkscape:window-height="738"
id="namedview3091"
showgrid="false"
inkscape:zoom="1.0949899"
inkscape:cx="249.10624"
inkscape:cy="125.11088"
inkscape:window-x="-8"
inkscape:window-y="-8"
inkscape:window-maximized="1"
inkscape:current-layer="Layer_1"
fit-margin-top="0"
fit-margin-left="0"
fit-margin-right="0"
fit-margin-bottom="0" />
<radialGradient
id="SVGID_1_"
cx="255.45261"
cy="231.6748"
r="206.35049"
gradientTransform="matrix(0.1182761,0,0,0.12913623,-4.4457028,-6.9088686)"
gradientUnits="userSpaceOnUse">
<stop
offset="0"
style="stop-color:#FFDE17"
id="stop3074" />
<stop
offset="1"
style="stop-color:#ABA01F"
id="stop3076" />
</radialGradient>
<path
stroke-miterlimit="10"
d="M 1.2974519,42.730481 C -1.4443604,39.150401 21.620352,1.0717714 25.887967,1.0717714 c 4.269682,0 27.060213,38.8621096 24.35608,41.6587096 -3.013913,3.11312 -46.8075615,2.80177 -48.9465951,0 z"
id="path3078"
style="fill:url(#SVGID_1_);stroke:#000000;stroke-width:2.14355946;stroke-miterlimit:10"
inkscape:connector-curvature="0" />
<path
d="m 22.987071,36.405661 c 0,-1.55651 1.465096,-2.59423 3.118544,-2.59423 1.674394,0 3.013911,1.03772 3.013911,2.59423 0,1.55658 -1.255794,2.59427 -3.118542,2.59427 -1.674391,0 -3.034841,-1.03769 -3.034841,-2.59427 z m 1.465096,-5.24042 c -0.627898,-0.77824 -1.67439,-20.36495 -0.627898,-21.3507596 0.837188,-0.77831 3.872026,-0.77831 4.604571,0 0.8372,0.7782796 -0.209304,20.8059796 -0.627897,21.3507596 -0.418602,0.51889 -2.762741,0.51889 -3.265057,0 z"
id="path3080"
inkscape:connector-curvature="0" />
<linearGradient
id="SVGID_2_"
gradientUnits="userSpaceOnUse"
x1="256.45209"
y1="304.9277"
x2="256.45209"
y2="48.449699"
gradientTransform="matrix(0.11827613,0,0,0.10761355,-4.4457031,-1.9220086)">
<stop
offset="0"
style="stop-color:#FFFFFF"
id="stop3083" />
<stop
offset="0.0896"
style="stop-color:#FFFFFF;stop-opacity:0.9104"
id="stop3085" />
<stop
offset="1"
style="stop-color:#FFFFFF;stop-opacity:0"
id="stop3087" />
</linearGradient>
<path
d="M 10.709612,23.014111 C 16.695555,12.974321 23.623336,3.2976914 25.779115,3.2976914 c 2.197635,0 9.313793,10.2991996 15.320665,20.7021496 5.651063,9.75447 -36.2902985,8.92436 -30.396443,-1.03772 z"
id="path3089"
style="opacity:0.31999996;fill:url(#SVGID_2_)"
inkscape:connector-curvature="0" />
</svg>

After

Width:  |  Height:  |  Size: 3.6 KiB

View File

@ -718,7 +718,7 @@ OP_DFU::Status DFUObject::UploadFirmwareT(const QString &sfile, const bool &veri
return OP_DFU::abort;;
}
quint32 crc=CRCFromQBArray(arr,devices[device].SizeOfCode);
quint32 crc=DFUObject::CRCFromQBArray(arr,devices[device].SizeOfCode);
if (debug)
qDebug() << "NEW FIRMWARE CRC=" << crc;
@ -817,7 +817,7 @@ OP_DFU::Status DFUObject::CompareFirmware(const QString &sfile, const CompareTyp
}
if(type==OP_DFU::crccompare)
{
quint32 crc=CRCFromQBArray(arr,devices[device].SizeOfCode);
quint32 crc=DFUObject::CRCFromQBArray(arr,devices[device].SizeOfCode);
if(crc==devices[device].FW_CRC)
{
cout<<"Compare Successfull CRC MATCH!\n";
@ -971,7 +971,7 @@ quint32 DFUObject::CRCFromQBArray(QByteArray array, quint32 Size)
aux+=(char)array[x*4+0]&0xFF;
t[x]=aux;
}
return CRC32WideFast(0xFFFFFFFF,Size/4,(quint32*)t);
return DFUObject::CRC32WideFast(0xFFFFFFFF,Size/4,(quint32*)t);
}

View File

@ -108,7 +108,7 @@ namespace OP_DFU {
Q_OBJECT;
public:
static quint32 CRCFromQBArray(QByteArray array, quint32 Size);
//DFUObject(bool debug);
DFUObject(bool debug,bool use_serial,QString port);
@ -152,7 +152,7 @@ namespace OP_DFU {
// Helper functions:
QString StatusToString(OP_DFU::Status const & status);
quint32 CRC32WideFast(quint32 Crc, quint32 Size, quint32 *Buffer);
static quint32 CRC32WideFast(quint32 Crc, quint32 Size, quint32 *Buffer);
@ -179,7 +179,7 @@ namespace OP_DFU {
// USB Bootloader:
pjrc_rawhid hidHandle;
int setStartBit(int command){ return command|0x20; }
quint32 CRCFromQBArray(QByteArray array, quint32 Size);
void CopyWords(char * source, char* destination, int count);
void printProgBar( int const & percent,QString const& label);
bool StartUpload(qint32 const &numberOfBytes, TransferTypes const & type,quint32 crc);

View File

@ -25,7 +25,8 @@
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "runningdevicewidget.h"
#include "devicedescriptorstruct.h"
#include "uploadergadgetwidget.h"
runningDeviceWidget::runningDeviceWidget(QWidget *parent) :
QWidget(parent)
{
@ -68,8 +69,11 @@ void runningDeviceWidget::populate()
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
int id = utilMngr->getBoardModel();
myDevice->deviceID->setText(QString("Device ID: ") + QString::number(id, 16));
myDevice->lblDeviceID->setText(QString("Device ID: ") + QString::number(id, 16));
myDevice->lblBoardName->setText(deviceDescriptorStruct::idToBoardName(id));
myDevice->lblHWRev->setText(QString(tr("HW Revision: "))+QString::number(id & 0x0011, 16));
qDebug()<<"CRC"<<utilMngr->getFirmwareCRC();
myDevice->lblCRC->setText(QString(tr("Firmware CRC: "))+QVariant(utilMngr->getFirmwareCRC()).toString());
// DeviceID tells us what sort of HW we have detected:
// display a nice icon:
myDevice->devicePicture->scene()->clear();
@ -100,13 +104,41 @@ void runningDeviceWidget::populate()
myDevice->devicePicture->fitInView(devicePic,Qt::KeepAspectRatio);
QString serial = utilMngr->getBoardCPUSerial().toHex();
myDevice->cpuSerial->setText(serial);
myDevice->lblCPU->setText(QString("CPU serial number: "+serial));
QString description = utilMngr->getBoardDescription();
myDevice->description->setText(description);
QByteArray description = utilMngr->getBoardDescription();
deviceDescriptorStruct devDesc;
if(UploaderGadgetWidget::descriptionToStructure(description,&devDesc))
{
if(devDesc.description.startsWith("release",Qt::CaseInsensitive))
{
myDevice->lblFWTag->setText(QString("Firmware tag: ")+devDesc.description);
QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg"));
myDevice->lblCertified->setPixmap(pix);
myDevice->lblCertified->setToolTip(tr("Official Firmware Build"));
}
else
{
myDevice->lblFWTag->setText(QString("Firmware tag: ")+devDesc.description+QString(" (beta or custom build)"));
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
myDevice->lblCertified->setPixmap(pix);
myDevice->lblCertified->setToolTip(tr("Custom Firmware Build"));
}
myDevice->lblGitCommitTag->setText("Git commit tag: "+devDesc.gitTag);
myDevice->lblFWDate->setText(QString("Firmware date: ") + devDesc.buildDate);
}
else
{
myDevice->lblFWTag->setText(QString("Firmware tag: ")+QString(description).left(QString(description).indexOf(QChar(255))));
myDevice->lblGitCommitTag->setText("Git commit tag: Unknown");
myDevice->lblFWDate->setText(QString("Firmware date: Unknown"));
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
myDevice->lblCertified->setPixmap(pix);
myDevice->lblCertified->setToolTip(tr("Custom Firmware Build"));
}
status("Ready...", STATUSICON_INFO);
}

View File

@ -29,7 +29,7 @@
#define RUNNINGDEVICEWIDGET_H
#include "ui_runningdevicewidget.h"
#include "uploadergadgetwidget.h"
#include <QWidget>
#include <QErrorMessage>
#include <QtSvg/QGraphicsSvgItem>

View File

@ -14,9 +14,114 @@
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QGroupBox" name="horizontalGroupBox">
<property name="title">
<string>Device Information</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QGraphicsView" name="devicePicture">
<property name="maximumSize">
<size>
<width>160</width>
<height>160</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background: transparent</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QLabel" name="lblBoardName">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblDeviceID">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblHWRev">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblCPU">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="horizontalGroupBox">
<property name="title">
<string>Firmware Information</string>
</property>
<layout class="QHBoxLayout" name="_2">
<item>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QLabel" name="lblFWTag">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblFWDate">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblGitCommitTag">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lblCRC">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="lblCertified">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="6" column="0" colspan="2">
<item row="3" column="0" colspan="2">
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="statusIcon">
@ -46,50 +151,6 @@
</item>
</layout>
</item>
<item row="5" column="0">
<widget class="QLabel" name="deviceID">
<property name="text">
<string>DeviceID</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="cpuSerialLabel">
<property name="text">
<string>CPU Serial:</string>
</property>
</widget>
</item>
<item row="4" column="2" rowspan="2">
<widget class="QGraphicsView" name="devicePicture">
<property name="maximumSize">
<size>
<width>160</width>
<height>160</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background: transparent</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
</widget>
</item>
<item row="2" column="0" colspan="3">
<widget class="QLineEdit" name="description">
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QLineEdit" name="cpuSerial">
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>

View File

@ -22,7 +22,8 @@ HEADERS += uploadergadget.h \
SSP/qssp.h \
SSP/qsspt.h \
SSP/common.h \
runningdevicewidget.h
runningdevicewidget.h \
devicedescriptorstruct.h
SOURCES += uploadergadget.cpp \
uploadergadgetconfiguration.cpp \
uploadergadgetfactory.cpp \
@ -35,7 +36,8 @@ SOURCES += uploadergadget.cpp \
SSP/port.cpp \
SSP/qssp.cpp \
SSP/qsspt.cpp \
runningdevicewidget.cpp
runningdevicewidget.cpp \
devicedescriptorstruct.cpp
OTHER_FILES += Uploader.pluginspec
FORMS += \

View File

@ -10,5 +10,6 @@
<file>images/deviceID-0201.svg</file>
<file>images/deviceID-0101.svg</file>
<file>images/application-certificate.svg</file>
<file>images/warning.svg</file>
</qresource>
</RCC>

View File

@ -27,7 +27,44 @@
#include "uploadergadgetwidget.h"
#define DFU_DEBUG true
bool UploaderGadgetWidget::descriptionToStructure(QByteArray desc,deviceDescriptorStruct * struc)
{
if (desc.startsWith("OpFw")) {
// This looks like a binary with a description at the end
/*
# 4 bytes: header: "OpFw"
# 4 bytes: GIT commit tag (short version of SHA1)
# 4 bytes: Unix timestamp of compile time
# 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.
*/
// Note: the ARM binary is big-endian:
quint32 gitCommitTag = desc.at(7)&0xFF;
for (int i=1;i<4;i++) {
gitCommitTag = gitCommitTag<<8;
gitCommitTag += desc.at(7-i) & 0xFF;
}
struc->gitTag=QString::number(gitCommitTag,16);
quint32 buildDate = desc.at(11)&0xFF;
for (int i=1;i<4;i++) {
buildDate = buildDate<<8;
buildDate += desc.at(11-i) & 0xFF;
}
struc->buildDate= QDateTime::fromTime_t(buildDate).toLocalTime().toString("yyyy MMMM dd HH:mm:ss");
QByteArray targetPlatform = desc.mid(12,2);
// TODO: check platform compatibility
QString dscText = QString(desc.mid(14,26));
struc->boardType=(int)targetPlatform.at(0);
struc->boardRevision=(int)targetPlatform.at(1);
struc->description=dscText;
return true;
}
return false;
}
UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent)
{
m_config = new Ui_UploaderWidget();

View File

@ -52,20 +52,23 @@
#include <QThread>
#include <QMessageBox>
#include <QTimer>
#include "devicedescriptorstruct.h"
#include <QProgressDialog>
using namespace OP_DFU;
class UploaderGadgetWidget : public QWidget
{
Q_OBJECT
public:
UploaderGadgetWidget(QWidget *parent = 0);
~UploaderGadgetWidget();
typedef enum { IAP_STATE_READY, IAP_STATE_STEP_1, IAP_STATE_STEP_2, IAP_STEP_RESET, IAP_STATE_BOOTLOADER} IAPStep;
void log(QString str);
static bool descriptionToStructure(QByteArray desc,deviceDescriptorStruct * struc);
public slots:
void onAutopilotConnect();

View File

@ -33,16 +33,15 @@ CLEAN_GROUND := YES
CLEAN_FLIGHT := YES
endif
# Set up targets
FW_STEMS_COMMON := ahrs pipxtreme
FW_STEMS_INPUT := coptercontrol openpilot
FW_STEMS_TOOLS := coptercontrol
FW_STEMS_ALL := $(FW_STEMS_COMMON) $(FW_STEMS_INPUT)
FW_TARGETS_COMMON := $(addprefix fw_, $(FW_STEMS_COMMON))
FW_TARGETS_INPUT := $(addprefix fw_, $(FW_STEMS_INPUT))
FW_TARGETS_TOOLS := $(addprefix fw_, $(FW_STEMS_TOOLS))
BL_TARGETS := $(addprefix bl_, $(FW_STEMS_ALL))
BU_TARGETS := $(addprefix bu_, $(FW_STEMS_ALL))
# Set up targets (PPM target seems to be broken at the moment)
FW_TARGETS_COMMON := $(addprefix fw_, ahrs pipxtreme)
FW_TARGETS_PWM := $(addprefix fw_, coptercontrol openpilot)
FW_TARGETS_DSM2 := $(addprefix fw_, coptercontrol openpilot)
FW_TARGETS_SBUS := $(addprefix fw_, coptercontrol)
FW_TARGETS_PPM := $(addprefix fw_, openpilot)
FW_TARGETS_TOOLS := $(addprefix fw_, coptercontrol)
BL_TARGETS := $(addprefix bl_, coptercontrol openpilot ahrs pipxtreme)
BU_TARGETS := $(addprefix bu_, coptercontrol openpilot ahrs pipxtreme)
help:
@echo
@ -102,9 +101,10 @@ endef
# Firmware for different input drivers
$(eval $(call INSTALL_TEMPLATE,fw_common,uavobjects,$(FW_DIR),,-$(PACKAGE_LBL),,,$(FW_TARGETS_COMMON),install))
$(eval $(call INSTALL_TEMPLATE,fw_pwm,uavobjects,$(FW_DIR),,-pwm-$(PACKAGE_LBL),,clean,$(FW_TARGETS_INPUT),install))
$(eval $(call INSTALL_TEMPLATE,fw_spektrum,uavobjects,$(FW_DIR),,-dsm2sat-$(PACKAGE_LBL),USE_SPEKTRUM=YES,clean,$(FW_TARGETS_INPUT),install))
$(eval $(call INSTALL_TEMPLATE,fw_ppm,uavobjects,$(FW_DIR),,-ppm-$(PACKAGE_LBL),USE_PPM=YES,clean,$(FW_TARGETS_INPUT),install))
$(eval $(call INSTALL_TEMPLATE,fw_pwm,uavobjects,$(FW_DIR),,-pwm-$(PACKAGE_LBL),,clean,$(FW_TARGETS_PWM),install))
$(eval $(call INSTALL_TEMPLATE,fw_dsm2,uavobjects,$(FW_DIR),,-dsm2sat-$(PACKAGE_LBL),USE_SPEKTRUM=YES,clean,$(FW_TARGETS_DSM2),install))
$(eval $(call INSTALL_TEMPLATE,fw_sbus,uavobjects,$(FW_DIR),,-sbus-$(PACKAGE_LBL),USE_SBUS=YES USE_TELEMETRY=3,clean,$(FW_TARGETS_SBUS),install))
$(eval $(call INSTALL_TEMPLATE,fw_ppm,uavobjects,$(FW_DIR),,-ppm-$(PACKAGE_LBL),USE_PPM=YES,clean,$(FW_TARGETS_PPM),install))
# Bootloaders (change 'install' to 'bin' if you don't want to install bootloaders)
$(eval $(call INSTALL_TEMPLATE,all_bl,uavobjects,$(BL_DIR),,-$(PACKAGE_LBL),,,$(BL_TARGETS),install))
@ -121,13 +121,15 @@ $(eval $(call INSTALL_TEMPLATE,fw_tools,uavobjects,$(FE_DIR),,-flash-erase-$(PAC
fw_pwm: | # default dependencies, will be built first
fw_spektrum: | fw_pwm # ordered build
fw_dsm2: | fw_pwm # ordered build
fw_ppm: | fw_spektrum # ordered build
fw_sbus: | fw_dsm2 # ordered build
fw_tools: | fw_spektrum # ordered build, replace fw_spektrum by fw_ppm if uncommented below
fw_ppm: | fw_sbus # ordered build
package_fw: | fw_common fw_pwm fw_spektrum # fw_ppm
fw_tools: | fw_ppm # ordered build
package_fw: | fw_common fw_pwm fw_dsm2 fw_sbus fw_ppm
package_bu: | all_bu

View File

@ -0,0 +1,11 @@
<xml>
<object name="HwSettings" singleinstance="true" settings="true">
<description>Selection of optional hardware configurations.</description>
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,Spektrum,ComAux,I2C" defaultvalue="Disabled"/>
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,S.Bus,GPS,Spektrum,ComAux" defaultvalue="Telemetry"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>
<logging updatemode="never" period="0"/>
</object>
</xml>

View File

@ -1,7 +1,7 @@
<xml>
<object name="ManualControlSettings" singleinstance="true" settings="true">
<description>Settings to indicate how to decode receiver input by @ref ManualControlModule.</description>
<field name="InputMode" units="" type="enum" elements="1" options="PWM,PPM,Spektrum" defaultvalue="PWM"/>
<field name="InputMode" units="" type="enum" elements="1" options="PWM,PPM,Spektrum,S.Bus" defaultvalue="PWM"/>
<field name="Roll" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="Pitch" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="Yaw" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>

View File

@ -5,7 +5,7 @@
<field name="FeedForward" units="" type="float" elements="1" defaultvalue="0"/>
<field name="AccelTime" units="ms" type="float" elements="1" defaultvalue="0"/>
<field name="DecelTime" units="ms" type="float" elements="1" defaultvalue="0"/>
<field name="ThrottleCurve1" units="percent" type="float" elements="5" elementnames="0,25,50,75,100" defaultvalue="0,0.25,0.5,0.75,1"/>
<field name="ThrottleCurve1" units="percent" type="float" elements="5" elementnames="0,25,50,75,100" defaultvalue="0,0,0,0,0"/>
<field name="Curve2Source" units="" type="enum" elements="1" options="Throttle,Roll,Pitch,Yaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Throttle"/>
<field name="ThrottleCurve2" units="percent" type="float" elements="5" elementnames="0,25,50,75,100" defaultvalue="0,0.25,0.5,0.75,1"/>
<field name="Mixer1Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>

View File

@ -2,6 +2,7 @@
<object name="SystemSettings" singleinstance="true" settings="true">
<description>Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand</description>
<field name="AirframeType" units="" type="enum" elements="1" options="FixedWing,FixedWingElevon,FixedWingVtail,VTOL,HeliCP,QuadX,QuadP,Hexa,Octo,Custom,HexaX,OctoV,OctoCoaxP,OctoCoaxX,HexaCoax,Tri" defaultvalue="FixedWing"/>
<field name="GUIConfigData" units="bits" type="uint32" elements="2" defaultvalue="0"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>