mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
Merge branch 'next' into os/TxPID-module
Conflicts: flight/CopterControl/Makefile flight/CopterControl/System/coptercontrol.c ground/uavobjgenerator/generators/generator_common.h shared/uavobjectdefinition/hwsettings.xml component free heap used ---------------------------- Nothing 2544 - PWM 2416 128 PPM 2392 152 DSM 2448 96 S.Bus 2432 112 GPS (port only) 2352 192 GPS (port+module) 1296 1248 CameraStab 2080 464 Telemetry 1912 632 TxPID 2272 272
This commit is contained in:
commit
de6e450b5f
16
HISTORY.txt
16
HISTORY.txt
@ -1,5 +1,21 @@
|
||||
Short summary of changes. For a complete list see the git log.
|
||||
|
||||
2011-11-04
|
||||
New Spektrum/JR satellite receiver driver implementation.
|
||||
It now provides explicit selection of DSM2 (and DSMJ), DSMX (10bit) and
|
||||
DSMX (11bit) serial protocol variations to better serve different frame
|
||||
and resolution modes. The protocol name used now is DSM instead of
|
||||
previously used Spektrum to make it less ambiguous when used with JR
|
||||
2.4GHz radios.
|
||||
|
||||
2011-10-20
|
||||
Inputs can be remapped to outputs to allow up to 10 channels of control. The
|
||||
receiver inputs remap as follows:
|
||||
Receiver 3 because output channel 7
|
||||
Receiver 4 because output channel 8
|
||||
Receiver 5 because output channel 9
|
||||
Receiver 6 because output channel 10
|
||||
|
||||
2011-10-11
|
||||
Fix for the Mac telemetry rates and specifically how long enumeration took.
|
||||
|
||||
|
@ -354,7 +354,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
|
||||
$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin
|
||||
|
||||
# Add jtag targets (program and wipe)
|
||||
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG)))
|
||||
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG)))
|
||||
|
||||
.PHONY: elf lss sym hex bin bino
|
||||
elf: $(OUTDIR)/$(TARGET).elf
|
||||
|
@ -413,7 +413,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
|
||||
$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin
|
||||
|
||||
# Add jtag targets (program and wipe)
|
||||
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG)))
|
||||
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG)))
|
||||
|
||||
.PHONY: elf lss sym hex bin bino
|
||||
elf: $(OUTDIR)/$(TARGET).elf
|
||||
|
@ -419,7 +419,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
|
||||
$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin
|
||||
|
||||
# Add jtag targets (program and wipe)
|
||||
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG)))
|
||||
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG)))
|
||||
|
||||
.PHONY: elf lss sym hex bin bino
|
||||
elf: $(OUTDIR)/$(TARGET).elf
|
||||
|
@ -43,23 +43,12 @@
|
||||
#define PIOS_INCLUDE_OPAHRS
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_NO_GPS
|
||||
//#define DEBUG_SSP
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define TELEM_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
/* Servos */
|
||||
#define SERVOS_POSITION_MIN 800
|
||||
#define SERVOS_POSITION_MAX 2200
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
|
@ -414,7 +414,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
|
||||
$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin
|
||||
|
||||
# Add jtag targets (program and wipe)
|
||||
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG)))
|
||||
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG)))
|
||||
|
||||
.PHONY: elf lss sym hex bin bino
|
||||
elf: $(OUTDIR)/$(TARGET).elf
|
||||
|
@ -40,23 +40,12 @@
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_NO_GPS
|
||||
//#define DEBUG_SSP
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define TELEM_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
/* Servos */
|
||||
#define SERVOS_POSITION_MIN 800
|
||||
#define SERVOS_POSITION_MAX 2200
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
|
@ -48,7 +48,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_GPS ?= NO
|
||||
USE_GPS ?= YES
|
||||
|
||||
USE_I2C ?= NO
|
||||
|
||||
@ -65,8 +65,14 @@ endif
|
||||
FLASH_TOOL = OPENOCD
|
||||
|
||||
# List of modules to include
|
||||
MODULES = Attitude Stabilization Actuator ManualControl FirmwareIAP CameraStab TxPID
|
||||
# Telemetry must be last to grab the optional modules
|
||||
OPTMODULES = CameraStab
|
||||
ifeq ($(USE_GPS), YES)
|
||||
OPTMODULES += GPS
|
||||
endif
|
||||
OPTMODULES += TxPID
|
||||
|
||||
MODULES = Attitude Stabilization Actuator ManualControl FirmwareIAP
|
||||
# Telemetry must be last to grab the optional modules (why?)
|
||||
MODULES += Telemetry
|
||||
|
||||
# Paths
|
||||
@ -120,6 +126,7 @@ OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
|
||||
|
||||
ifndef TESTAPP
|
||||
## MODULES
|
||||
SRC += ${foreach MOD, ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
## OPENPILOT CORE:
|
||||
SRC += ${OPMODULEDIR}/System/systemmod.c
|
||||
@ -159,13 +166,13 @@ SRC += $(OPUAVSYNTHDIR)/attitudeactual.c
|
||||
SRC += $(OPUAVSYNTHDIR)/manualcontrolcommand.c
|
||||
SRC += $(OPUAVSYNTHDIR)/i2cstats.c
|
||||
SRC += $(OPUAVSYNTHDIR)/watchdogstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/telemetrysettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/manualcontrolsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/mixersettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/firmwareiapobj.c
|
||||
SRC += $(OPUAVSYNTHDIR)/attitudesettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/camerastabsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/cameradesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gpsposition.c
|
||||
SRC += $(OPUAVSYNTHDIR)/hwsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c
|
||||
SRC += $(OPUAVSYNTHDIR)/receiveractivity.c
|
||||
@ -188,7 +195,7 @@ SRC += $(PIOSSTM32F10X)/pios_i2c.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_spi.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_ppm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_pwm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_spektrum.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_dsm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_sbus.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_debug.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_gpio.c
|
||||
@ -333,7 +340,7 @@ EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
EXTRAINCDIRS += $(AHRSBOOTLOADERINC)
|
||||
EXTRAINCDIRS += $(PYMITEINC)
|
||||
|
||||
EXTRAINCDIRS += ${foreach MOD, ${MODULES}, ${OPMODULEDIR}/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES}, ${OPMODULEDIR}/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
|
@ -36,8 +36,6 @@
|
||||
#include "openpilot.h"
|
||||
#include "uavobjectsinit.h"
|
||||
#include "hwsettings.h"
|
||||
#include "camerastab.h"
|
||||
#include "txpid.h"
|
||||
#include "systemmod.h"
|
||||
|
||||
/* Task Priorities */
|
||||
@ -75,17 +73,6 @@ int main()
|
||||
/* Initialize modules */
|
||||
MODULE_INITIALISE_ALL
|
||||
|
||||
/* Optional module initialization. This code might want to go somewhere else as
|
||||
* it grows */
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
if(optionalModules[HWSETTINGS_OPTIONALMODULES_CAMERASTABILIZATION] == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
CameraStabInitialize();
|
||||
}
|
||||
if(optionalModules[HWSETTINGS_OPTIONALMODULES_TXPID] == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
TxPIDInitialize();
|
||||
}
|
||||
|
||||
/* swap the stack to use the IRQ stack */
|
||||
Stack_Change();
|
||||
|
||||
|
@ -46,7 +46,7 @@
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
|
||||
/* Supported receiver interfaces */
|
||||
#define PIOS_INCLUDE_SPEKTRUM
|
||||
#define PIOS_INCLUDE_DSM
|
||||
#define PIOS_INCLUDE_SBUS
|
||||
#define PIOS_INCLUDE_PPM
|
||||
#define PIOS_INCLUDE_PWM
|
||||
@ -54,7 +54,8 @@
|
||||
|
||||
/* Supported USART-based PIOS modules */
|
||||
#define PIOS_INCLUDE_TELEMETRY_RF
|
||||
//#define PIOS_INCLUDE_GPS
|
||||
#define PIOS_INCLUDE_GPS
|
||||
#define PIOS_GPS_MINIMAL
|
||||
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
#define PIOS_INCLUDE_SPI
|
||||
@ -80,12 +81,6 @@
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define TELEM_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 220
|
||||
#define HEAP_LIMIT_CRITICAL 40
|
||||
@ -107,6 +102,9 @@
|
||||
// This can't be too high to stop eventdispatcher thread overflowing
|
||||
#define PIOS_EVENTDISAPTCHER_QUEUE 10
|
||||
|
||||
/* PIOS Initcall infrastructure */
|
||||
#define PIOS_INCLUDE_INITCALL
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
|
@ -44,11 +44,4 @@
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define TELEM_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
|
||||
#endif /* PIOS_CONFIG_POSIX_H */
|
||||
|
@ -410,6 +410,133 @@ static const struct pios_tim_channel pios_tim_servoport_all_pins[] = {
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM4,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM1,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
|
||||
// Receiver port pins
|
||||
// S3-S6 inputs are used as outputs in this case
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
#if defined(PIOS_INCLUDE_USART)
|
||||
|
||||
#include "pios_usart_priv.h"
|
||||
@ -568,13 +695,13 @@ static const struct pios_usart_cfg pios_usart_gps_flexi_cfg = {
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
/*
|
||||
* SPEKTRUM USART
|
||||
* Spektrum/JR DSM USART
|
||||
*/
|
||||
#include <pios_spektrum_priv.h>
|
||||
#include <pios_dsm_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_spektrum_main_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
@ -610,7 +737,7 @@ static const struct pios_usart_cfg pios_usart_spektrum_main_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_spektrum_cfg pios_spektrum_main_cfg = {
|
||||
static const struct pios_dsm_cfg pios_dsm_main_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
@ -619,10 +746,9 @@ static const struct pios_spektrum_cfg pios_spektrum_main_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.remap = 0,
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_spektrum_flexi_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
@ -658,7 +784,7 @@ static const struct pios_usart_cfg pios_usart_spektrum_flexi_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_spektrum_cfg pios_spektrum_flexi_cfg = {
|
||||
static const struct pios_dsm_cfg pios_dsm_flexi_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
@ -667,14 +793,13 @@ static const struct pios_spektrum_cfg pios_spektrum_flexi_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.remap = 0,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPEKTRUM */
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
/*
|
||||
* SBUS USART
|
||||
* S.Bus USART
|
||||
*/
|
||||
#include <pios_sbus_priv.h>
|
||||
|
||||
@ -740,7 +865,7 @@ static const struct pios_sbus_cfg pios_sbus_cfg = {
|
||||
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192
|
||||
|
||||
#define PIOS_COM_GPS_RX_BUF_LEN 96
|
||||
#define PIOS_COM_GPS_RX_BUF_LEN 32
|
||||
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
|
||||
@ -795,6 +920,22 @@ const struct pios_servo_cfg pios_servo_cfg = {
|
||||
.num_channels = NELEMENTS(pios_tim_servoport_all_pins),
|
||||
};
|
||||
|
||||
const struct pios_servo_cfg pios_servo_rcvr_cfg = {
|
||||
.tim_oc_init = {
|
||||
.TIM_OCMode = TIM_OCMode_PWM1,
|
||||
.TIM_OutputState = TIM_OutputState_Enable,
|
||||
.TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
|
||||
.TIM_OCPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCNPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCIdleState = TIM_OCIdleState_Reset,
|
||||
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
|
||||
},
|
||||
.channels = pios_tim_servoport_rcvrport_pins,
|
||||
.num_channels = NELEMENTS(pios_tim_servoport_rcvrport_pins),
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
* PPM Inputs
|
||||
*/
|
||||
@ -916,7 +1057,7 @@ void PIOS_I2C_main_adapter_er_irq_handler(void)
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
/* One slot per selectable receiver group.
|
||||
* eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS
|
||||
* eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS
|
||||
* NOTE: No slot in this map for NONE.
|
||||
*/
|
||||
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
@ -1025,7 +1166,7 @@ void PIOS_Board_Init(void) {
|
||||
}
|
||||
|
||||
uint32_t pios_sbus_id;
|
||||
if (PIOS_SBUS_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
|
||||
if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
@ -1056,31 +1197,48 @@ void PIOS_Board_Init(void) {
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_SPEKTRUM1:
|
||||
case HWSETTINGS_CC_MAINPORT_SPEKTRUM2:
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
case HWSETTINGS_CC_MAINPORT_DSM2:
|
||||
case HWSETTINGS_CC_MAINPORT_DSMX10BIT:
|
||||
case HWSETTINGS_CC_MAINPORT_DSMX11BIT:
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
{
|
||||
uint32_t pios_usart_spektrum_id;
|
||||
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_main_cfg)) {
|
||||
enum pios_dsm_proto proto;
|
||||
switch (hwsettings_cc_mainport) {
|
||||
case HWSETTINGS_CC_MAINPORT_DSM2:
|
||||
proto = PIOS_DSM_PROTO_DSM2;
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_DSMX10BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX10BIT;
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_DSMX11BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX11BIT;
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
|
||||
uint32_t pios_usart_dsm_id;
|
||||
if (PIOS_USART_Init(&pios_usart_dsm_id, &pios_usart_dsm_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_spektrum_id;
|
||||
if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_main_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, 0)) {
|
||||
uint32_t pios_dsm_id;
|
||||
if (PIOS_DSM_Init(&pios_dsm_id,
|
||||
&pios_dsm_main_cfg,
|
||||
&pios_usart_com_driver,
|
||||
pios_usart_dsm_id,
|
||||
proto, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_spektrum_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_spektrum_rcvr_id, &pios_spektrum_rcvr_driver, pios_spektrum_id)) {
|
||||
uint32_t pios_dsm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (hwsettings_cc_mainport == HWSETTINGS_CC_MAINPORT_SPEKTRUM1) {
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM1] = pios_spektrum_rcvr_id;
|
||||
} else {
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM2] = pios_spektrum_rcvr_id;
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT] = pios_dsm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SPEKTRUM */
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_COMAUX:
|
||||
break;
|
||||
@ -1129,31 +1287,48 @@ void PIOS_Board_Init(void) {
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_SPEKTRUM1:
|
||||
case HWSETTINGS_CC_FLEXIPORT_SPEKTRUM2:
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
case HWSETTINGS_CC_FLEXIPORT_DSM2:
|
||||
case HWSETTINGS_CC_FLEXIPORT_DSMX10BIT:
|
||||
case HWSETTINGS_CC_FLEXIPORT_DSMX11BIT:
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
{
|
||||
uint32_t pios_usart_spektrum_id;
|
||||
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_flexi_cfg)) {
|
||||
enum pios_dsm_proto proto;
|
||||
switch (hwsettings_cc_flexiport) {
|
||||
case HWSETTINGS_CC_FLEXIPORT_DSM2:
|
||||
proto = PIOS_DSM_PROTO_DSM2;
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_DSMX10BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX10BIT;
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_DSMX11BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX11BIT;
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
|
||||
uint32_t pios_usart_dsm_id;
|
||||
if (PIOS_USART_Init(&pios_usart_dsm_id, &pios_usart_dsm_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_spektrum_id;
|
||||
if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_flexi_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, hwsettings_DSMxBind)) {
|
||||
uint32_t pios_dsm_id;
|
||||
if (PIOS_DSM_Init(&pios_dsm_id,
|
||||
&pios_dsm_flexi_cfg,
|
||||
&pios_usart_com_driver,
|
||||
pios_usart_dsm_id,
|
||||
proto, hwsettings_DSMxBind)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_spektrum_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_spektrum_rcvr_id, &pios_spektrum_rcvr_driver, pios_spektrum_id)) {
|
||||
uint32_t pios_dsm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (hwsettings_cc_flexiport == HWSETTINGS_CC_FLEXIPORT_SPEKTRUM1) {
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM1] = pios_spektrum_rcvr_id;
|
||||
} else {
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM2] = pios_spektrum_rcvr_id;
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT] = pios_dsm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SPEKTRUM */
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_COMAUX:
|
||||
break;
|
||||
@ -1190,6 +1365,7 @@ void PIOS_Board_Init(void) {
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMSERVO:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
{
|
||||
uint32_t pios_ppm_id;
|
||||
@ -1219,7 +1395,17 @@ void PIOS_Board_Init(void) {
|
||||
GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
|
||||
|
||||
#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS
|
||||
PIOS_Servo_Init(&pios_servo_cfg);
|
||||
switch (hwsettings_rcvrport) {
|
||||
case HWSETTINGS_CC_RCVRPORT_DISABLED:
|
||||
case HWSETTINGS_CC_RCVRPORT_PWM:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM:
|
||||
PIOS_Servo_Init(&pios_servo_cfg);
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMSERVO:
|
||||
case HWSETTINGS_CC_RCVRPORT_SERVO:
|
||||
PIOS_Servo_Init(&pios_servo_rcvr_cfg);
|
||||
break;
|
||||
}
|
||||
#else
|
||||
PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels));
|
||||
#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */
|
||||
|
@ -54,13 +54,7 @@
|
||||
|
||||
#define PIOS_INCLUDE_BMA180
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
|
@ -51,6 +51,7 @@
|
||||
#include "attitudeactual.h"
|
||||
#include "camerastabsettings.h"
|
||||
#include "cameradesired.h"
|
||||
#include "hwsettings.h"
|
||||
|
||||
//
|
||||
// Configuration
|
||||
@ -61,6 +62,8 @@
|
||||
|
||||
// Private variables
|
||||
|
||||
static uint8_t camerastabEnabled = 0;
|
||||
|
||||
// Private functions
|
||||
static void attitudeUpdated(UAVObjEvent* ev);
|
||||
static float bound(float val);
|
||||
@ -72,18 +75,43 @@ static float bound(float val);
|
||||
int32_t CameraStabInitialize(void)
|
||||
{
|
||||
static UAVObjEvent ev;
|
||||
ev.obj = AttitudeActualHandle();
|
||||
ev.instId = 0;
|
||||
ev.event = 0;
|
||||
|
||||
CameraStabSettingsInitialize();
|
||||
CameraDesiredInitialize();
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_CAMERASTAB] == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
camerastabEnabled=1;
|
||||
} else {
|
||||
camerastabEnabled=0;
|
||||
}
|
||||
|
||||
EventPeriodicCallbackCreate(&ev, attitudeUpdated, SAMPLE_PERIOD_MS / portTICK_RATE_MS);
|
||||
if (camerastabEnabled) {
|
||||
|
||||
AttitudeActualInitialize();
|
||||
|
||||
ev.obj = AttitudeActualHandle();
|
||||
ev.instId = 0;
|
||||
ev.event = 0;
|
||||
|
||||
CameraStabSettingsInitialize();
|
||||
CameraDesiredInitialize();
|
||||
|
||||
EventPeriodicCallbackCreate(&ev, attitudeUpdated, SAMPLE_PERIOD_MS / portTICK_RATE_MS);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* stub: module has no module thread */
|
||||
int32_t CameraStabStart(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(CameraStabInitialize, CameraStabStart)
|
||||
|
||||
static void attitudeUpdated(UAVObjEvent* ev)
|
||||
{
|
||||
if (ev->obj != AttitudeActualHandle())
|
||||
|
@ -43,11 +43,14 @@
|
||||
#include "gpssatellites.h"
|
||||
#include "WorldMagModel.h"
|
||||
#include "CoordinateConversions.h"
|
||||
#include "hwsettings.h"
|
||||
|
||||
|
||||
// ****************
|
||||
// Private functions
|
||||
|
||||
static void gpsTask(void *parameters);
|
||||
static void updateSettings();
|
||||
|
||||
#ifdef PIOS_GPS_SETS_HOMELOCATION
|
||||
static void setHomeLocation(GPSPositionData * gpsData);
|
||||
@ -75,6 +78,7 @@ static float GravityAccel(float latitude, float longitude, float altitude);
|
||||
// Private variables
|
||||
|
||||
static uint32_t gpsPort;
|
||||
static bool gpsEnabled = false;
|
||||
|
||||
static xTaskHandle gpsTaskHandle;
|
||||
|
||||
@ -95,12 +99,19 @@ static uint32_t numParsingErrors;
|
||||
|
||||
int32_t GPSStart(void)
|
||||
{
|
||||
// Start gps task
|
||||
xTaskCreate(gpsTask, (signed char *)"GPS", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &gpsTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_GPS, gpsTaskHandle);
|
||||
if (gpsEnabled) {
|
||||
if (gpsPort) {
|
||||
// Start gps task
|
||||
xTaskCreate(gpsTask, (signed char *)"GPS", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &gpsTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_GPS, gpsTaskHandle);
|
||||
return 0;
|
||||
}
|
||||
|
||||
return 0;
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the gps module
|
||||
* \return -1 if initialisation failed
|
||||
@ -108,20 +119,35 @@ int32_t GPSStart(void)
|
||||
*/
|
||||
int32_t GPSInitialize(void)
|
||||
{
|
||||
GPSPositionInitialize();
|
||||
GPSTimeInitialize();
|
||||
GPSSatellitesInitialize();
|
||||
#ifdef PIOS_GPS_SETS_HOMELOCATION
|
||||
HomeLocationInitialize();
|
||||
#endif
|
||||
|
||||
// TODO: Get gps settings object
|
||||
gpsPort = PIOS_COM_GPS;
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_GPS] == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
gpsEnabled = true;
|
||||
} else {
|
||||
gpsEnabled = false;
|
||||
}
|
||||
|
||||
gps_rx_buffer = pvPortMalloc(NMEA_MAX_PACKET_LENGTH);
|
||||
PIOS_Assert(gps_rx_buffer);
|
||||
if (gpsPort && gpsEnabled) {
|
||||
GPSPositionInitialize();
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
GPSTimeInitialize();
|
||||
GPSSatellitesInitialize();
|
||||
#endif
|
||||
#ifdef PIOS_GPS_SETS_HOMELOCATION
|
||||
HomeLocationInitialize();
|
||||
#endif
|
||||
HwSettingsInitialize();
|
||||
updateSettings();
|
||||
|
||||
return 0;
|
||||
gps_rx_buffer = pvPortMalloc(NMEA_MAX_PACKET_LENGTH);
|
||||
PIOS_Assert(gps_rx_buffer);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
MODULE_INITCALL(GPSInitialize, GPSStart)
|
||||
|
||||
@ -330,7 +356,47 @@ static void setHomeLocation(GPSPositionData * gpsData)
|
||||
}
|
||||
#endif
|
||||
|
||||
// ****************
|
||||
/**
|
||||
* Update the GPS settings, called on startup.
|
||||
* FIXME: This should be in the GPSSettings object. But objects have
|
||||
* too much overhead yet. Also the GPS has no any specific settings
|
||||
* like protocol, etc. Thus the HwSettings object which contains the
|
||||
* GPS port speed is used for now.
|
||||
*/
|
||||
static void updateSettings()
|
||||
{
|
||||
if (gpsPort) {
|
||||
|
||||
// Retrieve settings
|
||||
uint8_t speed;
|
||||
HwSettingsGPSSpeedGet(&speed);
|
||||
|
||||
// Set port speed
|
||||
switch (speed) {
|
||||
case HWSETTINGS_GPSSPEED_2400:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 2400);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_4800:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 4800);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_9600:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 9600);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_19200:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 19200);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_38400:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 38400);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_57600:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 57600);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_115200:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 115200);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -70,8 +70,10 @@ static bool nmeaProcessGPGGA(GPSPositionData * GpsData, bool* gpsDataUpdated, ch
|
||||
static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam);
|
||||
static bool nmeaProcessGPVTG(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam);
|
||||
static bool nmeaProcessGPGSA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam);
|
||||
static bool nmeaProcessGPZDA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam);
|
||||
static bool nmeaProcessGPGSV(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam);
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
static bool nmeaProcessGPZDA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam);
|
||||
static bool nmeaProcessGPGSV(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam);
|
||||
#endif //PIOS_GPS_MINIMAL
|
||||
|
||||
|
||||
static struct nmea_parser nmea_parsers[] = {
|
||||
@ -95,6 +97,7 @@ static struct nmea_parser nmea_parsers[] = {
|
||||
.handler = nmeaProcessGPRMC,
|
||||
.cnt = 0,
|
||||
},
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
{
|
||||
.prefix = "GPZDA",
|
||||
.handler = nmeaProcessGPZDA,
|
||||
@ -105,6 +108,7 @@ static struct nmea_parser nmea_parsers[] = {
|
||||
.handler = nmeaProcessGPGSV,
|
||||
.cnt = 0,
|
||||
},
|
||||
#endif //PIOS_GPS_MINIMAL
|
||||
};
|
||||
|
||||
static struct nmea_parser *NMEA_find_parser_by_prefix(const char *prefix)
|
||||
@ -428,6 +432,7 @@ static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, ch
|
||||
|
||||
*gpsDataUpdated = true;
|
||||
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
GPSTimeData gpst;
|
||||
GPSTimeGet(&gpst);
|
||||
|
||||
@ -436,6 +441,7 @@ static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, ch
|
||||
gpst.Second = (int)hms % 100;
|
||||
gpst.Minute = (((int)hms - gpst.Second) / 100) % 100;
|
||||
gpst.Hour = (int)hms / 10000;
|
||||
#endif //PIOS_GPS_MINIMAL
|
||||
|
||||
// get latitude [DDMM.mmmmm] [N|S]
|
||||
if (!NMEA_latlon_to_fixed_point(&GpsData->Latitude, param[3], param[4][0] == 'S')) {
|
||||
@ -453,6 +459,7 @@ static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, ch
|
||||
// get True course
|
||||
GpsData->Heading = NMEA_real_to_float(param[8]);
|
||||
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
// get Date of fix
|
||||
// TODO: Should really not use a float here to be safe
|
||||
float date = NMEA_real_to_float(param[9]);
|
||||
@ -461,6 +468,7 @@ static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, ch
|
||||
gpst.Day = (int)(date / 10000);
|
||||
gpst.Year += 2000;
|
||||
GPSTimeSet(&gpst);
|
||||
#endif //PIOS_GPS_MINIMAL
|
||||
|
||||
return true;
|
||||
}
|
||||
@ -488,6 +496,7 @@ static bool nmeaProcessGPVTG(GPSPositionData * GpsData, bool* gpsDataUpdated, ch
|
||||
return true;
|
||||
}
|
||||
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
/**
|
||||
* Parse an NMEA GPZDA sentence and update the @ref GPSTime object
|
||||
* \param[in] A pointer to a GPSPosition UAVObject to be updated (unused).
|
||||
@ -610,6 +619,7 @@ static bool nmeaProcessGPGSV(GPSPositionData * GpsData, bool* gpsDataUpdated, ch
|
||||
|
||||
return true;
|
||||
}
|
||||
#endif //PIOS_GPS_MINIMAL
|
||||
|
||||
/**
|
||||
* Parse an NMEA GPGSA sentence and update the given UAVObject
|
||||
|
@ -439,11 +439,11 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_PPM;
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM1:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_SPEKTRUM1;
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_DSMMAINPORT;
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM2:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_SPEKTRUM2;
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_DSMFLEXIPORT;
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_SBUS;
|
||||
|
@ -389,25 +389,24 @@ static void updateSystemAlarms()
|
||||
EventStats evStats;
|
||||
SystemStatsGet(&stats);
|
||||
|
||||
// Check heap
|
||||
if (stats.HeapRemaining < HEAP_LIMIT_CRITICAL) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else if (stats.HeapRemaining < HEAP_LIMIT_WARNING) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_WARNING);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY);
|
||||
}
|
||||
|
||||
// Check heap, IRQ stack and malloc failures
|
||||
if ( mallocFailed
|
||||
|| (stats.HeapRemaining < HEAP_LIMIT_CRITICAL)
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) && defined(CHECK_IRQ_STACK)
|
||||
// Check IRQ stack
|
||||
if (stats.IRQStackRemaining < IRQSTACK_LIMIT_CRITICAL) {
|
||||
|| (stats.IRQStackRemaining < IRQSTACK_LIMIT_CRITICAL)
|
||||
#endif
|
||||
) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else if (stats.IRQStackRemaining < IRQSTACK_LIMIT_WARNING) {
|
||||
} else if (
|
||||
(stats.HeapRemaining < HEAP_LIMIT_WARNING)
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) && defined(CHECK_IRQ_STACK)
|
||||
|| (stats.IRQStackRemaining < IRQSTACK_LIMIT_WARNING)
|
||||
#endif
|
||||
) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_WARNING);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Check CPU load
|
||||
if (stats.CPULoad > CPULOAD_LIMIT_CRITICAL) {
|
||||
@ -425,13 +424,6 @@ static void updateSystemAlarms()
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_STACKOVERFLOW);
|
||||
}
|
||||
|
||||
// Check for malloc failures
|
||||
if (mallocFailed) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_SDCARD)
|
||||
// Check for SD card
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
|
@ -34,7 +34,7 @@
|
||||
#include "telemetry.h"
|
||||
#include "flighttelemetrystats.h"
|
||||
#include "gcstelemetrystats.h"
|
||||
#include "telemetrysettings.h"
|
||||
#include "hwsettings.h"
|
||||
|
||||
// Private constants
|
||||
#define MAX_QUEUE_SIZE TELEM_QUEUE_SIZE
|
||||
@ -65,7 +65,6 @@ static xTaskHandle telemetryTxTaskHandle;
|
||||
static xTaskHandle telemetryRxTaskHandle;
|
||||
static uint32_t txErrors;
|
||||
static uint32_t txRetries;
|
||||
static TelemetrySettingsData settings;
|
||||
static uint32_t timeOfLastObjectUpdate;
|
||||
static UAVTalkConnection uavTalkCon;
|
||||
|
||||
@ -94,7 +93,6 @@ int32_t TelemetryStart(void)
|
||||
|
||||
// Listen to objects of interest
|
||||
GCSTelemetryStatsConnectQueue(priorityQueue);
|
||||
TelemetrySettingsConnectQueue(priorityQueue);
|
||||
|
||||
// Start telemetry tasks
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
|
||||
@ -117,11 +115,8 @@ int32_t TelemetryStart(void)
|
||||
*/
|
||||
int32_t TelemetryInitialize(void)
|
||||
{
|
||||
UAVObjEvent ev;
|
||||
|
||||
FlightTelemetryStatsInitialize();
|
||||
GCSTelemetryStatsInitialize();
|
||||
TelemetrySettingsInitialize();
|
||||
|
||||
// Initialize vars
|
||||
timeOfLastObjectUpdate = 0;
|
||||
@ -132,7 +127,9 @@ int32_t TelemetryInitialize(void)
|
||||
priorityQueue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
#endif
|
||||
|
||||
// Get telemetry settings object
|
||||
// Update telemetry settings
|
||||
telemetryPort = PIOS_COM_TELEM_RF;
|
||||
HwSettingsInitialize();
|
||||
updateSettings();
|
||||
|
||||
// Initialise UAVTalk
|
||||
@ -141,9 +138,9 @@ int32_t TelemetryInitialize(void)
|
||||
// Create periodic event that will be used to update the telemetry stats
|
||||
txErrors = 0;
|
||||
txRetries = 0;
|
||||
UAVObjEvent ev;
|
||||
memset(&ev, 0, sizeof(UAVObjEvent));
|
||||
EventPeriodicQueueCreate(&ev, priorityQueue, STATS_UPDATE_PERIOD_MS);
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
@ -226,8 +223,6 @@ static void processObjEvent(UAVObjEvent * ev)
|
||||
updateTelemetryStats();
|
||||
} else if (ev->obj == GCSTelemetryStatsHandle()) {
|
||||
gcsTelemetryStatsUpdated();
|
||||
} else if (ev->obj == TelemetrySettingsHandle()) {
|
||||
updateSettings();
|
||||
} else {
|
||||
// Only process event if connected to GCS or if object FlightTelemetryStats is updated
|
||||
FlightTelemetryStatsGet(&flightStats);
|
||||
@ -509,27 +504,45 @@ static void updateTelemetryStats()
|
||||
}
|
||||
|
||||
/**
|
||||
* Update the telemetry settings, called on startup and
|
||||
* each time the settings object is updated
|
||||
* Update the telemetry settings, called on startup.
|
||||
* FIXME: This should be in the TelemetrySettings object. But objects
|
||||
* have too much overhead yet. Also the telemetry has no any specific
|
||||
* settings, etc. Thus the HwSettings object which contains the
|
||||
* telemetry port speed is used for now.
|
||||
*/
|
||||
static void updateSettings()
|
||||
{
|
||||
// Set port
|
||||
telemetryPort = PIOS_COM_TELEM_RF;
|
||||
if (telemetryPort) {
|
||||
|
||||
// Retrieve settings
|
||||
TelemetrySettingsGet(&settings);
|
||||
// Retrieve settings
|
||||
uint8_t speed;
|
||||
HwSettingsTelemetrySpeedGet(&speed);
|
||||
|
||||
if (telemetryPort) {
|
||||
// Set port speed
|
||||
if (settings.Speed == TELEMETRYSETTINGS_SPEED_2400) PIOS_COM_ChangeBaud(telemetryPort, 2400);
|
||||
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_4800) PIOS_COM_ChangeBaud(telemetryPort, 4800);
|
||||
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_9600) PIOS_COM_ChangeBaud(telemetryPort, 9600);
|
||||
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_19200) PIOS_COM_ChangeBaud(telemetryPort, 19200);
|
||||
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_38400) PIOS_COM_ChangeBaud(telemetryPort, 38400);
|
||||
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_57600) PIOS_COM_ChangeBaud(telemetryPort, 57600);
|
||||
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_115200) PIOS_COM_ChangeBaud(telemetryPort, 115200);
|
||||
}
|
||||
// Set port speed
|
||||
switch (speed) {
|
||||
case HWSETTINGS_TELEMETRYSPEED_2400:
|
||||
PIOS_COM_ChangeBaud(telemetryPort, 2400);
|
||||
break;
|
||||
case HWSETTINGS_TELEMETRYSPEED_4800:
|
||||
PIOS_COM_ChangeBaud(telemetryPort, 4800);
|
||||
break;
|
||||
case HWSETTINGS_TELEMETRYSPEED_9600:
|
||||
PIOS_COM_ChangeBaud(telemetryPort, 9600);
|
||||
break;
|
||||
case HWSETTINGS_TELEMETRYSPEED_19200:
|
||||
PIOS_COM_ChangeBaud(telemetryPort, 19200);
|
||||
break;
|
||||
case HWSETTINGS_TELEMETRYSPEED_38400:
|
||||
PIOS_COM_ChangeBaud(telemetryPort, 38400);
|
||||
break;
|
||||
case HWSETTINGS_TELEMETRYSPEED_57600:
|
||||
PIOS_COM_ChangeBaud(telemetryPort, 57600);
|
||||
break;
|
||||
case HWSETTINGS_TELEMETRYSPEED_115200:
|
||||
PIOS_COM_ChangeBaud(telemetryPort, 115200);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -57,6 +57,7 @@
|
||||
#include "manualcontrolcommand.h"
|
||||
#include "stabilizationsettings.h"
|
||||
#include "flightstatus.h"
|
||||
#include "hwsettings.h"
|
||||
|
||||
//
|
||||
// Configuration
|
||||
@ -87,34 +88,58 @@ static float scale(float val, float inMin, float inMax, float outMin, float outM
|
||||
int32_t TxPIDInitialize(void)
|
||||
{
|
||||
static UAVObjEvent ev;
|
||||
ev.obj = AccessoryDesiredHandle();
|
||||
ev.instId = 0;
|
||||
ev.event = 0;
|
||||
|
||||
// Initialize settings object
|
||||
TxPIDSettingsInitialize();
|
||||
bool txPIDEnabled;
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
|
||||
HwSettingsInitialize();
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_TXPID] == HWSETTINGS_OPTIONALMODULES_ENABLED)
|
||||
txPIDEnabled = true;
|
||||
else
|
||||
txPIDEnabled = false;
|
||||
|
||||
if (txPIDEnabled) {
|
||||
ev.obj = AccessoryDesiredHandle();
|
||||
ev.instId = 0;
|
||||
ev.event = 0;
|
||||
|
||||
// Initialize settings object
|
||||
TxPIDSettingsInitialize();
|
||||
|
||||
#if (TELEMETRY_UPDATE_PERIOD_MS != 0)
|
||||
// Change StabilizationSettings update rate from OnChange to periodic
|
||||
// to prevent telemetry link flooding with frequent updates in case of
|
||||
// control channel jitter.
|
||||
// Warning: saving to flash with this code active will change the
|
||||
// StabilizationSettings update rate permanently. Use Metadata via
|
||||
// browser to reset to defaults (telemetryAcked=true, OnChange).
|
||||
UAVObjMetadata metadata;
|
||||
StabilizationSettingsGetMetadata(&metadata);
|
||||
metadata.telemetryAcked = 0;
|
||||
metadata.telemetryUpdateMode = UPDATEMODE_PERIODIC;
|
||||
metadata.telemetryUpdatePeriod = TELEMETRY_UPDATE_PERIOD_MS;
|
||||
StabilizationSettingsSetMetadata(&metadata);
|
||||
// Change StabilizationSettings update rate from OnChange to periodic
|
||||
// to prevent telemetry link flooding with frequent updates in case of
|
||||
// control channel jitter.
|
||||
// Warning: saving to flash with this code active will change the
|
||||
// StabilizationSettings update rate permanently. Use Metadata via
|
||||
// browser to reset to defaults (telemetryAcked=true, OnChange).
|
||||
UAVObjMetadata metadata;
|
||||
StabilizationSettingsGetMetadata(&metadata);
|
||||
metadata.telemetryAcked = 0;
|
||||
metadata.telemetryUpdateMode = UPDATEMODE_PERIODIC;
|
||||
metadata.telemetryUpdatePeriod = TELEMETRY_UPDATE_PERIOD_MS;
|
||||
StabilizationSettingsSetMetadata(&metadata);
|
||||
#endif
|
||||
|
||||
// Setup the callback function
|
||||
EventPeriodicCallbackCreate(&ev, updatePIDs, SAMPLE_PERIOD_MS / portTICK_RATE_MS);
|
||||
// Setup the callback function
|
||||
EventPeriodicCallbackCreate(&ev, updatePIDs, SAMPLE_PERIOD_MS / portTICK_RATE_MS);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* stub: module has no module thread */
|
||||
int32_t TxPIDStart(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(TxPIDInitialize, TxPIDStart)
|
||||
|
||||
/**
|
||||
* Update PIDs callback function
|
||||
*/
|
||||
|
@ -37,6 +37,9 @@ OUTDIR := $(TOP)/build/$(TARGET)
|
||||
# Set to YES to compile for debugging
|
||||
DEBUG ?= YES
|
||||
|
||||
# Include objects that are just nice information to show
|
||||
DIAGNOSTICS ?= YES
|
||||
|
||||
# Set to YES to use the Servo output pins for debugging via scope or logic analyser
|
||||
ENABLE_DEBUG_PINS ?= NO
|
||||
|
||||
@ -55,13 +58,16 @@ endif
|
||||
|
||||
FLASH_TOOL = OPENOCD
|
||||
|
||||
|
||||
# List of modules to include
|
||||
MODULES = Actuator Telemetry GPS ManualControl Altitude AHRSComms Stabilization Guidance FirmwareIAP
|
||||
OPTMODULES = CameraStab GPS
|
||||
MODULES = Actuator ManualControl Altitude AHRSComms Stabilization Guidance FirmwareIAP
|
||||
PYMODULES = FlightPlan
|
||||
#MODULES = Telemetry Example
|
||||
#MODULES = Telemetry MK/MKSerial
|
||||
#MODULES = Telemetry
|
||||
#MODULES += Osd/OsdEtStd
|
||||
MODULES += Telemetry
|
||||
|
||||
# Paths
|
||||
OPSYSTEM = ./System
|
||||
@ -125,6 +131,7 @@ PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
SRC += $(PYSRC)
|
||||
|
||||
## MODULES
|
||||
SRC += ${foreach MOD, ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
## OPENPILOT CORE:
|
||||
SRC += ${OPMODULEDIR}/System/systemmod.c
|
||||
@ -162,7 +169,7 @@ SRC += $(PIOSSTM32F10X)/pios_i2c.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_spi.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_ppm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_pwm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_spektrum.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_dsm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_sbus.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_tim.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_debug.c
|
||||
@ -307,7 +314,7 @@ EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
EXTRAINCDIRS += $(AHRSBOOTLOADERINC)
|
||||
EXTRAINCDIRS += $(PYMITEINC)
|
||||
|
||||
EXTRAINCDIRS += ${foreach MOD, ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
@ -385,12 +392,14 @@ CSTANDARD = -std=gnu99
|
||||
# Flags for C and C++ (arm-elf-gcc/arm-elf-g++)
|
||||
|
||||
ifeq ($(DEBUG),YES)
|
||||
CFLAGS = -g$(DEBUGF) -DDEBUG
|
||||
CFLAGS = -DDEBUG
|
||||
endif
|
||||
|
||||
# OP has enough memory to always enable optional objects
|
||||
CFLAGS += -DDIAGNOSTICS
|
||||
ifeq ($(DIAGNOSTICS),YES)
|
||||
CFLAGS = -DDIAGNOSTICS
|
||||
endif
|
||||
|
||||
CFLAGS += -g$(DEBUGF)
|
||||
CFLAGS += -O$(OPT)
|
||||
CFLAGS += -mcpu=$(MCU)
|
||||
CFLAGS += $(CDEFS)
|
||||
@ -472,9 +481,6 @@ endif
|
||||
endif
|
||||
|
||||
# Generate intermediate code
|
||||
gencode: ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h
|
||||
|
||||
$(PYSRC): gencode
|
||||
|
||||
# Generate code for PyMite
|
||||
${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py)
|
||||
@ -582,4 +588,4 @@ else
|
||||
endif
|
||||
|
||||
# Listing of phony targets.
|
||||
.PHONY : all build clean clean_list gencode install
|
||||
.PHONY : all build clean clean_list install
|
||||
|
@ -27,6 +27,9 @@
|
||||
# Set to YES to compile for debugging
|
||||
DEBUG ?= YES
|
||||
|
||||
# Include objects that are just nice information to show
|
||||
DIAGNOSTICS ?= YES
|
||||
|
||||
# Set to YES to use the Servo output pins for debugging via scope or logic analyser
|
||||
ENABLE_DEBUG_PINS ?= NO
|
||||
|
||||
@ -53,10 +56,12 @@ FLASH_TOOL = OPENOCD
|
||||
USE_THUMB_MODE = YES
|
||||
|
||||
# List of modules to include
|
||||
MODULES = Telemetry Actuator Stabilization Guidance ManualControl FlightPlan GPS
|
||||
OPTMODULES = CameraStab GPS
|
||||
MODULES = Telemetry Actuator Stabilization Guidance ManualControl
|
||||
#MODULES = Telemetry ManualControl Actuator Attitude Stabilization
|
||||
#MODULES = Telemetry Example
|
||||
#MODULES = Telemetry MK/MKSerial
|
||||
PYMODULES = FlightPlan
|
||||
|
||||
#MODULES += Osd/OsdEtStd
|
||||
|
||||
@ -121,6 +126,7 @@ UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python
|
||||
# use file-extension c for "c-only"-files
|
||||
|
||||
MODNAMES = $(notdir ${MODULES})
|
||||
MODNAMES += $(notdir ${OPTMODULES})
|
||||
|
||||
ifndef TESTAPP
|
||||
|
||||
@ -129,10 +135,13 @@ SRC += $(OUTDIR)/pmlib_img.c
|
||||
SRC += $(OUTDIR)/pmlib_nat.c
|
||||
SRC += $(OUTDIR)/pmlibusr_img.c
|
||||
SRC += $(OUTDIR)/pmlibusr_nat.c
|
||||
SRC += $(wildcard ${PYMITEVM}/*.c)
|
||||
SRC += $(wildcard ${PYMITEPLAT}/*.c)
|
||||
PYSRC += $(wildcard ${PYMITEVM}/*.c)
|
||||
PYSRC += $(wildcard ${PYMITEPLAT}/*.c)
|
||||
PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
SRC += $(PYSRC)
|
||||
|
||||
## MODULES
|
||||
SRC += ${foreach MOD, ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
SRC += ${OUTDIR}/InitMods.c
|
||||
## OPENPILOT CORE:
|
||||
@ -228,7 +237,7 @@ EXTRAINCDIRS += $(APPLIBDIR)
|
||||
EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Posix
|
||||
EXTRAINCDIRS += $(PYMITEINC)
|
||||
|
||||
EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
EXTRAINCDIRS += ${foreach MOD, ${PYMODULES} ${OPTMODULES} ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
@ -306,6 +315,10 @@ ifeq ($(DEBUG),YES)
|
||||
CFLAGS = -g$(DEBUGF) -DDEBUG
|
||||
endif
|
||||
|
||||
ifeq ($(DIAGNOSTICS),YES)
|
||||
CFLAGS = -DDIAGNOSTICS
|
||||
endif
|
||||
|
||||
CFLAGS += $(CFLAGS_UAVOBJECTS)
|
||||
CFLAGS += -DARCH_POSIX
|
||||
CFLAGS += -O$(OPT)
|
||||
@ -436,9 +449,6 @@ else
|
||||
quote =
|
||||
endif
|
||||
|
||||
# Generate intermediate code
|
||||
gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h
|
||||
|
||||
# Generate code for module initialization
|
||||
${OUTDIR}/InitMods.c: Makefile.posix
|
||||
@echo ${MSG_MODINIT}
|
||||
@ -453,9 +463,9 @@ ${OUTDIR}/InitMods.c: Makefile.posix
|
||||
@echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c
|
||||
|
||||
# Generate code for PyMite
|
||||
${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py)
|
||||
@echo ${MSG_PYMITEINIT}
|
||||
@$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py)
|
||||
${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py)
|
||||
@echo $(MSG_PYMITEINIT) $(call toprel, $@)
|
||||
@$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py)
|
||||
@$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h
|
||||
@$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py
|
||||
|
||||
@ -651,5 +661,5 @@ endif
|
||||
|
||||
# Listing of phony targets.
|
||||
.PHONY : all begin finish end sizebefore sizeafter gccversion \
|
||||
build elf hex bin lss sym clean clean_list program gencode
|
||||
build elf hex bin lss sym clean clean_list program
|
||||
|
||||
|
@ -44,7 +44,7 @@
|
||||
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
|
||||
#define PIOS_INCLUDE_SPEKTRUM
|
||||
#define PIOS_INCLUDE_DSM
|
||||
//#define PIOS_INCLUDE_SBUS
|
||||
#define PIOS_INCLUDE_PWM
|
||||
#define PIOS_INCLUDE_PPM
|
||||
@ -78,12 +78,6 @@
|
||||
/* Enable a priority queue in telemetry */
|
||||
#define PIOS_TELEM_PRIORITY_QUEUE
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define TELEM_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 4000
|
||||
#define HEAP_LIMIT_CRITICAL 1000
|
||||
@ -98,6 +92,8 @@
|
||||
/* GPS options */
|
||||
#define PIOS_GPS_SETS_HOMELOCATION
|
||||
|
||||
/* PIOS Initcall infrastructure */
|
||||
#define PIOS_INCLUDE_INITCALL
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
|
@ -50,15 +50,17 @@
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define TELEM_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
#define TELEM_QUEUE_SIZE 20
|
||||
#define PIOS_TELEM_STACK_SIZE 2048
|
||||
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 4000
|
||||
#define HEAP_LIMIT_CRITICAL 1000
|
||||
#define IRQSTACK_LIMIT_WARNING 150
|
||||
#define IRQSTACK_LIMIT_CRITICAL 80
|
||||
#define CPULOAD_LIMIT_WARNING 80
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
/* Stabilization options */
|
||||
#define PIOS_QUATERNION_STABILIZATION
|
||||
|
||||
|
@ -143,11 +143,11 @@ static void TaskTesting(void *pvParameters)
|
||||
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u\r", PIOS_BMP085_GetPressure());
|
||||
*/
|
||||
|
||||
#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));
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_DSM_Get(0), PIOS_DSM_Get(1), PIOS_DSM_Get(2), PIOS_DSM_Get(3), PIOS_DSM_Get(4), PIOS_DSM_Get(5), PIOS_DSM_Get(6), PIOS_DSM_Get(7));
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_SBUS_Get(0), PIOS_SBUS_Get(1), PIOS_SBUS_Get(2), PIOS_SBUS_Get(3), PIOS_SBUS_Get(4), PIOS_SBUS_Get(5), PIOS_SBUS_Get(6), PIOS_SBUS_Get(7));
|
||||
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));
|
||||
|
@ -31,7 +31,7 @@
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
#include <hwsettings.h>
|
||||
#include "manualcontrolsettings.h"
|
||||
#include <manualcontrolsettings.h>
|
||||
|
||||
//#define I2C_DEBUG_PIN 0
|
||||
//#define USART_GPS_DEBUG_PIN 1
|
||||
@ -538,13 +538,13 @@ void PIOS_RTC_IRQ_Handler (void)
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
/*
|
||||
* SPEKTRUM USART
|
||||
* Spektrum/JR DSM USART
|
||||
*/
|
||||
#include <pios_spektrum_priv.h>
|
||||
#include <pios_dsm_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_spektrum_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_dsm_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
@ -580,7 +580,7 @@ static const struct pios_usart_cfg pios_usart_spektrum_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_spektrum_cfg pios_spektrum_cfg = {
|
||||
static const struct pios_dsm_cfg pios_dsm_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
@ -589,10 +589,9 @@ static const struct pios_spektrum_cfg pios_spektrum_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.remap = 0,
|
||||
};
|
||||
|
||||
#endif /* PIOS_COM_SPEKTRUM */
|
||||
#endif /* PIOS_COM_DSM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
#error PIOS_INCLUDE_SBUS not implemented
|
||||
@ -1035,7 +1034,7 @@ static const struct stm32_gpio pios_debug_pins[] = {
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
/* One slot per selectable receiver group.
|
||||
* eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS
|
||||
* eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS
|
||||
* NOTE: No slot in this map for NONE.
|
||||
*/
|
||||
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
@ -1063,7 +1062,7 @@ uint32_t pios_com_telem_rf_id;
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
uint32_t pios_com_gps_id;
|
||||
uint32_t pios_com_aux_id;
|
||||
uint32_t pios_com_spektrum_id;
|
||||
uint32_t pios_com_dsm_id;
|
||||
|
||||
#include "ahrs_spi_comm.h"
|
||||
|
||||
@ -1204,24 +1203,46 @@ void PIOS_Board_Init(void) {
|
||||
case HWSETTINGS_OP_RCVRPORT_DEBUG:
|
||||
/* Not supported yet */
|
||||
break;
|
||||
case HWSETTINGS_OP_RCVRPORT_SPEKTRUM1:
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
case HWSETTINGS_OP_RCVRPORT_DSM2:
|
||||
case HWSETTINGS_OP_RCVRPORT_DSMX10BIT:
|
||||
case HWSETTINGS_OP_RCVRPORT_DSMX11BIT:
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
{
|
||||
uint32_t pios_usart_spektrum_id;
|
||||
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_cfg)) {
|
||||
enum pios_dsm_proto proto;
|
||||
switch (hwsettings_rcvrport) {
|
||||
case HWSETTINGS_OP_RCVRPORT_DSM2:
|
||||
proto = PIOS_DSM_PROTO_DSM2;
|
||||
break;
|
||||
case HWSETTINGS_OP_RCVRPORT_DSMX10BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX10BIT;
|
||||
break;
|
||||
case HWSETTINGS_OP_RCVRPORT_DSMX11BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX11BIT;
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
|
||||
uint32_t pios_usart_dsm_id;
|
||||
if (PIOS_USART_Init(&pios_usart_dsm_id, &pios_usart_dsm_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_spektrum_id;
|
||||
if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, false)) {
|
||||
uint32_t pios_dsm_id;
|
||||
if (PIOS_DSM_Init(&pios_dsm_id,
|
||||
&pios_dsm_cfg,
|
||||
&pios_usart_com_driver,
|
||||
pios_usart_dsm_id,
|
||||
proto, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_spektrum_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_spektrum_rcvr_id, &pios_spektrum_rcvr_driver, pios_spektrum_id)) {
|
||||
uint32_t pios_dsm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM1] = pios_spektrum_rcvr_id;
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT] = pios_dsm_rcvr_id;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
|
@ -29,6 +29,7 @@
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
|
||||
#include "hwsettings.h"
|
||||
#include "attituderaw.h"
|
||||
#include "attitudeactual.h"
|
||||
#include "positionactual.h"
|
||||
@ -39,7 +40,7 @@
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
/* One slot per selectable receiver group.
|
||||
* eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS
|
||||
* eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS
|
||||
* NOTE: No slot in this map for NONE.
|
||||
*/
|
||||
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
@ -187,6 +188,7 @@ void PIOS_Board_Init(void) {
|
||||
AttitudeActualInitialize();
|
||||
VelocityActualInitialize();
|
||||
PositionActualInitialize();
|
||||
HwSettingsInitialize();
|
||||
|
||||
}
|
||||
|
||||
|
@ -64,7 +64,6 @@ UAVOBJSRCFILENAMES += systemalarms
|
||||
UAVOBJSRCFILENAMES += systemsettings
|
||||
UAVOBJSRCFILENAMES += systemstats
|
||||
UAVOBJSRCFILENAMES += taskinfo
|
||||
UAVOBJSRCFILENAMES += telemetrysettings
|
||||
UAVOBJSRCFILENAMES += velocityactual
|
||||
UAVOBJSRCFILENAMES += velocitydesired
|
||||
UAVOBJSRCFILENAMES += watchdogstatus
|
||||
|
@ -222,10 +222,16 @@ extern uint32_t pios_com_telem_usb_id;
|
||||
#define PIOS_PWM_NUM_INPUTS 6
|
||||
|
||||
//-------------------------
|
||||
// Receiver SPEKTRUM input
|
||||
// Receiver DSM input
|
||||
//-------------------------
|
||||
#define PIOS_SPEKTRUM_MAX_DEVS 2
|
||||
#define PIOS_SPEKTRUM_NUM_INPUTS 12
|
||||
#define PIOS_DSM_MAX_DEVS 2
|
||||
#define PIOS_DSM_NUM_INPUTS 12
|
||||
|
||||
//-------------------------
|
||||
// Receiver S.Bus input
|
||||
//-------------------------
|
||||
#define PIOS_SBUS_MAX_DEVS 1
|
||||
#define PIOS_SBUS_NUM_INPUTS (16+2)
|
||||
|
||||
//-------------------------
|
||||
// Servo outputs
|
||||
|
@ -195,10 +195,16 @@ extern uint32_t pios_com_aux_id;
|
||||
#define PIOS_PWM_NUM_INPUTS 8
|
||||
|
||||
//-------------------------
|
||||
// Receiver SPEKTRUM input
|
||||
// Receiver DSM input
|
||||
//-------------------------
|
||||
#define PIOS_SPEKTRUM_MAX_DEVS 1
|
||||
#define PIOS_SPEKTRUM_NUM_INPUTS 12
|
||||
#define PIOS_DSM_MAX_DEVS 1
|
||||
#define PIOS_DSM_NUM_INPUTS 12
|
||||
|
||||
//-------------------------
|
||||
// Receiver S.Bus input
|
||||
//-------------------------
|
||||
#define PIOS_SBUS_MAX_DEVS 0
|
||||
#define PIOS_SBUS_NUM_INPUTS (16+2)
|
||||
|
||||
//-------------------------
|
||||
// Servo outputs
|
||||
|
@ -32,8 +32,8 @@
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
#if !(defined(PIOS_INCLUDE_SPEKTRUM) || defined(PIOS_INCLUDE_SBUS))
|
||||
#error Only supported with Spektrum or S.Bus interface!
|
||||
#if !(defined(PIOS_INCLUDE_DSM) || defined(PIOS_INCLUDE_SBUS))
|
||||
#error Only supported with Spektrum/JR DSM or S.Bus interface!
|
||||
#endif
|
||||
|
||||
/* Local Variables */
|
||||
|
407
flight/PiOS/STM32F10x/pios_dsm.c
Normal file
407
flight/PiOS/STM32F10x/pios_dsm.c
Normal file
@ -0,0 +1,407 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_DSM Spektrum/JR DSMx satellite receiver functions
|
||||
* @brief Code to bind and read Spektrum/JR DSMx satellite receiver serial stream
|
||||
* @{
|
||||
*
|
||||
* @file pios_dsm.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
|
||||
* @brief Code bind and read Spektrum/JR DSMx satellite receiver serial stream
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
#include "pios_dsm_priv.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
|
||||
/* Forward Declarations */
|
||||
static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel);
|
||||
static uint16_t PIOS_DSM_RxInCallback(uint32_t context,
|
||||
uint8_t *buf,
|
||||
uint16_t buf_len,
|
||||
uint16_t *headroom,
|
||||
bool *need_yield);
|
||||
static void PIOS_DSM_Supervisor(uint32_t dsm_id);
|
||||
|
||||
/* Local Variables */
|
||||
const struct pios_rcvr_driver pios_dsm_rcvr_driver = {
|
||||
.read = PIOS_DSM_Get,
|
||||
};
|
||||
|
||||
enum pios_dsm_dev_magic {
|
||||
PIOS_DSM_DEV_MAGIC = 0x44534d78,
|
||||
};
|
||||
|
||||
struct pios_dsm_state {
|
||||
uint16_t channel_data[PIOS_DSM_NUM_INPUTS];
|
||||
uint8_t received_data[DSM_FRAME_LENGTH];
|
||||
uint8_t receive_timer;
|
||||
uint8_t failsafe_timer;
|
||||
uint8_t frame_found;
|
||||
uint8_t byte_count;
|
||||
#ifdef DSM_LOST_FRAME_COUNTER
|
||||
uint8_t frames_lost_last;
|
||||
uint16_t frames_lost;
|
||||
#endif
|
||||
};
|
||||
|
||||
struct pios_dsm_dev {
|
||||
enum pios_dsm_dev_magic magic;
|
||||
const struct pios_dsm_cfg *cfg;
|
||||
enum pios_dsm_proto proto;
|
||||
struct pios_dsm_state state;
|
||||
};
|
||||
|
||||
/* Allocate DSM device descriptor */
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_dsm_dev *PIOS_DSM_Alloc(void)
|
||||
{
|
||||
struct pios_dsm_dev *dsm_dev;
|
||||
|
||||
dsm_dev = (struct pios_dsm_dev *)pvPortMalloc(sizeof(*dsm_dev));
|
||||
if (!dsm_dev)
|
||||
return NULL;
|
||||
|
||||
dsm_dev->magic = PIOS_DSM_DEV_MAGIC;
|
||||
return dsm_dev;
|
||||
}
|
||||
#else
|
||||
static struct pios_dsm_dev pios_dsm_devs[PIOS_DSM_MAX_DEVS];
|
||||
static uint8_t pios_dsm_num_devs;
|
||||
static struct pios_dsm_dev *PIOS_DSM_Alloc(void)
|
||||
{
|
||||
struct pios_dsm_dev *dsm_dev;
|
||||
|
||||
if (pios_dsm_num_devs >= PIOS_DSM_MAX_DEVS)
|
||||
return NULL;
|
||||
|
||||
dsm_dev = &pios_dsm_devs[pios_dsm_num_devs++];
|
||||
dsm_dev->magic = PIOS_DSM_DEV_MAGIC;
|
||||
|
||||
return dsm_dev;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Validate DSM device descriptor */
|
||||
static bool PIOS_DSM_Validate(struct pios_dsm_dev *dsm_dev)
|
||||
{
|
||||
return (dsm_dev->magic == PIOS_DSM_DEV_MAGIC);
|
||||
}
|
||||
|
||||
/* Try to bind DSMx satellite using specified number of pulses */
|
||||
static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t bind)
|
||||
{
|
||||
const struct pios_dsm_cfg *cfg = dsm_dev->cfg;
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Pin = cfg->bind.init.GPIO_Pin;
|
||||
GPIO_InitStructure.GPIO_Speed = cfg->bind.init.GPIO_Speed;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
|
||||
|
||||
/* just to limit bind pulses */
|
||||
if (bind > 10)
|
||||
bind = 10;
|
||||
|
||||
GPIO_Init(cfg->bind.gpio, &cfg->bind.init);
|
||||
|
||||
/* RX line, set high */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
|
||||
/* on CC works up to 140ms, guess bind window is around 20-140ms after power up */
|
||||
PIOS_DELAY_WaitmS(60);
|
||||
|
||||
for (int i = 0; i < bind ; i++) {
|
||||
/* RX line, drive low for 120us */
|
||||
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
}
|
||||
/* RX line, set input and wait for data */
|
||||
GPIO_Init(cfg->bind.gpio, &GPIO_InitStructure);
|
||||
}
|
||||
|
||||
/* Reset channels in case of lost signal or explicit failsafe receiver flag */
|
||||
static void PIOS_DSM_ResetChannels(struct pios_dsm_dev *dsm_dev)
|
||||
{
|
||||
struct pios_dsm_state *state = &(dsm_dev->state);
|
||||
for (int i = 0; i < PIOS_DSM_NUM_INPUTS; i++) {
|
||||
state->channel_data[i] = PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
}
|
||||
|
||||
/* Reset DSM receiver state */
|
||||
static void PIOS_DSM_ResetState(struct pios_dsm_dev *dsm_dev)
|
||||
{
|
||||
struct pios_dsm_state *state = &(dsm_dev->state);
|
||||
state->receive_timer = 0;
|
||||
state->failsafe_timer = 0;
|
||||
state->frame_found = 0;
|
||||
#ifdef DSM_LOST_FRAME_COUNTER
|
||||
state->frames_lost_last = 0;
|
||||
state->frames_lost = 0;
|
||||
#endif
|
||||
PIOS_DSM_ResetChannels(dsm_dev);
|
||||
}
|
||||
|
||||
/**
|
||||
* Check and unroll complete frame data.
|
||||
* \output 0 frame data accepted
|
||||
* \output -1 frame error found
|
||||
*/
|
||||
static int PIOS_DSM_UnrollChannels(struct pios_dsm_dev *dsm_dev)
|
||||
{
|
||||
struct pios_dsm_state *state = &(dsm_dev->state);
|
||||
uint8_t resolution;
|
||||
|
||||
#ifdef DSM_LOST_FRAME_COUNTER
|
||||
/* increment the lost frame counter */
|
||||
uint8_t frames_lost = state->received_data[0];
|
||||
state->frames_lost += (frames_lost - state->frames_lost_last);
|
||||
state->frames_lost_last = frames_lost;
|
||||
#endif
|
||||
|
||||
/* check the frame type assuming master satellite stream */
|
||||
uint8_t type = state->received_data[1];
|
||||
switch (type) {
|
||||
case 0x01:
|
||||
case 0x02:
|
||||
case 0x12:
|
||||
/* DSM2, DSMJ stream */
|
||||
if (dsm_dev->proto == PIOS_DSM_PROTO_DSM2) {
|
||||
/* DSM2/DSMJ resolution is known from the header */
|
||||
resolution = (type & DSM_DSM2_RES_MASK) ? 11 : 10;
|
||||
} else {
|
||||
/* DSMX resolution should explicitly be selected */
|
||||
goto stream_error;
|
||||
}
|
||||
break;
|
||||
case 0xA2:
|
||||
case 0xB2:
|
||||
/* DSMX stream */
|
||||
if (dsm_dev->proto == PIOS_DSM_PROTO_DSMX10BIT) {
|
||||
resolution = 10;
|
||||
} else if (dsm_dev->proto == PIOS_DSM_PROTO_DSMX11BIT) {
|
||||
resolution = 11;
|
||||
} else {
|
||||
/* DSMX resolution should explicitly be selected */
|
||||
goto stream_error;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
/* unknown yet data stream */
|
||||
goto stream_error;
|
||||
}
|
||||
|
||||
/* unroll channels */
|
||||
uint8_t *s = &(state->received_data[2]);
|
||||
uint16_t mask = (resolution == 10) ? 0x03ff : 0x07ff;
|
||||
|
||||
for (int i = 0; i < DSM_CHANNELS_PER_FRAME; i++) {
|
||||
uint16_t word = ((uint16_t)s[0] << 8) | s[1];
|
||||
s += 2;
|
||||
|
||||
/* skip empty channel slot */
|
||||
if (word == 0xffff)
|
||||
continue;
|
||||
|
||||
/* minimal data validation */
|
||||
if ((i > 0) && (word & DSM_2ND_FRAME_MASK)) {
|
||||
/* invalid frame data, ignore rest of the frame */
|
||||
goto stream_error;
|
||||
}
|
||||
|
||||
/* extract and save the channel value */
|
||||
uint8_t channel_num = (word >> resolution) & 0x0f;
|
||||
if (channel_num < PIOS_DSM_NUM_INPUTS)
|
||||
state->channel_data[channel_num] = (word & mask);
|
||||
}
|
||||
|
||||
#ifdef DSM_LOST_FRAME_COUNTER
|
||||
/* put lost frames counter into the last channel for debugging */
|
||||
state->channel_data[PIOS_DSM_NUM_INPUTS-1] = state->frames_lost;
|
||||
#endif
|
||||
|
||||
/* all channels processed */
|
||||
return 0;
|
||||
|
||||
stream_error:
|
||||
/* either DSM2 selected with DSMX stream found, or vice-versa */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Update decoder state processing input byte from the DSMx stream */
|
||||
static void PIOS_DSM_UpdateState(struct pios_dsm_dev *dsm_dev, uint8_t byte)
|
||||
{
|
||||
struct pios_dsm_state *state = &(dsm_dev->state);
|
||||
if (state->frame_found) {
|
||||
/* receiving the data frame */
|
||||
if (state->byte_count < DSM_FRAME_LENGTH) {
|
||||
/* store next byte */
|
||||
state->received_data[state->byte_count++] = byte;
|
||||
if (state->byte_count == DSM_FRAME_LENGTH) {
|
||||
/* full frame received - process and wait for new one */
|
||||
if (!PIOS_DSM_UnrollChannels(dsm_dev))
|
||||
/* data looking good */
|
||||
state->failsafe_timer = 0;
|
||||
|
||||
/* prepare for the next frame */
|
||||
state->frame_found = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Initialise DSM receiver interface */
|
||||
int32_t PIOS_DSM_Init(uint32_t *dsm_id,
|
||||
const struct pios_dsm_cfg *cfg,
|
||||
const struct pios_com_driver *driver,
|
||||
uint32_t lower_id,
|
||||
enum pios_dsm_proto proto,
|
||||
uint8_t bind)
|
||||
{
|
||||
PIOS_DEBUG_Assert(dsm_id);
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
PIOS_DEBUG_Assert(driver);
|
||||
|
||||
struct pios_dsm_dev *dsm_dev;
|
||||
|
||||
dsm_dev = (struct pios_dsm_dev *)PIOS_DSM_Alloc();
|
||||
if (!dsm_dev)
|
||||
return -1;
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
dsm_dev->cfg = cfg;
|
||||
dsm_dev->proto = proto;
|
||||
|
||||
/* Bind the receiver if requested */
|
||||
if (bind)
|
||||
PIOS_DSM_Bind(dsm_dev, bind);
|
||||
|
||||
PIOS_DSM_ResetState(dsm_dev);
|
||||
|
||||
*dsm_id = (uint32_t)dsm_dev;
|
||||
|
||||
/* Set comm driver callback */
|
||||
(driver->bind_rx_cb)(lower_id, PIOS_DSM_RxInCallback, *dsm_id);
|
||||
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_DSM_Supervisor, *dsm_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Comm byte received callback */
|
||||
static uint16_t PIOS_DSM_RxInCallback(uint32_t context,
|
||||
uint8_t *buf,
|
||||
uint16_t buf_len,
|
||||
uint16_t *headroom,
|
||||
bool *need_yield)
|
||||
{
|
||||
struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)context;
|
||||
|
||||
bool valid = PIOS_DSM_Validate(dsm_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/* process byte(s) and clear receive timer */
|
||||
for (uint8_t i = 0; i < buf_len; i++) {
|
||||
PIOS_DSM_UpdateState(dsm_dev, buf[i]);
|
||||
dsm_dev->state.receive_timer = 0;
|
||||
}
|
||||
|
||||
/* Always signal that we can accept another byte */
|
||||
if (headroom)
|
||||
*headroom = DSM_FRAME_LENGTH;
|
||||
|
||||
/* We never need a yield */
|
||||
*need_yield = false;
|
||||
|
||||
/* Always indicate that all bytes were consumed */
|
||||
return buf_len;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the value of an input channel
|
||||
* \param[in] channel Number of the channel desired (zero based)
|
||||
* \output PIOS_RCVR_INVALID channel not available
|
||||
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||
* \output >0 channel value
|
||||
*/
|
||||
static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)rcvr_id;
|
||||
|
||||
if (!PIOS_DSM_Validate(dsm_dev))
|
||||
return PIOS_RCVR_INVALID;
|
||||
|
||||
/* return error if channel is not available */
|
||||
if (channel >= PIOS_DSM_NUM_INPUTS)
|
||||
return PIOS_RCVR_INVALID;
|
||||
|
||||
/* may also be PIOS_RCVR_TIMEOUT set by other function */
|
||||
return dsm_dev->state.channel_data[channel];
|
||||
}
|
||||
|
||||
/**
|
||||
* Input data supervisor is called periodically and provides
|
||||
* two functions: frame syncing and failsafe triggering.
|
||||
*
|
||||
* DSM frames come at 11ms or 22ms rate at 115200bps.
|
||||
* RTC timer is running at 625Hz (1.6ms). So with divider 5 it gives
|
||||
* 8ms pause between frames which is good for both DSM frame rates.
|
||||
*
|
||||
* Data receive function must clear the receive_timer to confirm new
|
||||
* data reception. If no new data received in 100ms, we must call the
|
||||
* failsafe function which clears all channels.
|
||||
*/
|
||||
static void PIOS_DSM_Supervisor(uint32_t dsm_id)
|
||||
{
|
||||
struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)dsm_id;
|
||||
|
||||
bool valid = PIOS_DSM_Validate(dsm_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
struct pios_dsm_state *state = &(dsm_dev->state);
|
||||
|
||||
/* waiting for new frame if no bytes were received in 8ms */
|
||||
if (++state->receive_timer > 4) {
|
||||
state->frame_found = 1;
|
||||
state->byte_count = 0;
|
||||
state->receive_timer = 0;
|
||||
}
|
||||
|
||||
/* activate failsafe if no frames have arrived in 102.4ms */
|
||||
if (++state->failsafe_timer > 64) {
|
||||
PIOS_DSM_ResetChannels(dsm_dev);
|
||||
state->failsafe_timer = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -2,13 +2,13 @@
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SBUS Futaba S.Bus receiver functions
|
||||
* @brief Code to read Futaba S.Bus input
|
||||
* @addtogroup PIOS_SBus Futaba S.Bus receiver functions
|
||||
* @brief Code to read Futaba S.Bus receiver serial stream
|
||||
* @{
|
||||
*
|
||||
* @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)
|
||||
* @brief Code to read Futaba S.Bus receiver serial stream
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
@ -34,44 +34,166 @@
|
||||
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
|
||||
/* Provide a RCVR driver */
|
||||
static int32_t PIOS_SBUS_Get(uint32_t rcvr_id, uint8_t channel);
|
||||
/* Forward Declarations */
|
||||
static int32_t PIOS_SBus_Get(uint32_t rcvr_id, uint8_t channel);
|
||||
static uint16_t PIOS_SBus_RxInCallback(uint32_t context,
|
||||
uint8_t *buf,
|
||||
uint16_t buf_len,
|
||||
uint16_t *headroom,
|
||||
bool *need_yield);
|
||||
static void PIOS_SBus_Supervisor(uint32_t sbus_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;
|
||||
const struct pios_rcvr_driver pios_sbus_rcvr_driver = {
|
||||
.read = PIOS_SBus_Get,
|
||||
};
|
||||
|
||||
static void PIOS_SBUS_Supervisor(uint32_t sbus_id);
|
||||
enum pios_sbus_dev_magic {
|
||||
PIOS_SBUS_DEV_MAGIC = 0x53427573,
|
||||
};
|
||||
|
||||
/**
|
||||
* 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)
|
||||
struct pios_sbus_state {
|
||||
uint16_t channel_data[PIOS_SBUS_NUM_INPUTS];
|
||||
uint8_t received_data[SBUS_FRAME_LENGTH - 2];
|
||||
uint8_t receive_timer;
|
||||
uint8_t failsafe_timer;
|
||||
uint8_t frame_found;
|
||||
uint8_t byte_count;
|
||||
};
|
||||
|
||||
struct pios_sbus_dev {
|
||||
enum pios_sbus_dev_magic magic;
|
||||
const struct pios_sbus_cfg *cfg;
|
||||
struct pios_sbus_state state;
|
||||
};
|
||||
|
||||
/* Allocate S.Bus device descriptor */
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_sbus_dev *PIOS_SBus_Alloc(void)
|
||||
{
|
||||
for (int i = 0; i < SBUS_NUMBER_OF_CHANNELS; i++) {
|
||||
channel_data[i] = PIOS_RCVR_TIMEOUT;
|
||||
struct pios_sbus_dev *sbus_dev;
|
||||
|
||||
sbus_dev = (struct pios_sbus_dev *)pvPortMalloc(sizeof(*sbus_dev));
|
||||
if (!sbus_dev) return(NULL);
|
||||
|
||||
sbus_dev->magic = PIOS_SBUS_DEV_MAGIC;
|
||||
return(sbus_dev);
|
||||
}
|
||||
#else
|
||||
static struct pios_sbus_dev pios_sbus_devs[PIOS_SBUS_MAX_DEVS];
|
||||
static uint8_t pios_sbus_num_devs;
|
||||
static struct pios_sbus_dev *PIOS_SBus_Alloc(void)
|
||||
{
|
||||
struct pios_sbus_dev *sbus_dev;
|
||||
|
||||
if (pios_sbus_num_devs >= PIOS_SBUS_MAX_DEVS) {
|
||||
return (NULL);
|
||||
}
|
||||
|
||||
sbus_dev = &pios_sbus_devs[pios_sbus_num_devs++];
|
||||
sbus_dev->magic = PIOS_SBUS_DEV_MAGIC;
|
||||
|
||||
return (sbus_dev);
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Validate S.Bus device descriptor */
|
||||
static bool PIOS_SBus_Validate(struct pios_sbus_dev *sbus_dev)
|
||||
{
|
||||
return (sbus_dev->magic == PIOS_SBUS_DEV_MAGIC);
|
||||
}
|
||||
|
||||
/* Reset channels in case of lost signal or explicit failsafe receiver flag */
|
||||
static void PIOS_SBus_ResetChannels(struct pios_sbus_state *state)
|
||||
{
|
||||
for (int i = 0; i < PIOS_SBUS_NUM_INPUTS; i++) {
|
||||
state->channel_data[i] = PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
}
|
||||
|
||||
/* Reset S.Bus receiver state */
|
||||
static void PIOS_SBus_ResetState(struct pios_sbus_state *state)
|
||||
{
|
||||
state->receive_timer = 0;
|
||||
state->failsafe_timer = 0;
|
||||
state->frame_found = 0;
|
||||
PIOS_SBus_ResetChannels(state);
|
||||
}
|
||||
|
||||
/* Initialise S.Bus receiver interface */
|
||||
int32_t PIOS_SBus_Init(uint32_t *sbus_id,
|
||||
const struct pios_sbus_cfg *cfg,
|
||||
const struct pios_com_driver *driver,
|
||||
uint32_t lower_id)
|
||||
{
|
||||
PIOS_DEBUG_Assert(sbus_id);
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
PIOS_DEBUG_Assert(driver);
|
||||
|
||||
struct pios_sbus_dev *sbus_dev;
|
||||
|
||||
sbus_dev = (struct pios_sbus_dev *)PIOS_SBus_Alloc();
|
||||
if (!sbus_dev) goto out_fail;
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
sbus_dev->cfg = cfg;
|
||||
|
||||
PIOS_SBus_ResetState(&(sbus_dev->state));
|
||||
|
||||
*sbus_id = (uint32_t)sbus_dev;
|
||||
|
||||
/* 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);
|
||||
|
||||
/* Set comm driver callback */
|
||||
(driver->bind_rx_cb)(lower_id, PIOS_SBus_RxInCallback, *sbus_id);
|
||||
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_SBus_Supervisor, *sbus_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* unroll_channels() function computes channel_data[] from received_data[]
|
||||
* Get the value of an input channel
|
||||
* \param[in] channel Number of the channel desired (zero based)
|
||||
* \output PIOS_RCVR_INVALID channel not available
|
||||
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||
* \output >0 channel value
|
||||
*/
|
||||
static int32_t PIOS_SBus_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
struct pios_sbus_dev *sbus_dev = (struct pios_sbus_dev *)rcvr_id;
|
||||
|
||||
if (!PIOS_SBus_Validate(sbus_dev))
|
||||
return PIOS_RCVR_INVALID;
|
||||
|
||||
/* return error if channel is not available */
|
||||
if (channel >= PIOS_SBUS_NUM_INPUTS) {
|
||||
return PIOS_RCVR_INVALID;
|
||||
}
|
||||
|
||||
return sbus_dev->state.channel_data[channel];
|
||||
}
|
||||
|
||||
/**
|
||||
* Compute channel_data[] from received_data[].
|
||||
* For efficiency it unrolls first 8 channels without loops and does the
|
||||
* same for other 8 channels. Also 2 discrete channels will be set.
|
||||
*/
|
||||
static void unroll_channels(void)
|
||||
static void PIOS_SBus_UnrollChannels(struct pios_sbus_state *state)
|
||||
{
|
||||
uint8_t *s = received_data;
|
||||
uint16_t *d = channel_data;
|
||||
uint8_t *s = state->received_data;
|
||||
uint16_t *d = state->channel_data;
|
||||
|
||||
#define F(v,s) ((v) >> s) & 0x7ff
|
||||
#define F(v,s) (((v) >> (s)) & 0x7ff)
|
||||
|
||||
/* unroll channels 1-8 */
|
||||
*d++ = F(s[0] | s[1] << 8, 0);
|
||||
@ -98,132 +220,119 @@ static void unroll_channels(void)
|
||||
*d++ = (s[22] & SBUS_FLAG_DC2) ? SBUS_VALUE_MAX : SBUS_VALUE_MIN;
|
||||
}
|
||||
|
||||
/**
|
||||
* process_byte() function processes incoming byte from S.Bus stream
|
||||
*/
|
||||
static void process_byte(uint8_t b)
|
||||
/* Update decoder state processing input byte from the S.Bus stream */
|
||||
static void PIOS_SBus_UpdateState(struct pios_sbus_state *state, uint8_t b)
|
||||
{
|
||||
static uint8_t byte_count;
|
||||
/* should not process any data until new frame is found */
|
||||
if (!state->frame_found)
|
||||
return;
|
||||
|
||||
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;
|
||||
if (state->byte_count == 0) {
|
||||
if (b != SBUS_SOF_BYTE) {
|
||||
/* discard the whole frame if the 1st byte is not correct */
|
||||
state->frame_found = 0;
|
||||
} 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;
|
||||
/* do not store the SOF byte */
|
||||
state->byte_count++;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
/* do not store last frame byte as well */
|
||||
if (state->byte_count < SBUS_FRAME_LENGTH - 1) {
|
||||
/* store next byte */
|
||||
state->received_data[state->byte_count - 1] = b;
|
||||
state->byte_count++;
|
||||
} else {
|
||||
if (b == SBUS_EOF_BYTE) {
|
||||
/* full frame received */
|
||||
uint8_t flags = state->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 */
|
||||
PIOS_SBus_ResetChannels(state);
|
||||
} else {
|
||||
/* data looking good */
|
||||
PIOS_SBus_UnrollChannels(state);
|
||||
state->failsafe_timer = 0;
|
||||
}
|
||||
} else {
|
||||
/* discard whole frame */
|
||||
}
|
||||
|
||||
/* prepare for the next frame */
|
||||
state->frame_found = 0;
|
||||
}
|
||||
}
|
||||
|
||||
static uint16_t PIOS_SBUS_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
|
||||
/* Comm byte received callback */
|
||||
static uint16_t PIOS_SBus_RxInCallback(uint32_t context,
|
||||
uint8_t *buf,
|
||||
uint16_t buf_len,
|
||||
uint16_t *headroom,
|
||||
bool *need_yield)
|
||||
{
|
||||
struct pios_sbus_dev *sbus_dev = (struct pios_sbus_dev *)context;
|
||||
|
||||
bool valid = PIOS_SBus_Validate(sbus_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
struct pios_sbus_state *state = &(sbus_dev->state);
|
||||
|
||||
/* process byte(s) and clear receive timer */
|
||||
for (uint8_t i = 0; i < buf_len; i++) {
|
||||
process_byte(buf[i]);
|
||||
receive_timer = 0;
|
||||
PIOS_SBus_UpdateState(state, buf[i]);
|
||||
state->receive_timer = 0;
|
||||
}
|
||||
|
||||
/* Always signal that we can accept another byte */
|
||||
if (headroom) {
|
||||
if (headroom)
|
||||
*headroom = SBUS_FRAME_LENGTH;
|
||||
}
|
||||
|
||||
/* We never need a yield */
|
||||
*need_yield = false;
|
||||
|
||||
/* Always indicate that all bytes were consumed */
|
||||
return (buf_len);
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise S.Bus receiver interface
|
||||
*/
|
||||
int32_t PIOS_SBUS_Init(uint32_t * sbus_id, const struct pios_sbus_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id)
|
||||
{
|
||||
/* 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);
|
||||
|
||||
(driver->bind_rx_cb)(lower_id, PIOS_SBUS_RxInCallback, 0);
|
||||
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_SBUS_Supervisor, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
return (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 rcvr_id, uint8_t channel)
|
||||
{
|
||||
/* return error if channel is not available */
|
||||
if (channel >= SBUS_NUMBER_OF_CHANNELS) {
|
||||
return PIOS_RCVR_INVALID;
|
||||
}
|
||||
return channel_data[channel];
|
||||
return buf_len;
|
||||
}
|
||||
|
||||
/**
|
||||
* 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.
|
||||
* 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 frame rates.
|
||||
*
|
||||
* Data receive function must clear the receive_timer to confirm new
|
||||
* data reception. If no new data received in 100ms, we must call the
|
||||
* failsafe function which clears all channels.
|
||||
*/
|
||||
static void PIOS_SBUS_Supervisor(uint32_t sbus_id)
|
||||
static void PIOS_SBus_Supervisor(uint32_t sbus_id)
|
||||
{
|
||||
struct pios_sbus_dev *sbus_dev = (struct pios_sbus_dev *)sbus_id;
|
||||
|
||||
bool valid = PIOS_SBus_Validate(sbus_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
struct pios_sbus_state *state = &(sbus_dev->state);
|
||||
|
||||
/* waiting for new frame if no bytes were received in 3.2ms */
|
||||
if (++receive_timer > 2) {
|
||||
receive_timer = 0;
|
||||
frame_found = 0;
|
||||
if (++state->receive_timer > 2) {
|
||||
state->frame_found = 1;
|
||||
state->byte_count = 0;
|
||||
state->receive_timer = 0;
|
||||
}
|
||||
|
||||
/* activate failsafe if no frames have arrived in 102.4ms */
|
||||
if (++failsafe_timer > 64) {
|
||||
reset_channels();
|
||||
failsafe_timer = 0;
|
||||
if (++state->failsafe_timer > 64) {
|
||||
PIOS_SBus_ResetChannels(state);
|
||||
state->failsafe_timer = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -1,350 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SPEKTRUM Spektrum receiver functions
|
||||
* @brief Code to read Spektrum input
|
||||
* @{
|
||||
*
|
||||
* @file pios_spektrum.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @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"
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
|
||||
#include "pios_spektrum_priv.h"
|
||||
|
||||
/**
|
||||
* @Note Framesyncing:
|
||||
* The code resets the watchdog timer whenever a single byte is received, so what watchdog code
|
||||
* is never called if regularly getting bytes.
|
||||
* RTC timer is running @625Hz, supervisor timer has divider 5 so frame sync comes every 1/125Hz=8ms.
|
||||
* Good for both 11ms and 22ms framecycles
|
||||
*/
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Provide a RCVR driver */
|
||||
static int32_t PIOS_SPEKTRUM_Get(uint32_t rcvr_id, uint8_t channel);
|
||||
|
||||
const struct pios_rcvr_driver pios_spektrum_rcvr_driver = {
|
||||
.read = PIOS_SPEKTRUM_Get,
|
||||
};
|
||||
|
||||
enum pios_spektrum_dev_magic {
|
||||
PIOS_SPEKTRUM_DEV_MAGIC = 0xa9b9c9d9,
|
||||
};
|
||||
|
||||
struct pios_spektrum_fsm {
|
||||
uint16_t channel;
|
||||
uint16_t CaptureValue[PIOS_SPEKTRUM_NUM_INPUTS];
|
||||
uint16_t CaptureValueTemp[PIOS_SPEKTRUM_NUM_INPUTS];
|
||||
uint8_t prev_byte;
|
||||
uint8_t sync;
|
||||
uint8_t bytecount;
|
||||
uint8_t datalength;
|
||||
uint8_t frame_error;
|
||||
uint8_t sync_of;
|
||||
};
|
||||
|
||||
struct pios_spektrum_dev {
|
||||
enum pios_spektrum_dev_magic magic;
|
||||
const struct pios_spektrum_cfg * cfg;
|
||||
|
||||
struct pios_spektrum_fsm fsm;
|
||||
|
||||
uint16_t supv_timer;
|
||||
};
|
||||
|
||||
static bool PIOS_SPEKTRUM_validate(struct pios_spektrum_dev * spektrum_dev)
|
||||
{
|
||||
return (spektrum_dev->magic == PIOS_SPEKTRUM_DEV_MAGIC);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_spektrum_dev * PIOS_SPEKTRUM_alloc(void)
|
||||
{
|
||||
struct pios_spektrum_dev * spektrum_dev;
|
||||
|
||||
spektrum_dev = (struct pios_spektrum_dev *)pvPortMalloc(sizeof(*spektrum_dev));
|
||||
if (!spektrum_dev) return(NULL);
|
||||
|
||||
spektrum_dev->magic = PIOS_SPEKTRUM_DEV_MAGIC;
|
||||
return(spektrum_dev);
|
||||
}
|
||||
#else
|
||||
static struct pios_spektrum_dev pios_spektrum_devs[PIOS_SPEKTRUM_MAX_DEVS];
|
||||
static uint8_t pios_spektrum_num_devs;
|
||||
static struct pios_spektrum_dev * PIOS_SPEKTRUM_alloc(void)
|
||||
{
|
||||
struct pios_spektrum_dev * spektrum_dev;
|
||||
|
||||
if (pios_spektrum_num_devs >= PIOS_SPEKTRUM_MAX_DEVS) {
|
||||
return (NULL);
|
||||
}
|
||||
|
||||
spektrum_dev = &pios_spektrum_devs[pios_spektrum_num_devs++];
|
||||
spektrum_dev->magic = PIOS_SPEKTRUM_DEV_MAGIC;
|
||||
|
||||
return (spektrum_dev);
|
||||
}
|
||||
#endif
|
||||
|
||||
static void PIOS_SPEKTRUM_Supervisor(uint32_t spektrum_id);
|
||||
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg, uint8_t bind);
|
||||
static int32_t PIOS_SPEKTRUM_UpdateFSM(struct pios_spektrum_fsm * fsm, uint8_t b);
|
||||
|
||||
static uint16_t PIOS_SPEKTRUM_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
|
||||
{
|
||||
struct pios_spektrum_dev * spektrum_dev = (struct pios_spektrum_dev *)context;
|
||||
|
||||
bool valid = PIOS_SPEKTRUM_validate(spektrum_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/* process byte(s) and clear receive timer */
|
||||
for (uint8_t i = 0; i < buf_len; i++) {
|
||||
PIOS_SPEKTRUM_UpdateFSM(&(spektrum_dev->fsm), buf[i]);
|
||||
spektrum_dev->supv_timer = 0;
|
||||
}
|
||||
|
||||
/* Always signal that we can accept another byte */
|
||||
if (headroom) {
|
||||
*headroom = 1;
|
||||
}
|
||||
|
||||
/* We never need a yield */
|
||||
*need_yield = false;
|
||||
|
||||
/* Always indicate that all bytes were consumed */
|
||||
return (buf_len);
|
||||
}
|
||||
|
||||
static void PIOS_SPEKTRUM_ResetFSM(struct pios_spektrum_fsm * fsm)
|
||||
{
|
||||
fsm->channel = 0;
|
||||
fsm->prev_byte = 0xFF;
|
||||
fsm->sync = 0;
|
||||
fsm->bytecount = 0;
|
||||
fsm->datalength = 0;
|
||||
fsm->frame_error = 0;
|
||||
fsm->sync_of = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Decodes a byte
|
||||
* \param[in] b byte which should be spektrum decoded
|
||||
* \return 0 if no error
|
||||
* \return -1 if USART not available
|
||||
* \return -2 if buffer full (retry)
|
||||
*/
|
||||
static int32_t PIOS_SPEKTRUM_UpdateFSM(struct pios_spektrum_fsm * fsm, uint8_t b)
|
||||
{
|
||||
fsm->bytecount++;
|
||||
if (fsm->sync == 0) {
|
||||
/* Known sync bytes, 0x01, 0x02, 0x12, 0xb2 */
|
||||
/* 0xb2 DX8 3bind pulses only */
|
||||
if (fsm->bytecount == 2) {
|
||||
if ((b == 0x01) || (b == 0x02) || (b == 0xb2)) {
|
||||
fsm->datalength=0; // 10bit
|
||||
fsm->sync = 1;
|
||||
fsm->bytecount = 2;
|
||||
}
|
||||
else if(b == 0x12) {
|
||||
fsm->datalength=1; // 11bit
|
||||
fsm->sync = 1;
|
||||
fsm->bytecount = 2;
|
||||
}
|
||||
else
|
||||
{
|
||||
fsm->bytecount = 0;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if ((fsm->bytecount % 2) == 0) {
|
||||
uint16_t data;
|
||||
uint8_t channeln;
|
||||
|
||||
fsm->channel = (fsm->prev_byte << 8) + b;
|
||||
channeln = (fsm->channel >> (10+fsm->datalength)) & 0x0F;
|
||||
data = fsm->channel & (0x03FF+(0x0400*fsm->datalength));
|
||||
if(channeln==0 && data<10) // discard frame if throttle misbehaves
|
||||
{
|
||||
fsm->frame_error=1;
|
||||
}
|
||||
if (channeln < PIOS_SPEKTRUM_NUM_INPUTS && !fsm->frame_error)
|
||||
fsm->CaptureValueTemp[channeln] = data;
|
||||
}
|
||||
}
|
||||
if (fsm->bytecount == 16) {
|
||||
fsm->bytecount = 0;
|
||||
fsm->sync = 0;
|
||||
fsm->sync_of = 0;
|
||||
if (!fsm->frame_error)
|
||||
{
|
||||
for(int i=0;i<PIOS_SPEKTRUM_NUM_INPUTS;i++)
|
||||
{
|
||||
fsm->CaptureValue[i] = fsm->CaptureValueTemp[i];
|
||||
}
|
||||
}
|
||||
fsm->frame_error=0;
|
||||
}
|
||||
fsm->prev_byte = b;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Bind and Initialise Spektrum satellite receiver
|
||||
*/
|
||||
int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t bind)
|
||||
{
|
||||
PIOS_DEBUG_Assert(spektrum_id);
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
PIOS_DEBUG_Assert(driver);
|
||||
|
||||
struct pios_spektrum_dev * spektrum_dev;
|
||||
|
||||
spektrum_dev = (struct pios_spektrum_dev *) PIOS_SPEKTRUM_alloc();
|
||||
if (!spektrum_dev) goto out_fail;
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
spektrum_dev->cfg = cfg;
|
||||
|
||||
if (bind) {
|
||||
PIOS_SPEKTRUM_Bind(cfg,bind);
|
||||
}
|
||||
|
||||
PIOS_SPEKTRUM_ResetFSM(&(spektrum_dev->fsm));
|
||||
|
||||
*spektrum_id = (uint32_t)spektrum_dev;
|
||||
|
||||
(driver->bind_rx_cb)(lower_id, PIOS_SPEKTRUM_RxInCallback, *spektrum_id);
|
||||
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_SPEKTRUM_Supervisor, *spektrum_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
return (0);
|
||||
|
||||
out_fail:
|
||||
return(-1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the value of an input channel
|
||||
* \param[in] Channel Number of the channel desired
|
||||
* \output -1 Channel not available
|
||||
* \output >0 Channel value
|
||||
*/
|
||||
static int32_t PIOS_SPEKTRUM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
struct pios_spektrum_dev * spektrum_dev = (struct pios_spektrum_dev *)rcvr_id;
|
||||
|
||||
if(!PIOS_SPEKTRUM_validate(spektrum_dev))
|
||||
return PIOS_RCVR_INVALID;
|
||||
|
||||
/* Return error if channel not available */
|
||||
if (channel >= PIOS_SPEKTRUM_NUM_INPUTS) {
|
||||
return PIOS_RCVR_INVALID;
|
||||
}
|
||||
return spektrum_dev->fsm.CaptureValue[channel];
|
||||
}
|
||||
|
||||
/**
|
||||
* Spektrum bind function
|
||||
* \output true Successful bind
|
||||
* \output false Bind failed
|
||||
*/
|
||||
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg, uint8_t bind)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Pin = cfg->bind.init.GPIO_Pin;
|
||||
GPIO_InitStructure.GPIO_Speed = cfg->bind.init.GPIO_Speed;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
|
||||
|
||||
/* just to limit bind pulses */
|
||||
bind=(bind<=10)?bind:10;
|
||||
|
||||
GPIO_Init(cfg->bind.gpio, &cfg->bind.init);
|
||||
/* RX line, set high */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
|
||||
/* on CC works upto 140ms, I guess bind window is around 20-140ms after powerup */
|
||||
PIOS_DELAY_WaitmS(60);
|
||||
|
||||
for (int i = 0; i < bind ; i++) {
|
||||
/* RX line, drive low for 120us */
|
||||
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
}
|
||||
/* RX line, set input and wait for data, PIOS_SPEKTRUM_Init */
|
||||
GPIO_Init(cfg->bind.gpio, &GPIO_InitStructure);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
*@brief This function is called between frames and when a spektrum word hasnt been decoded for too long
|
||||
*@brief clears the channel values
|
||||
*/
|
||||
static void PIOS_SPEKTRUM_Supervisor(uint32_t spektrum_id)
|
||||
{
|
||||
struct pios_spektrum_dev * spektrum_dev = (struct pios_spektrum_dev *)spektrum_id;
|
||||
|
||||
bool valid = PIOS_SPEKTRUM_validate(spektrum_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/* 625hz */
|
||||
spektrum_dev->supv_timer++;
|
||||
if(spektrum_dev->supv_timer > 4) {
|
||||
/* sync between frames */
|
||||
struct pios_spektrum_fsm * fsm = &(spektrum_dev->fsm);
|
||||
|
||||
fsm->sync = 0;
|
||||
fsm->bytecount = 0;
|
||||
fsm->prev_byte = 0xFF;
|
||||
fsm->frame_error = 0;
|
||||
fsm->sync_of++;
|
||||
/* watchdog activated after 200ms silence */
|
||||
if (fsm->sync_of > 30) {
|
||||
|
||||
/* signal lost */
|
||||
fsm->sync_of = 0;
|
||||
for (int i = 0; i < PIOS_SPEKTRUM_NUM_INPUTS; i++) {
|
||||
fsm->CaptureValue[i] = PIOS_RCVR_TIMEOUT;
|
||||
fsm->CaptureValueTemp[i] = PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
}
|
||||
spektrum_dev->supv_timer = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -2,13 +2,12 @@
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SPEKTRUM Spektrum receiver functions
|
||||
* @addtogroup PIOS_DSM Spektrum/JR DSMx satellite receiver functions
|
||||
* @{
|
||||
*
|
||||
* @file pios_spektrum.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org)
|
||||
* @brief Spektrum satellite functions header.
|
||||
* @file pios_dsm.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
|
||||
* @brief Spektrum/JR DSMx satellite receiver functions header.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
@ -28,16 +27,16 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_SPEKTRUM_H
|
||||
#define PIOS_SPEKTRUM_H
|
||||
#ifndef PIOS_DSM_H
|
||||
#define PIOS_DSM_H
|
||||
|
||||
/* Global Types */
|
||||
|
||||
/* Public Functions */
|
||||
|
||||
#endif /* PIOS_SPEKTRUM_H */
|
||||
#endif /* PIOS_DSM_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
* @}
|
||||
* @}
|
||||
*/
|
139
flight/PiOS/inc/pios_dsm_priv.h
Normal file
139
flight/PiOS/inc/pios_dsm_priv.h
Normal file
@ -0,0 +1,139 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_DSM Spektrum/JR DSMx satellite receiver functions
|
||||
* @brief PIOS interface to bind and read Spektrum/JR DSMx satellite receiver
|
||||
* @{
|
||||
*
|
||||
* @file pios_dsm_priv.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
|
||||
* @brief Spektrum/JR DSMx satellite receiver 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_DSM_PRIV_H
|
||||
#define PIOS_DSM_PRIV_H
|
||||
|
||||
#include <pios.h>
|
||||
#include <pios_stm32.h>
|
||||
#include <pios_usart_priv.h>
|
||||
|
||||
/*
|
||||
* Currently known DSMx (DSM2, DSMJ, DSMX) satellite serial port settings:
|
||||
* 115200bps serial stream, 8 bits, no parity, 1 stop bit
|
||||
* size of each frame: 16 bytes
|
||||
* data resolution: 10 or 11 bits
|
||||
* number of frames: 1 or 2
|
||||
* frame period: 11ms or 22ms
|
||||
*
|
||||
* Currently known DSMx frame structure:
|
||||
* 2 bytes - depend on protocol version:
|
||||
* for DSM2/DSMJ:
|
||||
* 1 byte - lost frame counter (8 bit)
|
||||
* 1 byte - data format (for master receiver bound with 3 or 5 pulses),
|
||||
* or unknown (for slave receiver bound with 4 or 6 pulses,
|
||||
* some sources call it also the lost frame counter)
|
||||
* for DSMX:
|
||||
* 1 byte - unknown data (does not look like lost frame counter)
|
||||
* 1 byte - unknown data, has been seen only 0xB2 so far
|
||||
|
||||
* 14 bytes - up to 7 channels (16 bit word per channel) with encoded channel
|
||||
* number, channel value, the "2nd frame in a sequence" flag.
|
||||
* Unused channels have FF FF instead of data bytes.
|
||||
*
|
||||
* Data format identification:
|
||||
* - for DSM2/DSMJ: [0 0 0 R 0 0 N1 N0]
|
||||
* where
|
||||
* R is data resolution (0 - 10 bits, 1 - 11 bits),
|
||||
* N1..N0 is the number of frames required to receive all channel
|
||||
* data (01 or 10 are known to the moment, which means 1 or 2 frames).
|
||||
* Three values for the transmitter information byte have been seen
|
||||
* thus far: 0x01, 0x02, 0x12.
|
||||
* - for DSMX this byte contains just 0xB2 or 0xA2 value for any resolution.
|
||||
* It is not known at the moment how to find the exact resolution from the
|
||||
* DSMX data stream. The frame number (1 or 2) and 10/11 bit resolution were
|
||||
* found in different data streams. So it is safer at the moment to ask user
|
||||
* explicitly choose the resolution.
|
||||
* Also some weird throttle channel (0) behavior was found in some streams
|
||||
* from DX8 transmitter (all zeroes). Thus DSMX needs special processing.
|
||||
*
|
||||
* Channel data are:
|
||||
* - for 10 bit: [F 0 C3 C2 C1 C0 D9 D8 D7 D6 D5 D4 D3 D2 D1 D0]
|
||||
* - for 11 bit: [F C3 C2 C1 C0 D10 D9 D8 D7 D6 D5 D4 D3 D2 D1 D0]
|
||||
* where
|
||||
* F is normally 0 but set to 1 for the first channel of the 2nd frame,
|
||||
* C3 to C0 is the channel number, 4 bit, zero-based, in any order,
|
||||
* Dx..D0 - channel data (10 or 11 bits)
|
||||
*
|
||||
* DSM2 protocol bug: in some cases in 2-frame format some bytes of the
|
||||
* frame can contain invalid values from the previous frame. They usually
|
||||
* are the last 5 bytes and can be equal to FF or other data from last
|
||||
* frame. There is no explicit workaround currently known.
|
||||
*
|
||||
* Binding: the number of pulses within bind window after power up defines
|
||||
* if this receiver is a master (provides receiver capabilities info to
|
||||
* the transmitter to choose data format) or slave (does not respond to
|
||||
* the transmitter which falls back to the old DSM mode in that case).
|
||||
* Currently known are 3(4) pulses for low resolution (10 bit) mode, and
|
||||
* 5(6) pulses for high resolution (11 bit) mode. Thus only 3 or 5 pulses
|
||||
* should be used for stand-alone satellite receiver to be bound correctly
|
||||
* as the master. 5 pulses (high resolution) mode simulates high-end
|
||||
* receivers which should work in all cases except user explicitly wants
|
||||
* to bind in low resolution mode.
|
||||
*/
|
||||
|
||||
#define DSM_CHANNELS_PER_FRAME 7
|
||||
#define DSM_FRAME_LENGTH (1+1+DSM_CHANNELS_PER_FRAME*2)
|
||||
#define DSM_DSM2_RES_MASK 0x0010
|
||||
#define DSM_2ND_FRAME_MASK 0x8000
|
||||
|
||||
/*
|
||||
* Include lost frame counter and provide it as a last channel value
|
||||
* for debugging. Currently is not used by the receiver layer.
|
||||
*/
|
||||
//#define DSM_LOST_FRAME_COUNTER
|
||||
|
||||
/* DSM protocol variations */
|
||||
enum pios_dsm_proto {
|
||||
PIOS_DSM_PROTO_DSM2,
|
||||
PIOS_DSM_PROTO_DSMX10BIT,
|
||||
PIOS_DSM_PROTO_DSMX11BIT,
|
||||
};
|
||||
|
||||
/* DSM receiver instance configuration */
|
||||
struct pios_dsm_cfg {
|
||||
struct stm32_gpio bind;
|
||||
};
|
||||
|
||||
extern const struct pios_rcvr_driver pios_dsm_rcvr_driver;
|
||||
|
||||
extern int32_t PIOS_DSM_Init(uint32_t *dsm_id,
|
||||
const struct pios_dsm_cfg *cfg,
|
||||
const struct pios_com_driver *driver,
|
||||
uint32_t lower_id,
|
||||
enum pios_dsm_proto proto,
|
||||
uint8_t bind);
|
||||
|
||||
#endif /* PIOS_DSM_PRIV_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SBUS Futaba S.Bus receiver functions
|
||||
* @addtogroup PIOS_SBus Futaba S.Bus receiver functions
|
||||
* @{
|
||||
*
|
||||
* @file pios_sbus.h
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SBUS S.Bus Functions
|
||||
* @addtogroup PIOS_SBus S.Bus Functions
|
||||
* @brief PIOS interface to read and write from Futaba S.Bus port
|
||||
* @{
|
||||
*
|
||||
@ -63,7 +63,9 @@
|
||||
* S.Bus protocol provides 16 proportional and 2 discrete channels.
|
||||
* Do not change unless driver code is updated accordingly.
|
||||
*/
|
||||
#define SBUS_NUMBER_OF_CHANNELS (16 + 2)
|
||||
#if (PIOS_SBUS_NUM_INPUTS != (16+2))
|
||||
#error "S.Bus protocol provides 16 proportional and 2 discrete channels"
|
||||
#endif
|
||||
|
||||
/* Discrete channels represented as bits, provide values for them */
|
||||
#define SBUS_VALUE_MIN 352
|
||||
@ -81,7 +83,10 @@ struct pios_sbus_cfg {
|
||||
|
||||
extern const struct pios_rcvr_driver pios_sbus_rcvr_driver;
|
||||
|
||||
extern int32_t PIOS_SBUS_Init(uint32_t * sbus_id, const struct pios_sbus_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id);
|
||||
extern int32_t PIOS_SBus_Init(uint32_t *sbus_id,
|
||||
const struct pios_sbus_cfg *cfg,
|
||||
const struct pios_com_driver *driver,
|
||||
uint32_t lower_id);
|
||||
|
||||
#endif /* PIOS_SBUS_PRIV_H */
|
||||
|
||||
|
@ -1,52 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SPEKTRUM SPEKTRUM Functions
|
||||
* @brief PIOS interface to read and write from spektrum port
|
||||
* @{
|
||||
*
|
||||
* @file pios_spektrum_priv.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Servo 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_SPEKTRUM_PRIV_H
|
||||
#define PIOS_SPEKTRUM_PRIV_H
|
||||
|
||||
#include <pios.h>
|
||||
#include <pios_stm32.h>
|
||||
#include <pios_usart_priv.h>
|
||||
|
||||
struct pios_spektrum_cfg {
|
||||
struct stm32_gpio bind;
|
||||
uint32_t remap; /* GPIO_Remap_* */
|
||||
};
|
||||
|
||||
extern const struct pios_rcvr_driver pios_spektrum_rcvr_driver;
|
||||
|
||||
extern int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t bind);
|
||||
|
||||
#endif /* PIOS_SPEKTRUM_PRIV_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -59,7 +59,9 @@
|
||||
#endif
|
||||
|
||||
/* Generic initcall infrastructure */
|
||||
#if defined(PIOS_INCLUDE_INITCALL)
|
||||
#include "pios_initcall.h"
|
||||
#endif
|
||||
|
||||
/* PIOS Board Specific Device Configuration */
|
||||
#include "pios_board.h"
|
||||
@ -79,7 +81,7 @@
|
||||
#include <pios_ppm.h>
|
||||
#include <pios_pwm.h>
|
||||
#include <pios_rcvr.h>
|
||||
#include <pios_spektrum.h>
|
||||
#include <pios_dsm.h>
|
||||
#include <pios_sbus.h>
|
||||
#include <pios_usb_hid.h>
|
||||
#include <pios_debug.h>
|
||||
|
@ -96,11 +96,9 @@
|
||||
65643CAD1413322000A32F59 /* pios_rtc_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rtc_priv.h; sourceTree = "<group>"; };
|
||||
65643CAE1413322000A32F59 /* pios_sbus_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_sbus_priv.h; sourceTree = "<group>"; };
|
||||
65643CAF1413322000A32F59 /* pios_sbus.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_sbus.h; sourceTree = "<group>"; };
|
||||
65643CB01413322000A32F59 /* pios_spektrum_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_spektrum_priv.h; sourceTree = "<group>"; };
|
||||
65643CB01413322000A32F59 /* pios_dsm_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_dsm_priv.h; sourceTree = "<group>"; };
|
||||
65643CB91413456D00A32F59 /* pios_tim.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_tim.c; sourceTree = "<group>"; };
|
||||
65643CBA141350C200A32F59 /* pios_sbus.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_sbus.c; sourceTree = "<group>"; };
|
||||
65643CEC141429A100A32F59 /* NMEA.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = NMEA.c; sourceTree = "<group>"; };
|
||||
65643CEE141429AF00A32F59 /* NMEA.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = NMEA.h; sourceTree = "<group>"; };
|
||||
6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_memory.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_memory.ld; sourceTree = SOURCE_ROOT; };
|
||||
6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_sections.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld; sourceTree = SOURCE_ROOT; };
|
||||
657CEEAD121DB6C8007A1FBE /* homelocation.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = homelocation.xml; sourceTree = "<group>"; };
|
||||
@ -2658,7 +2656,6 @@
|
||||
65C35E5612EFB2F3004811C2 /* attitudeactual.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitudeactual.xml; sourceTree = "<group>"; };
|
||||
65C35E5812EFB2F3004811C2 /* attituderaw.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attituderaw.xml; sourceTree = "<group>"; };
|
||||
65C35E5912EFB2F3004811C2 /* baroaltitude.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = baroaltitude.xml; sourceTree = "<group>"; };
|
||||
65C35E5A12EFB2F3004811C2 /* batterysettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = batterysettings.xml; sourceTree = "<group>"; };
|
||||
65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightbatterystate.xml; sourceTree = "<group>"; };
|
||||
65C35E5D12EFB2F3004811C2 /* flightplancontrol.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightplancontrol.xml; sourceTree = "<group>"; };
|
||||
65C35E5E12EFB2F3004811C2 /* flightplansettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightplansettings.xml; sourceTree = "<group>"; };
|
||||
@ -2799,7 +2796,7 @@
|
||||
65E8F04911EFF25C00BBF654 /* pios_pwm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_pwm.h; path = ../../PiOS/inc/pios_pwm.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04A11EFF25C00BBF654 /* pios_sdcard.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_sdcard.h; path = ../../PiOS/inc/pios_sdcard.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04B11EFF25C00BBF654 /* pios_servo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_servo.h; path = ../../PiOS/inc/pios_servo.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04C11EFF25C00BBF654 /* pios_spektrum.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_spektrum.h; path = ../../PiOS/inc/pios_spektrum.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04C11EFF25C00BBF654 /* pios_dsm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_dsm.h; path = ../../PiOS/inc/pios_dsm.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04D11EFF25C00BBF654 /* pios_spi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_spi.h; path = ../../PiOS/inc/pios_spi.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04E11EFF25C00BBF654 /* pios_spi_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_spi_priv.h; path = ../../PiOS/inc/pios_spi_priv.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04F11EFF25C00BBF654 /* pios_stm32.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_stm32.h; path = ../../PiOS/inc/pios_stm32.h; sourceTree = SOURCE_ROOT; };
|
||||
@ -2928,7 +2925,7 @@
|
||||
65E8F0E411EFF25C00BBF654 /* pios_ppm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_ppm.c; path = ../../PiOS/STM32F10x/pios_ppm.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E511EFF25C00BBF654 /* pios_pwm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_pwm.c; path = ../../PiOS/STM32F10x/pios_pwm.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E611EFF25C00BBF654 /* pios_servo.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_servo.c; path = ../../PiOS/STM32F10x/pios_servo.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E711EFF25C00BBF654 /* pios_spektrum.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_spektrum.c; path = ../../PiOS/STM32F10x/pios_spektrum.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E711EFF25C00BBF654 /* pios_dsm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_dsm.c; path = ../../PiOS/STM32F10x/pios_dsm.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E811EFF25C00BBF654 /* pios_spi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_spi.c; path = ../../PiOS/STM32F10x/pios_spi.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E911EFF25C00BBF654 /* pios_sys.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_sys.c; path = ../../PiOS/STM32F10x/pios_sys.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0EA11EFF25C00BBF654 /* pios_usart.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_usart.c; path = ../../PiOS/STM32F10x/pios_usart.c; sourceTree = SOURCE_ROOT; };
|
||||
@ -7436,7 +7433,6 @@
|
||||
65C35E4F12EFB2F3004811C2 /* uavobjectdefinition */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E6D80713E3A4D0002A557A /* hwsettings.xml */,
|
||||
65E8C788139AA2A800E1F979 /* accessorydesired.xml */,
|
||||
65C35E5012EFB2F3004811C2 /* actuatorcommand.xml */,
|
||||
65C35E5112EFB2F3004811C2 /* actuatordesired.xml */,
|
||||
@ -7448,7 +7444,6 @@
|
||||
65C35E5812EFB2F3004811C2 /* attituderaw.xml */,
|
||||
65E410AE12F65AEA00725888 /* attitudesettings.xml */,
|
||||
65C35E5912EFB2F3004811C2 /* baroaltitude.xml */,
|
||||
65C35E5A12EFB2F3004811C2 /* batterysettings.xml */,
|
||||
655B1A8E13B2FC0900B0E48D /* camerastabsettings.xml */,
|
||||
652C8568132B632A00BFCC70 /* firmwareiapobj.xml */,
|
||||
65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */,
|
||||
@ -7463,6 +7458,7 @@
|
||||
65C35E6412EFB2F3004811C2 /* gpstime.xml */,
|
||||
65C35E6512EFB2F3004811C2 /* guidancesettings.xml */,
|
||||
65C35E6612EFB2F3004811C2 /* homelocation.xml */,
|
||||
65E6D80713E3A4D0002A557A /* hwsettings.xml */,
|
||||
65C35E6712EFB2F3004811C2 /* i2cstats.xml */,
|
||||
65C35E6812EFB2F3004811C2 /* manualcontrolcommand.xml */,
|
||||
65C35E6912EFB2F3004811C2 /* manualcontrolsettings.xml */,
|
||||
@ -7743,8 +7739,8 @@
|
||||
65E8F04A11EFF25C00BBF654 /* pios_sdcard.h */,
|
||||
65E8F04B11EFF25C00BBF654 /* pios_servo.h */,
|
||||
65FBE14412E7C98100176B5A /* pios_servo_priv.h */,
|
||||
65E8F04C11EFF25C00BBF654 /* pios_spektrum.h */,
|
||||
65643CB01413322000A32F59 /* pios_spektrum_priv.h */,
|
||||
65E8F04C11EFF25C00BBF654 /* pios_dsm.h */,
|
||||
65643CB01413322000A32F59 /* pios_dsm_priv.h */,
|
||||
65E8F04D11EFF25C00BBF654 /* pios_spi.h */,
|
||||
65E8F04E11EFF25C00BBF654 /* pios_spi_priv.h */,
|
||||
65E8F04F11EFF25C00BBF654 /* pios_stm32.h */,
|
||||
@ -7768,24 +7764,8 @@
|
||||
65E8F05811EFF25C00BBF654 /* STM32F10x */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65D1FBD813F51865006374A6 /* pios_bmp085.c */,
|
||||
6560A39D13EE277E00105DA5 /* pios_iap.c */,
|
||||
6560A39E13EE277E00105DA5 /* pios_sbus.c */,
|
||||
6560A38E13EE270C00105DA5 /* link_STM3210E_INS_BL_sections.ld */,
|
||||
6560A38F13EE270C00105DA5 /* link_STM3210E_INS_memory.ld */,
|
||||
6560A39013EE270C00105DA5 /* link_STM3210E_INS_sections.ld */,
|
||||
6560A39113EE270C00105DA5 /* link_STM3210E_OP_BL_sections.ld */,
|
||||
6560A39213EE270C00105DA5 /* link_STM3210E_OP_memory.ld */,
|
||||
6560A39313EE270C00105DA5 /* link_STM3210E_OP_sections.ld */,
|
||||
6560A39413EE270C00105DA5 /* link_STM32103CB_AHRS_BL_sections.ld */,
|
||||
6560A39513EE270C00105DA5 /* link_STM32103CB_AHRS_memory.ld */,
|
||||
6560A39613EE270C00105DA5 /* link_STM32103CB_AHRS_sections.ld */,
|
||||
6560A39713EE270C00105DA5 /* link_STM32103CB_CC_Rev1_BL_sections.ld */,
|
||||
6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */,
|
||||
6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */,
|
||||
6560A39813EE270C00105DA5 /* link_STM32103CB_PIPXTREME_BL_sections.ld */,
|
||||
6560A39913EE270C00105DA5 /* link_STM32103CB_PIPXTREME_memory.ld */,
|
||||
6560A39A13EE270C00105DA5 /* link_STM32103CB_PIPXTREME_sections.ld */,
|
||||
65E8F05911EFF25C00BBF654 /* Libraries */,
|
||||
65E8F0D811EFF25C00BBF654 /* link_stm32f10x_HD.ld */,
|
||||
65E8F0DB11EFF25C00BBF654 /* link_stm32f10x_MD.ld */,
|
||||
@ -7802,7 +7782,7 @@
|
||||
6589A9DB131DEE76006BD67C /* pios_rtc.c */,
|
||||
65643CBA141350C200A32F59 /* pios_sbus.c */,
|
||||
65E8F0E611EFF25C00BBF654 /* pios_servo.c */,
|
||||
65E8F0E711EFF25C00BBF654 /* pios_spektrum.c */,
|
||||
65E8F0E711EFF25C00BBF654 /* pios_dsm.c */,
|
||||
65E8F0E811EFF25C00BBF654 /* pios_spi.c */,
|
||||
65E8F0E911EFF25C00BBF654 /* pios_sys.c */,
|
||||
65643CB91413456D00A32F59 /* pios_tim.c */,
|
||||
|
@ -64,6 +64,7 @@ typedef struct {
|
||||
uint32_t objId;
|
||||
uint16_t instId;
|
||||
uint32_t length;
|
||||
uint8_t instanceLength;
|
||||
uint8_t cs;
|
||||
int32_t rxCount;
|
||||
UAVTalkRxState state;
|
||||
|
@ -351,9 +351,15 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx
|
||||
|
||||
// Determine data length
|
||||
if (iproc->type == UAVTALK_TYPE_OBJ_REQ || iproc->type == UAVTALK_TYPE_ACK || iproc->type == UAVTALK_TYPE_NACK)
|
||||
{
|
||||
iproc->length = 0;
|
||||
iproc->instanceLength = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
iproc->length = UAVObjGetNumBytes(iproc->obj);
|
||||
iproc->instanceLength = (UAVObjIsSingleInstance(iproc->obj) ? 0 : 2);
|
||||
}
|
||||
|
||||
// Check length and determine next state
|
||||
if (iproc->length >= UAVTALK_MAX_PAYLOAD_LENGTH)
|
||||
@ -364,7 +370,7 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx
|
||||
}
|
||||
|
||||
// Check the lengths match
|
||||
if ((iproc->rxPacketLength + iproc->length) != iproc->packet_size)
|
||||
if ((iproc->rxPacketLength + iproc->instanceLength + iproc->length) != iproc->packet_size)
|
||||
{ // packet error - mismatched packet size
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
|
@ -172,7 +172,7 @@
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Output channel asignmets</string>
|
||||
<string>Output channel assignments</string>
|
||||
</property>
|
||||
<layout class="QFormLayout" name="formLayout_3">
|
||||
<item row="0" column="0">
|
||||
|
@ -138,46 +138,6 @@
|
||||
<string>None</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 1</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 2</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 3</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 4</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 5</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 6</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 7</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 8</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
@ -187,46 +147,6 @@
|
||||
<string>None</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 1</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 2</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 3</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 4</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 5</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 6</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 7</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 8</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
@ -243,46 +163,6 @@
|
||||
<string>None</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 1</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 2</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 3</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 4</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 5</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 6</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 7</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 8</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
@ -323,6 +203,13 @@
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="message">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
|
@ -1,283 +1,307 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>CC_HW_Widget</class>
|
||||
<widget class="QWidget" name="CC_HW_Widget">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>517</width>
|
||||
<height>487</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QFrame" name="frame">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<item row="1" column="1" rowspan="5" colspan="3">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="pixmap">
|
||||
<pixmap resource="configgadget.qrc">:/configgadget/images/coptercontrol.svg</pixmap>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QComboBox" name="cbFlexi"/>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QComboBox" name="cbTele"/>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="text">
|
||||
<string>MainPort</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>FlexiPort</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label_7">
|
||||
<property name="text">
|
||||
<string>RcvrPort</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QComboBox" name="cbRcvr"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Telemetry speed:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="telemetrySpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="problems">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="textFormat">
|
||||
<enum>Qt::AutoText</enum>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Changes on this page only take effect after board reset or power cycle</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="cchwHelp">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../coreplugin/core.qrc">
|
||||
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToRAM">
|
||||
<property name="toolTip">
|
||||
<string>Send to OpenPilot but don't write in SD.
|
||||
Beware of not locking yourself out!</string>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToSD">
|
||||
<property name="toolTip">
|
||||
<string>Applies and Saves all settings to SD.
|
||||
Beware of not locking yourself out!</string>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="configgadget.qrc"/>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>CC_HW_Widget</class>
|
||||
<widget class="QWidget" name="CC_HW_Widget">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>517</width>
|
||||
<height>487</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QFrame" name="frame">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<item row="1" column="1" rowspan="5" colspan="3">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="pixmap">
|
||||
<pixmap resource="configgadget.qrc">:/configgadget/images/coptercontrol.svg</pixmap>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QComboBox" name="cbFlexi"/>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QComboBox" name="cbTele"/>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="text">
|
||||
<string>MainPort</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>FlexiPort</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label_7">
|
||||
<property name="text">
|
||||
<string>RcvrPort</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QComboBox" name="cbRcvr"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="telemetrySpeedLabel">
|
||||
<property name="text">
|
||||
<string>Telemetry speed:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="GpsSpeedLabel">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>55</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>GPS speed:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QComboBox" name="telemetrySpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="gpsSpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="problems">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="textFormat">
|
||||
<enum>Qt::AutoText</enum>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Changes on this page only take effect after board reset or power cycle</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="cchwHelp">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../coreplugin/core.qrc">
|
||||
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToRAM">
|
||||
<property name="toolTip">
|
||||
<string>Send to OpenPilot but don't write in SD.
|
||||
Beware of not locking yourself out!</string>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToSD">
|
||||
<property name="toolTip">
|
||||
<string>Applies and Saves all settings to SD.
|
||||
Beware of not locking yourself out!</string>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="configgadget.qrc"/>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
||||
|
@ -25,6 +25,7 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "config_cc_hw_widget.h"
|
||||
#include "hwsettings.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QStringList>
|
||||
@ -40,10 +41,11 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
m_telemetry = new Ui_CC_HW_Widget();
|
||||
m_telemetry->setupUi(this);
|
||||
setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
|
||||
addUAVObjectToWidgetRelation("TelemetrySettings","Speed",m_telemetry->telemetrySpeed);
|
||||
addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi);
|
||||
addUAVObjectToWidgetRelation("HwSettings","CC_MainPort",m_telemetry->cbTele);
|
||||
addUAVObjectToWidgetRelation("HwSettings","CC_RcvrPort",m_telemetry->cbRcvr);
|
||||
addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_telemetry->telemetrySpeed);
|
||||
addUAVObjectToWidgetRelation("HwSettings","GPSSpeed",m_telemetry->gpsSpeed);
|
||||
connect(m_telemetry->cchwHelp,SIGNAL(clicked()),this,SLOT(openHelp()));
|
||||
enableControls(false);
|
||||
populateWidgets();
|
||||
@ -62,10 +64,13 @@ void ConfigCCHWWidget::refreshValues()
|
||||
void ConfigCCHWWidget::widgetsContentsChanged()
|
||||
{
|
||||
ConfigTaskWidget::widgetsContentsChanged();
|
||||
enableControls(false);
|
||||
if((m_telemetry->cbFlexi->currentText()==m_telemetry->cbTele->currentText()) && m_telemetry->cbTele->currentText()!="Disabled")
|
||||
|
||||
if (((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_TELEMETRY) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_TELEMETRY)) ||
|
||||
((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_GPS) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_GPS)) ||
|
||||
((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_COMAUX) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_COMAUX)))
|
||||
{
|
||||
m_telemetry->problems->setText("Warning: you have configured the MainPort and the FlexiPort for the same function, this is currently not suported");
|
||||
enableControls(false);
|
||||
m_telemetry->problems->setText(tr("Warning: you have configured both MainPort and FlexiPort for the same function, this currently is not supported"));
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -83,4 +88,3 @@ void ConfigCCHWWidget::openHelp()
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
@ -40,7 +40,7 @@ ConfigProHWWidget::ConfigProHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
m_telemetry->setupUi(this);
|
||||
|
||||
setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
|
||||
addUAVObjectToWidgetRelation("TelemetrySettings","Speed",m_telemetry->telemetrySpeed);
|
||||
addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_telemetry->telemetrySpeed);
|
||||
enableControls(false);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
|
@ -105,10 +105,13 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
|
||||
ffTuningInProgress = false;
|
||||
ffTuningPhase = false;
|
||||
|
||||
mixerTypes << "Mixer1Type" << "Mixer2Type" << "Mixer3Type"
|
||||
<< "Mixer4Type" << "Mixer5Type" << "Mixer6Type" << "Mixer7Type" << "Mixer8Type";
|
||||
mixerVectors << "Mixer1Vector" << "Mixer2Vector" << "Mixer3Vector"
|
||||
<< "Mixer4Vector" << "Mixer5Vector" << "Mixer6Vector" << "Mixer7Vector" << "Mixer8Vector";
|
||||
QStringList channels;
|
||||
channels << "None";
|
||||
for (int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) {
|
||||
mixerTypes << QString("Mixer%1Type").arg(i+1);
|
||||
mixerVectors << QString("Mixer%1Vector").arg(i+1);
|
||||
channels << QString("Channel%1").arg(i+1);
|
||||
}
|
||||
|
||||
QStringList airframeTypes;
|
||||
airframeTypes << "Fixed Wing" << "Multirotor" << "Helicopter" << "Custom";
|
||||
@ -124,11 +127,6 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
|
||||
<< "Octo Coax X" << "Hexacopter Y6" << "Tricopter Y";
|
||||
m_aircraft->multirotorFrameType->addItems(multiRotorTypes);
|
||||
|
||||
|
||||
|
||||
QStringList channels;
|
||||
channels << "None" << "Channel1" << "Channel2" << "Channel3" <<
|
||||
"Channel4" << "Channel5" << "Channel6" << "Channel7" << "Channel8";
|
||||
// Now load all the channel assignements for fixed wing
|
||||
m_aircraft->fwElevator1Channel->addItems(channels);
|
||||
m_aircraft->fwElevator2Channel->addItems(channels);
|
||||
|
@ -41,12 +41,26 @@
|
||||
#include "camerastabsettings.h"
|
||||
#include "hwsettings.h"
|
||||
#include "mixersettings.h"
|
||||
#include "actuatorcommand.h"
|
||||
|
||||
ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_camerastabilization = new Ui_CameraStabilizationWidget();
|
||||
m_camerastabilization->setupUi(this);
|
||||
|
||||
QComboBox * selectors[3] = {
|
||||
m_camerastabilization->rollChannel,
|
||||
m_camerastabilization->pitchChannel,
|
||||
m_camerastabilization->yawChannel
|
||||
};
|
||||
|
||||
for (int i = 0; i < 3; i++) {
|
||||
selectors[i]->clear();
|
||||
selectors[i]->addItem("None");
|
||||
for (int j = 0; j < ActuatorCommand::CHANNEL_NUMELEM; j++)
|
||||
selectors[i]->addItem(QString("Channel %1").arg(j+1));
|
||||
}
|
||||
|
||||
connectUpdates();
|
||||
|
||||
// Connect buttons
|
||||
@ -87,7 +101,7 @@ void ConfigCameraStabilizationWidget::applySettings()
|
||||
// Enable or disable the settings
|
||||
HwSettings * hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTABILIZATION] =
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] =
|
||||
m_camerastabilization->enableCameraStabilization->isChecked() ?
|
||||
HwSettings::OPTIONALMODULES_ENABLED :
|
||||
HwSettings::OPTIONALMODULES_DISABLED;
|
||||
@ -95,7 +109,7 @@ void ConfigCameraStabilizationWidget::applySettings()
|
||||
// Update the mixer settings
|
||||
MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager());
|
||||
MixerSettings::DataFields mixerSettingsData = mixerSettings->getData();
|
||||
const int NUM_MIXERS = 8;
|
||||
const int NUM_MIXERS = 10;
|
||||
|
||||
QComboBox * selectors[3] = {
|
||||
m_camerastabilization->rollChannel,
|
||||
@ -114,8 +128,11 @@ void ConfigCameraStabilizationWidget::applySettings()
|
||||
&mixerSettingsData.Mixer6Type,
|
||||
&mixerSettingsData.Mixer7Type,
|
||||
&mixerSettingsData.Mixer8Type,
|
||||
&mixerSettingsData.Mixer9Type,
|
||||
&mixerSettingsData.Mixer10Type,
|
||||
};
|
||||
|
||||
m_camerastabilization->message->setText("");
|
||||
for (int i = 0; i < 3; i++)
|
||||
{
|
||||
// Channel 1 is second entry, so becomes zero
|
||||
@ -127,6 +144,7 @@ void ConfigCameraStabilizationWidget::applySettings()
|
||||
// If the mixer channel already to something that isn't what we are
|
||||
// about to set it to reset to none
|
||||
selectors[i]->setCurrentIndex(0);
|
||||
m_camerastabilization->message->setText("One of the channels is already assigned, reverted to none");
|
||||
} else {
|
||||
// Make sure no other channels have this output set
|
||||
for (int j = 0; j < NUM_MIXERS; j++)
|
||||
@ -177,7 +195,7 @@ void ConfigCameraStabilizationWidget::refreshValues()
|
||||
HwSettings * hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
m_camerastabilization->enableCameraStabilization->setChecked(
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTABILIZATION] ==
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] ==
|
||||
HwSettings::OPTIONALMODULES_ENABLED);
|
||||
|
||||
CameraStabSettings * cameraStabSettings = CameraStabSettings::GetInstance(getObjectManager());
|
||||
@ -188,7 +206,7 @@ void ConfigCameraStabilizationWidget::refreshValues()
|
||||
|
||||
MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager());
|
||||
MixerSettings::DataFields mixerSettingsData = mixerSettings->getData();
|
||||
const int NUM_MIXERS = 8;
|
||||
const int NUM_MIXERS = 10;
|
||||
QComboBox * selectors[3] = {
|
||||
m_camerastabilization->rollChannel,
|
||||
m_camerastabilization->pitchChannel,
|
||||
@ -206,6 +224,8 @@ void ConfigCameraStabilizationWidget::refreshValues()
|
||||
&mixerSettingsData.Mixer6Type,
|
||||
&mixerSettingsData.Mixer7Type,
|
||||
&mixerSettingsData.Mixer8Type,
|
||||
&mixerSettingsData.Mixer9Type,
|
||||
&mixerSettingsData.Mixer10Type,
|
||||
};
|
||||
|
||||
for (int i = 0; i < 3; i++)
|
||||
|
@ -464,7 +464,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
case wizardIdentifyLimits:
|
||||
{
|
||||
dimOtherControls(false);
|
||||
setTxMovement(moveAll);
|
||||
setTxMovement(nothing);
|
||||
m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready")));
|
||||
fastMdata();
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
@ -474,6 +474,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
manualSettingsData.ChannelMax[i]=manualSettingsData.ChannelNeutral[i];
|
||||
}
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
}
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
@ -570,6 +571,7 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
restoreMdata();
|
||||
break;
|
||||
@ -618,224 +620,6 @@ void ConfigInputWidget::restoreMdata()
|
||||
manualCommandObj->setMetadata(manualControlMdata);
|
||||
}
|
||||
|
||||
//void ConfigInputWidget::setupWizardWidget(int step)
|
||||
//{
|
||||
// if(step==wizardWelcome)
|
||||
// {
|
||||
// m_config->graphicsView->setVisible(false);
|
||||
// setTxMovement(nothing);
|
||||
// if(wizardStep==wizardChooseMode)
|
||||
// {
|
||||
// delete extraWidgets.at(0);
|
||||
// delete extraWidgets.at(1);
|
||||
// extraWidgets.clear();
|
||||
// }
|
||||
// manualSettingsData=manualSettingsObj->getData();
|
||||
// manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED;
|
||||
// manualSettingsObj->setData(manualSettingsData);
|
||||
// m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\n"
|
||||
// "Please follow the instructions on the screen and only move your controls when asked to.\n"
|
||||
// "Make sure you already configured your hardware settings on the proper tab and restarted your board.\n"
|
||||
// "At any time you can press 'back' to return to the previous screeen or 'Cancel' to cancel the wizard.\n"));
|
||||
// m_config->stackedWidget->setCurrentIndex(1);
|
||||
// m_config->wzBack->setEnabled(false);
|
||||
// wizardStep=wizardWelcome;
|
||||
// }
|
||||
// else if(step==wizardChooseMode)
|
||||
// {
|
||||
// m_config->graphicsView->setVisible(true);
|
||||
// setTxMovement(nothing);
|
||||
// if(wizardStep==wizardIdentifySticks)
|
||||
// {
|
||||
// disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
|
||||
// m_config->wzNext->setEnabled(true);
|
||||
// }
|
||||
// m_config->wzText->setText(tr("Please choose your transmiter type.\n"
|
||||
// "Mode 1 means your throttle stick is on the right\n"
|
||||
// "Mode 2 means your throttle stick is on the left\n"));
|
||||
// m_config->wzBack->setEnabled(true);
|
||||
// QRadioButton * mode1=new QRadioButton(tr("Mode 1"),this);
|
||||
// QRadioButton * mode2=new QRadioButton(tr("Mode 2"),this);
|
||||
// mode2->setChecked(true);
|
||||
// extraWidgets.clear();
|
||||
// extraWidgets.append(mode1);
|
||||
// extraWidgets.append(mode2);
|
||||
// m_config->checkBoxesLayout->layout()->addWidget(mode1);
|
||||
// m_config->checkBoxesLayout->layout()->addWidget(mode2);
|
||||
// wizardStep=wizardChooseMode;
|
||||
// }
|
||||
// else if(step==wizardChooseType)
|
||||
// {
|
||||
// if(wizardStep==wizardChooseMode)
|
||||
// {
|
||||
// QRadioButton * mode=qobject_cast<QRadioButton *>(extraWidgets.at(0));
|
||||
// if(mode->isChecked())
|
||||
// transmitterMode=mode1;
|
||||
// else
|
||||
// transmitterMode=mode2;
|
||||
// delete extraWidgets.at(0);
|
||||
// delete extraWidgets.at(1);
|
||||
// extraWidgets.clear();
|
||||
// }
|
||||
|
||||
// m_config->wzText->setText(tr("Please choose your transmiter mode.\n"
|
||||
// "Acro means normal transmitter\n"
|
||||
// "Heli means there is a collective pitch and throttle input\n"));
|
||||
// m_config->wzBack->setEnabled(true);
|
||||
// QRadioButton * typeAcro=new QRadioButton(tr("Acro"),this);
|
||||
// QRadioButton * typeHeli=new QRadioButton(tr("Heli"),this);
|
||||
// typeAcro->setChecked(true);
|
||||
// typeHeli->setChecked(false);
|
||||
// extraWidgets.clear();
|
||||
// extraWidgets.append(typeAcro);
|
||||
// extraWidgets.append(typeHeli);
|
||||
// m_config->checkBoxesLayout->layout()->addWidget(typeAcro);
|
||||
// m_config->checkBoxesLayout->layout()->addWidget(typeHeli);
|
||||
// wizardStep=wizardChooseType;
|
||||
// } else if(step==wizardIdentifySticks && !isSimple) {
|
||||
// usedChannels.clear();
|
||||
// if(wizardStep==wizardChooseType)
|
||||
// {
|
||||
// qDebug() << "Chosing type";
|
||||
// QRadioButton * type=qobject_cast<QRadioButton *>(extraWidgets.at(0));
|
||||
// if(type->isChecked())
|
||||
// transmitterType=acro;
|
||||
// else
|
||||
// transmitterType=heli;
|
||||
// qDebug() << "Checked: " << type->isChecked() << " " << "type is" << transmitterType;
|
||||
// delete extraWidgets.at(0);
|
||||
// delete extraWidgets.at(1);
|
||||
// extraWidgets.clear();
|
||||
// }
|
||||
// wizardStep=wizardIdentifySticks;
|
||||
// currentCommand=0;
|
||||
// getChannelFromStep(currentCommand);
|
||||
// manualSettingsData=manualSettingsObj->getData();
|
||||
// connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
|
||||
// m_config->wzNext->setEnabled(false);
|
||||
// }
|
||||
// else if(step==wizardIdentifyCenter || (isSimple && step==wizardIdentifySticks))
|
||||
// {
|
||||
// setTxMovement(centerAll);
|
||||
// if(wizardStep==wizardIdentifySticks)
|
||||
// disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
|
||||
// else
|
||||
// {
|
||||
// disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
// manualSettingsObj->setData(manualSettingsData);
|
||||
// manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata());
|
||||
// }
|
||||
// wizardStep=wizardIdentifyCenter;
|
||||
// m_config->wzText->setText(QString(tr("Please center all control controls and press next when ready (if your FlightMode switch has only two positions, leave it on either position)")));
|
||||
// }
|
||||
// else if(step==wizardIdentifyLimits)
|
||||
// {
|
||||
// dimOtherControls(false);
|
||||
// setTxMovement(moveAll);
|
||||
// if(wizardStep==wizardIdentifyCenter)
|
||||
// {
|
||||
// wizardStep=wizardIdentifyLimits;
|
||||
// manualCommandData=manualCommandObj->getData();
|
||||
// manualSettingsData=manualSettingsObj->getData();
|
||||
// for(unsigned int i=0;i<ManualControlCommand::CHANNEL_NUMELEM;++i)
|
||||
// {
|
||||
// manualSettingsData.ChannelNeutral[i]=manualCommandData.Channel[i];
|
||||
// }
|
||||
// manualSettingsObj->setData(manualSettingsData);
|
||||
// }
|
||||
// if(wizardStep==wizardIdentifyInverted)
|
||||
// {
|
||||
// foreach(QWidget * wd,extraWidgets)
|
||||
// {
|
||||
// QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
|
||||
// if(cb)
|
||||
// {
|
||||
// disconnect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
|
||||
// delete cb;
|
||||
// }
|
||||
// }
|
||||
// }
|
||||
// extraWidgets.clear();
|
||||
// disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
// wizardStep=wizardIdentifyLimits;
|
||||
// m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready")));
|
||||
// UAVObject::Metadata mdata= manualCommandObj->getMetadata();
|
||||
// mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC;
|
||||
// mdata.flightTelemetryUpdatePeriod = 150;
|
||||
// manualCommandObj->setMetadata(mdata);
|
||||
// manualSettingsData=manualSettingsObj->getData();
|
||||
// for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
|
||||
// {
|
||||
// manualSettingsData.ChannelMin[i]=manualSettingsData.ChannelNeutral[i];
|
||||
// manualSettingsData.ChannelMax[i]=manualSettingsData.ChannelNeutral[i];
|
||||
// }
|
||||
// connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
// }
|
||||
// else if(step==wizardIdentifyInverted)
|
||||
// {
|
||||
// dimOtherControls(true);
|
||||
// setTxMovement(nothing);
|
||||
// if(wizardStep==wizardIdentifyLimits)
|
||||
// {
|
||||
// disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
// manualSettingsObj->setData(manualSettingsData);
|
||||
// }
|
||||
// extraWidgets.clear();
|
||||
// foreach(QString name,manualSettingsObj->getFields().at(0)->getElementNames())
|
||||
// {
|
||||
// if(!name.contains("Access") && !name.contains("Flight"))
|
||||
// {
|
||||
// QCheckBox * cb=new QCheckBox(name,this);
|
||||
// extraWidgets.append(cb);
|
||||
// m_config->checkBoxesLayout->layout()->addWidget(cb);
|
||||
// connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
|
||||
// }
|
||||
// }
|
||||
// connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
// wizardStep=wizardIdentifyInverted;
|
||||
// m_config->wzText->setText(QString(tr("Please check the picture below and check all the sticks which show an inverted movement and press next when ready")));
|
||||
// }
|
||||
// else if(step==wizardFinish)
|
||||
// {
|
||||
// foreach(QWidget * wd,extraWidgets)
|
||||
// {
|
||||
// QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
|
||||
// if(cb)
|
||||
// {
|
||||
// disconnect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
|
||||
// delete cb;
|
||||
// }
|
||||
// }
|
||||
// wizardStep=wizardFinish;
|
||||
// extraWidgets.clear();
|
||||
// m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture below mimics your sticks movement.\n"
|
||||
// "This new settings aren't saved to the board yet, after pressing next you will go to the initial screen where you can do that.")));
|
||||
|
||||
// }
|
||||
|
||||
// else if(step==wizardFinish+1)
|
||||
// {
|
||||
// setTxMovement(nothing);
|
||||
// manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata());
|
||||
// disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
// manualSettingsData=manualSettingsObj->getData();
|
||||
// manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]=
|
||||
// manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+
|
||||
// ((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]-
|
||||
// manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02);
|
||||
// if((abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100) ||
|
||||
// (abs(manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100))
|
||||
// {
|
||||
// manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]=manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]+
|
||||
// (manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE])/2;
|
||||
// }
|
||||
// manualSettingsObj->setData(manualSettingsData);
|
||||
// m_config->stackedWidget->setCurrentIndex(0);
|
||||
// wizardStep=wizardWelcome;
|
||||
// }
|
||||
|
||||
//}
|
||||
|
||||
/**
|
||||
* Set the display to indicate which channel the person should move
|
||||
*/
|
||||
@ -849,12 +633,16 @@ void ConfigInputWidget::setChannel(int newChan)
|
||||
m_config->wzText->setText(QString(tr("Please move each control once at a time according to the instructions and picture below.\n\n"
|
||||
"Move the %1 stick")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan)));
|
||||
|
||||
if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory"))
|
||||
if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory")) {
|
||||
m_config->wzNext->setEnabled(true);
|
||||
m_config->wzText->setText(m_config->wzText->text() + tr(" or click next to skip this channel."));
|
||||
} else
|
||||
m_config->wzNext->setEnabled(false);
|
||||
|
||||
setMoveFromCommand(newChan);
|
||||
|
||||
currentChannelNum = newChan;
|
||||
channelDetected = false;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -907,6 +695,8 @@ void ConfigInputWidget::identifyControls()
|
||||
receiverActivityData=receiverActivityObj->getData();
|
||||
if(receiverActivityData.ActiveChannel==255)
|
||||
return;
|
||||
if(channelDetected)
|
||||
return;
|
||||
else
|
||||
{
|
||||
receiverActivityData=receiverActivityObj->getData();
|
||||
@ -918,6 +708,7 @@ void ConfigInputWidget::identifyControls()
|
||||
lastChannel.number=currentChannel.number;
|
||||
if(!usedChannels.contains(lastChannel) && debounce>1)
|
||||
{
|
||||
channelDetected = true;
|
||||
debounce=0;
|
||||
usedChannels.append(lastChannel);
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
@ -932,7 +723,7 @@ void ConfigInputWidget::identifyControls()
|
||||
m_config->wzText->clear();
|
||||
setTxMovement(nothing);
|
||||
|
||||
QTimer::singleShot(300, this, SLOT(wzNext()));
|
||||
QTimer::singleShot(500, this, SLOT(wzNext()));
|
||||
}
|
||||
|
||||
void ConfigInputWidget::identifyLimits()
|
||||
@ -945,6 +736,7 @@ void ConfigInputWidget::identifyLimits()
|
||||
if(manualSettingsData.ChannelMax[i]<manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i];
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
void ConfigInputWidget::setMoveFromCommand(int command)
|
||||
{
|
||||
@ -1368,6 +1160,8 @@ void ConfigInputWidget::updateCalibration()
|
||||
void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
m_config->configurationWizard->setEnabled(false);
|
||||
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety."));
|
||||
msgBox.setDetailedText(tr("You will have to reconfigure arming settings yourself afterwards."));
|
||||
@ -1392,6 +1186,8 @@ void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
|
||||
connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration()));
|
||||
} else {
|
||||
m_config->configurationWizard->setEnabled(true);
|
||||
|
||||
manualCommandData = manualCommandObj->getData();
|
||||
manualSettingsData = manualSettingsObj->getData();
|
||||
|
||||
|
@ -81,6 +81,7 @@ private:
|
||||
}lastChannel;
|
||||
channelsStruct currentChannel;
|
||||
QList<channelsStruct> usedChannels;
|
||||
bool channelDetected;
|
||||
QEventLoop * loop;
|
||||
bool skipflag;
|
||||
|
||||
|
@ -38,28 +38,39 @@
|
||||
#include <QMessageBox>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include "actuatorcommand.h"
|
||||
#include "systemalarms.h"
|
||||
#include "uavsettingsimportexport/uavsettingsimportexportfactory.h"
|
||||
|
||||
ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false)
|
||||
{
|
||||
m_config = new Ui_OutputWidget();
|
||||
m_config->setupUi(this);
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
|
||||
addUAVObject("ActuatorSettings");
|
||||
|
||||
UAVSettingsImportExportFactory * importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
|
||||
connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(stopTests()));
|
||||
|
||||
setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
|
||||
addUAVObject("ActuatorSettings");
|
||||
|
||||
// First of all, put all the channel widgets into lists, so that we can
|
||||
// First of all, put all the channel widgets into lists, so that we can
|
||||
// manipulate those:
|
||||
|
||||
// NOTE: for historical reasons, we have objects below called ch0 to ch7, but the convention for OP is Channel 1 to Channel 8.
|
||||
// NOTE: for historical reasons, we have objects below called ch0 to ch7, but the convention for OP is Channel 1 to Channel 8.
|
||||
outLabels << m_config->ch0OutValue
|
||||
<< m_config->ch1OutValue
|
||||
<< m_config->ch2OutValue
|
||||
<< m_config->ch3OutValue
|
||||
<< m_config->ch4OutValue
|
||||
<< m_config->ch5OutValue
|
||||
<< m_config->ch6OutValue
|
||||
<< m_config->ch7OutValue;
|
||||
<< m_config->ch1OutValue
|
||||
<< m_config->ch2OutValue
|
||||
<< m_config->ch3OutValue
|
||||
<< m_config->ch4OutValue
|
||||
<< m_config->ch5OutValue
|
||||
<< m_config->ch6OutValue
|
||||
<< m_config->ch7OutValue
|
||||
<< m_config->ch8OutValue
|
||||
<< m_config->ch9OutValue;
|
||||
|
||||
outSliders << m_config->ch0OutSlider
|
||||
<< m_config->ch1OutSlider
|
||||
@ -68,7 +79,9 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
<< m_config->ch4OutSlider
|
||||
<< m_config->ch5OutSlider
|
||||
<< m_config->ch6OutSlider
|
||||
<< m_config->ch7OutSlider;
|
||||
<< m_config->ch7OutSlider
|
||||
<< m_config->ch8OutSlider
|
||||
<< m_config->ch9OutSlider;
|
||||
|
||||
outMin << m_config->ch0OutMin
|
||||
<< m_config->ch1OutMin
|
||||
@ -77,7 +90,9 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
<< m_config->ch4OutMin
|
||||
<< m_config->ch5OutMin
|
||||
<< m_config->ch6OutMin
|
||||
<< m_config->ch7OutMin;
|
||||
<< m_config->ch7OutMin
|
||||
<< m_config->ch8OutMin
|
||||
<< m_config->ch9OutMin;
|
||||
|
||||
outMax << m_config->ch0OutMax
|
||||
<< m_config->ch1OutMax
|
||||
@ -86,7 +101,9 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
<< m_config->ch4OutMax
|
||||
<< m_config->ch5OutMax
|
||||
<< m_config->ch6OutMax
|
||||
<< m_config->ch7OutMax;
|
||||
<< m_config->ch7OutMax
|
||||
<< m_config->ch8OutMax
|
||||
<< m_config->ch9OutMax;
|
||||
|
||||
reversals << m_config->ch0Rev
|
||||
<< m_config->ch1Rev
|
||||
@ -95,7 +112,9 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
<< m_config->ch4Rev
|
||||
<< m_config->ch5Rev
|
||||
<< m_config->ch6Rev
|
||||
<< m_config->ch7Rev;
|
||||
<< m_config->ch7Rev
|
||||
<< m_config->ch8Rev
|
||||
<< m_config->ch9Rev;
|
||||
|
||||
links << m_config->ch0Link
|
||||
<< m_config->ch1Link
|
||||
@ -104,15 +123,23 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
<< m_config->ch4Link
|
||||
<< m_config->ch5Link
|
||||
<< m_config->ch6Link
|
||||
<< m_config->ch7Link;
|
||||
<< m_config->ch7Link
|
||||
<< m_config->ch8Link
|
||||
<< m_config->ch9Link;
|
||||
|
||||
// Register for ActuatorSettings changes:
|
||||
for (int i = 0; i < 8; i++) {
|
||||
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
|
||||
connect(outMin[i], SIGNAL(editingFinished()), this, SLOT(setChOutRange()));
|
||||
connect(outMax[i], SIGNAL(editingFinished()), this, SLOT(setChOutRange()));
|
||||
connect(reversals[i], SIGNAL(toggled(bool)), this, SLOT(reverseChannel(bool)));
|
||||
// Now connect the channel out sliders to our signal to send updates in test mode
|
||||
connect(outSliders[i], SIGNAL(valueChanged(int)), this, SLOT(sendChannelTest(int)));
|
||||
|
||||
addWidget(outMin[i]);
|
||||
addWidget(outMax[i]);
|
||||
addWidget(reversals[i]);
|
||||
addWidget(outSliders[i]);
|
||||
addWidget(links[i]);
|
||||
}
|
||||
|
||||
connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool)));
|
||||
@ -134,40 +161,14 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
addWidget(m_config->outputRate3);
|
||||
addWidget(m_config->outputRate2);
|
||||
addWidget(m_config->outputRate1);
|
||||
addWidget(m_config->ch0OutMin);
|
||||
addWidget(m_config->ch0OutSlider);
|
||||
addWidget(m_config->ch0OutMax);
|
||||
addWidget(m_config->ch0Rev);
|
||||
addWidget(m_config->ch0Link);
|
||||
addWidget(m_config->ch1OutMin);
|
||||
addWidget(m_config->ch1OutSlider);
|
||||
addWidget(m_config->ch1OutMax);
|
||||
addWidget(m_config->ch1Rev);
|
||||
addWidget(m_config->ch2OutMin);
|
||||
addWidget(m_config->ch2OutSlider);
|
||||
addWidget(m_config->ch2OutMax);
|
||||
addWidget(m_config->ch2Rev);
|
||||
addWidget(m_config->ch3OutMin);
|
||||
addWidget(m_config->ch3OutSlider);
|
||||
addWidget(m_config->ch3OutMax);
|
||||
addWidget(m_config->ch3Rev);
|
||||
addWidget(m_config->ch4OutMin);
|
||||
addWidget(m_config->ch4OutSlider);
|
||||
addWidget(m_config->ch4OutMax);
|
||||
addWidget(m_config->ch4Rev);
|
||||
addWidget(m_config->ch5OutMin);
|
||||
addWidget(m_config->ch5OutSlider);
|
||||
addWidget(m_config->ch5OutMax);
|
||||
addWidget(m_config->ch5Rev);
|
||||
addWidget(m_config->ch6OutMin);
|
||||
addWidget(m_config->ch6OutSlider);
|
||||
addWidget(m_config->ch6OutMax);
|
||||
addWidget(m_config->ch6Rev);
|
||||
addWidget(m_config->ch7OutMin);
|
||||
addWidget(m_config->ch7OutSlider);
|
||||
addWidget(m_config->ch7OutMax);
|
||||
addWidget(m_config->ch7Rev);
|
||||
|
||||
addWidget(m_config->spinningArmed);
|
||||
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
UAVObject* obj = objManager->getObject(QString("ActuatorCommand"));
|
||||
if(obj->getMetadata().gcsTelemetryUpdateMode == UAVObject::UPDATEMODE_ONCHANGE)
|
||||
this->setEnabled(false);
|
||||
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(disableIfNotMe(UAVObject*)));
|
||||
}
|
||||
|
||||
ConfigOutputWidget::~ConfigOutputWidget()
|
||||
@ -215,6 +216,22 @@ void ConfigOutputWidget::linkToggled(bool state)
|
||||
*/
|
||||
void ConfigOutputWidget::runChannelTests(bool state)
|
||||
{
|
||||
SystemAlarms * systemAlarmsObj = SystemAlarms::GetInstance(getObjectManager());
|
||||
SystemAlarms::DataFields systemAlarms = systemAlarmsObj->getData();
|
||||
|
||||
if(state && systemAlarms.Alarm[SystemAlarms::ALARM_ACTUATOR] != SystemAlarms::ALARM_OK) {
|
||||
QMessageBox mbox;
|
||||
mbox.setText(QString(tr("The actuator module is in an error state. This can also occur because there are no inputs. Please fix these before testing outputs.")));
|
||||
mbox.setStandardButtons(QMessageBox::Ok);
|
||||
mbox.exec();
|
||||
|
||||
// Unfortunately must cache this since callback will reoccur
|
||||
accInitialData = ActuatorCommand::GetInstance(getObjectManager())->getMetadata();
|
||||
|
||||
m_config->channelOutTest->setChecked(false);
|
||||
return;
|
||||
}
|
||||
|
||||
// Confirm this is definitely what they want
|
||||
if(state) {
|
||||
QMessageBox mbox;
|
||||
@ -229,14 +246,11 @@ void ConfigOutputWidget::runChannelTests(bool state)
|
||||
}
|
||||
}
|
||||
|
||||
qDebug() << "Running with state " << state;
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
|
||||
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("ActuatorCommand")));
|
||||
ActuatorCommand * obj = ActuatorCommand::GetInstance(getObjectManager());
|
||||
UAVObject::Metadata mdata = obj->getMetadata();
|
||||
if (state)
|
||||
{
|
||||
wasItMe=true;
|
||||
accInitialData = mdata;
|
||||
mdata.flightAccess = UAVObject::ACCESS_READONLY;
|
||||
mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE;
|
||||
@ -252,10 +266,14 @@ void ConfigOutputWidget::runChannelTests(bool state)
|
||||
foreach (QSpinBox* box, outMax) {
|
||||
box->setEnabled(false);
|
||||
}
|
||||
foreach (QCheckBox* box, reversals) {
|
||||
box->setEnabled(false);
|
||||
}
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
wasItMe=false;
|
||||
mdata = accInitialData; // Restore metadata
|
||||
foreach (QSpinBox* box, outMin) {
|
||||
box->setEnabled(true);
|
||||
@ -263,9 +281,13 @@ void ConfigOutputWidget::runChannelTests(bool state)
|
||||
foreach (QSpinBox* box, outMax) {
|
||||
box->setEnabled(true);
|
||||
}
|
||||
foreach (QCheckBox* box, reversals) {
|
||||
box->setEnabled(true);
|
||||
}
|
||||
|
||||
}
|
||||
obj->setMetadata(mdata);
|
||||
obj->updated();
|
||||
|
||||
}
|
||||
|
||||
@ -301,6 +323,12 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str)
|
||||
case 7:
|
||||
m_config->ch7Output->setText(str);
|
||||
break;
|
||||
case 8:
|
||||
m_config->ch8Output->setText(str);
|
||||
break;
|
||||
case 9:
|
||||
m_config->ch9Output->setText(str);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
@ -384,14 +412,8 @@ void ConfigOutputWidget::refreshWidgetsValues()
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
|
||||
// Reset all channel assignements:
|
||||
m_config->ch0Output->setText("-");
|
||||
m_config->ch1Output->setText("-");
|
||||
m_config->ch2Output->setText("-");
|
||||
m_config->ch3Output->setText("-");
|
||||
m_config->ch4Output->setText("-");
|
||||
m_config->ch5Output->setText("-");
|
||||
m_config->ch6Output->setText("-");
|
||||
m_config->ch7Output->setText("-");
|
||||
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++)
|
||||
outLabels[i]->setText("-");
|
||||
|
||||
// Get the channel assignements:
|
||||
UAVDataObject * obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("ActuatorSettings")));
|
||||
@ -418,8 +440,8 @@ void ConfigOutputWidget::refreshWidgetsValues()
|
||||
// CopterControl family
|
||||
m_config->chBank1->setText("1-3");
|
||||
m_config->chBank2->setText("4");
|
||||
m_config->chBank3->setText("5");
|
||||
m_config->chBank4->setText("6");
|
||||
m_config->chBank3->setText("5,7-8");
|
||||
m_config->chBank4->setText("6,9-10");
|
||||
m_config->outputRate1->setEnabled(true);
|
||||
m_config->outputRate2->setEnabled(true);
|
||||
m_config->outputRate3->setEnabled(true);
|
||||
@ -443,7 +465,7 @@ void ConfigOutputWidget::refreshWidgetsValues()
|
||||
|
||||
|
||||
// Get Channel ranges:
|
||||
for (int i=0;i<8;i++) {
|
||||
for (int i=0;i<ActuatorCommand::CHANNEL_NUMELEM;i++) {
|
||||
field = obj->getField(QString("ChannelMin"));
|
||||
int minValue = field->getValue(i).toInt();
|
||||
outMin[i]->setValue(minValue);
|
||||
@ -462,7 +484,7 @@ void ConfigOutputWidget::refreshWidgetsValues()
|
||||
}
|
||||
|
||||
field = obj->getField(QString("ChannelNeutral"));
|
||||
for (int i=0; i<8; i++) {
|
||||
for (int i=0; i<ActuatorCommand::CHANNEL_NUMELEM; i++) {
|
||||
int value = field->getValue(i).toInt();
|
||||
outSliders[i]->setValue(value);
|
||||
outLabels[i]->setText(QString::number(value));
|
||||
@ -483,17 +505,17 @@ void ConfigOutputWidget::updateObjectsFromWidgets()
|
||||
|
||||
// Now send channel ranges:
|
||||
UAVObjectField * field = obj->getField(QString("ChannelMax"));
|
||||
for (int i = 0; i < 8; i++) {
|
||||
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
|
||||
field->setValue(outMax[i]->value(),i);
|
||||
}
|
||||
|
||||
field = obj->getField(QString("ChannelMin"));
|
||||
for (int i = 0; i < 8; i++) {
|
||||
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
|
||||
field->setValue(outMin[i]->value(),i);
|
||||
}
|
||||
|
||||
field = obj->getField(QString("ChannelNeutral"));
|
||||
for (int i = 0; i < 8; i++) {
|
||||
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
|
||||
field->setValue(outSliders[i]->value(),i);
|
||||
}
|
||||
|
||||
@ -583,4 +605,18 @@ void ConfigOutputWidget::openHelp()
|
||||
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Output+Configuration", QUrl::StrictMode) );
|
||||
}
|
||||
|
||||
void ConfigOutputWidget::stopTests()
|
||||
{
|
||||
m_config->channelOutTest->setChecked(false);
|
||||
}
|
||||
|
||||
void ConfigOutputWidget::disableIfNotMe(UAVObject* obj)
|
||||
{
|
||||
if(obj->getMetadata().gcsTelemetryUpdateMode == UAVObject::UPDATEMODE_ONCHANGE)
|
||||
{
|
||||
if(!wasItMe)
|
||||
this->setEnabled(false);
|
||||
}
|
||||
else
|
||||
this->setEnabled(true);
|
||||
}
|
||||
|
@ -69,8 +69,10 @@ private:
|
||||
|
||||
bool firstUpdate;
|
||||
|
||||
|
||||
bool wasItMe;
|
||||
private slots:
|
||||
void stopTests();
|
||||
void disableIfNotMe(UAVObject *obj);
|
||||
virtual void refreshWidgetsValues();
|
||||
void updateObjectsFromWidgets();
|
||||
void runChannelTests(bool state);
|
||||
|
@ -85,8 +85,8 @@ void inputChannelForm::groupUpdated()
|
||||
count = 8; // Need to make this 6 for CC
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_PPM:
|
||||
case ManualControlSettings::CHANNELGROUPS_SPEKTRUM1:
|
||||
case ManualControlSettings::CHANNELGROUPS_SPEKTRUM2:
|
||||
case ManualControlSettings::CHANNELGROUPS_DSMMAINPORT:
|
||||
case ManualControlSettings::CHANNELGROUPS_DSMFLEXIPORT:
|
||||
count = 12;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_SBUS:
|
||||
|
@ -970,6 +970,172 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="actuator8Label">
|
||||
<property name="text">
|
||||
<string>Channel 9:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<widget class="QLabel" name="actuator9Label">
|
||||
<property name="text">
|
||||
<string>Channel 10:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="1">
|
||||
<widget class="QLabel" name="ch8Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="1">
|
||||
<widget class="QLabel" name="ch9Output">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="2">
|
||||
<widget class="QSpinBox" name="ch8OutMin">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="2">
|
||||
<widget class="QSpinBox" name="ch9OutMin">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="3">
|
||||
<widget class="QSlider" name="ch8OutSlider">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="3">
|
||||
<widget class="QSlider" name="ch9OutSlider">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="4">
|
||||
<widget class="QSpinBox" name="ch8OutMax">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="4">
|
||||
<widget class="QSpinBox" name="ch9OutMax">
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="5">
|
||||
<widget class="QLabel" name="ch8OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="5">
|
||||
<widget class="QLabel" name="ch9OutValue">
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="6">
|
||||
<widget class="QCheckBox" name="ch8Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="6">
|
||||
<widget class="QCheckBox" name="ch9Rev">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="7">
|
||||
<widget class="QCheckBox" name="ch8Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="7">
|
||||
<widget class="QCheckBox" name="ch9Link">
|
||||
<property name="toolTip">
|
||||
<string>Only used with Test Output mode</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
|
@ -55,6 +55,7 @@
|
||||
#include <QtGui/QStyleOption>
|
||||
#include <QtGui/QToolBar>
|
||||
#include <QtGui/QToolButton>
|
||||
#include <QtGui/QAbstractItemView>
|
||||
|
||||
// We define a currently unused state for indicating animations
|
||||
#define State_Animating 0x00000040
|
||||
@ -217,7 +218,35 @@ QRect ManhattanStyle::subControlRect(ComplexControl control, const QStyleOptionC
|
||||
SubControl subControl, const QWidget *widget) const
|
||||
{
|
||||
QRect rect;
|
||||
#ifndef Q_WS_MACX
|
||||
// Not using OSX, size combo dropdown to fit contents
|
||||
if(control == CC_ComboBox && subControl == SC_ComboBoxListBoxPopup)
|
||||
{
|
||||
const QStyleOptionComboBox *cb = qstyleoption_cast<const QStyleOptionComboBox *>(option);
|
||||
const QComboBox* combo = qobject_cast<const QComboBox*>(widget);
|
||||
QRect comboRect = cb->rect;
|
||||
int newWidth = combo->view()->sizeHintForColumn(0);
|
||||
if(newWidth > comboRect.width())
|
||||
{
|
||||
// Set new rectangle, only width matters, list height is set by
|
||||
// combination of number of combo box items and setMaxVisibleItems
|
||||
rect.setRect(comboRect.x(), comboRect.y(), newWidth, comboRect.height());
|
||||
rect = visualRect(cb->direction, cb->rect, rect);
|
||||
}
|
||||
else
|
||||
{
|
||||
rect = d->style->subControlRect(control, option, subControl, widget);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
rect = d->style->subControlRect(control, option, subControl, widget);
|
||||
}
|
||||
#else
|
||||
// Using OSX, use default style behaviour as this already sizes the
|
||||
// combo dropdown to fit
|
||||
rect = d->style->subControlRect(control, option, subControl, widget);
|
||||
#endif
|
||||
return rect;
|
||||
}
|
||||
|
||||
|
@ -2,7 +2,7 @@ TEMPLATE = lib
|
||||
TARGET = DebugGadget
|
||||
|
||||
include(../../openpilotgcsplugin.pri)
|
||||
include(../../plugins/coreplugin/coreplugin.pri)
|
||||
include(../../plugins/coreplugin/coreplugin.pri)
|
||||
include(../../libs/libqxt/core/logengines.pri)
|
||||
HEADERS += debugplugin.h \
|
||||
debugengine.h
|
||||
|
@ -19,10 +19,9 @@ plugin_emptygadget.subdir = emptygadget
|
||||
plugin_emptygadget.depends = plugin_coreplugin
|
||||
SUBDIRS += plugin_emptygadget
|
||||
|
||||
# UAV Settings Import/Export plugin
|
||||
# Debug Gadget plugin
|
||||
plugin_debuggadget.subdir = debuggadget
|
||||
#plugin_debughelper.depends = plugin_coreplugin
|
||||
#plugin_debughelper.depends += plugin_uavobjects
|
||||
plugin_debuggadget.depends = plugin_coreplugin
|
||||
SUBDIRS += plugin_debuggadget
|
||||
|
||||
# Welcome plugin
|
||||
|
@ -36,7 +36,6 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \
|
||||
$$UAVOBJECT_SYNTHETICS/systemstats.h \
|
||||
$$UAVOBJECT_SYNTHETICS/systemalarms.h \
|
||||
$$UAVOBJECT_SYNTHETICS/objectpersistence.h \
|
||||
$$UAVOBJECT_SYNTHETICS/telemetrysettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/systemsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/manualcontrolsettings.h \
|
||||
@ -89,7 +88,6 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/systemstats.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/systemalarms.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/objectpersistence.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/telemetrysettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/systemsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/stabilizationsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/manualcontrolsettings.cpp \
|
||||
|
@ -1,58 +1,65 @@
|
||||
function [] = OPLogConvert()
|
||||
%% Define indices and arrays of structures to hold data
|
||||
%% Define indices and arrays of structures to hold data
|
||||
% THIS FILE IS AUTOMATICALLY GENERATED.
|
||||
$(ALLOCATIONCODE)
|
||||
|
||||
%% Open file
|
||||
%fid = fopen('log.opl');
|
||||
[FileName,PathName,FilterIndex] = uigetfile('*.opl');
|
||||
logfile = strcat(PathName,FileName);
|
||||
fid = fopen(logfile);
|
||||
|
||||
while (1)
|
||||
%% Read logging header
|
||||
timestamp = fread(fid, 1, 'uint32');
|
||||
if (feof(fid)); break; end
|
||||
datasize = fread(fid, 1, 'int64');
|
||||
|
||||
|
||||
%% Read message header
|
||||
% get sync field (0x3C, 1 byte)
|
||||
sync = fread(fid, 1, 'uint8');
|
||||
if sync ~= hex2dec('3C')
|
||||
disp ('Wrong sync byte');
|
||||
return
|
||||
end
|
||||
% get msg type (quint8 1 byte ) should be 0x20, ignore the rest?
|
||||
msgType = fread(fid, 1, 'uint8');
|
||||
if msgType ~= hex2dec('20')
|
||||
disp ('Wrong msgType');
|
||||
return
|
||||
end
|
||||
% get msg size (quint16 2 bytes) excludes crc, include msg header and data payload
|
||||
msgSize = fread(fid, 1, 'uint16');
|
||||
% get obj id (quint32 4 bytes)
|
||||
objID = fread(fid, 1, 'uint32');
|
||||
|
||||
|
||||
%% Read object
|
||||
switch objID
|
||||
$(SWITCHCODE)
|
||||
otherwise
|
||||
disp('Unknown object ID');
|
||||
msgBytesLeft = datasize - 1 - 1 - 2 - 4;
|
||||
fread(fid, msgBytesLeft, 'uint8');
|
||||
end
|
||||
|
||||
end
|
||||
|
||||
%% Clean Up and Save mat file
|
||||
fclose(fid);
|
||||
|
||||
matfile = strrep(logfile,'opl','mat');
|
||||
save(matfile $(SAVEOBJECTSCODE));
|
||||
|
||||
|
||||
%% Open log file
|
||||
% [FileName,PathName,FilterIndex] = uigetfile('*.opl');
|
||||
|
||||
FileName='OP-2011-10-22_22-27-09.opl';
|
||||
PathName='/Users/kenz/Movies/brisk_videos/rover_test_1/';
|
||||
FilterIndex=1;
|
||||
|
||||
|
||||
logfile = fullfile(PathName,FileName);
|
||||
fid = fopen(logfile);
|
||||
|
||||
% Parse log file, entry by entry
|
||||
while (1)
|
||||
%% Read logging header
|
||||
timestamp = fread(fid, 1, 'uint32');
|
||||
if (feof(fid)); break; end
|
||||
datasize = fread(fid, 1, 'int64');
|
||||
|
||||
|
||||
%% Read message header
|
||||
% get sync field (0x3C, 1 byte)
|
||||
sync = fread(fid, 1, 'uint8');
|
||||
if sync ~= hex2dec('3C')
|
||||
disp ('Wrong sync byte');
|
||||
return
|
||||
end
|
||||
% get msg type (quint8 1 byte ) should be 0x20, ignore the rest?
|
||||
msgType = fread(fid, 1, 'uint8');
|
||||
if msgType ~= hex2dec('20')
|
||||
disp ('Wrong msgType');
|
||||
return
|
||||
end
|
||||
% get msg size (quint16 2 bytes) excludes crc, include msg header and data payload
|
||||
msgSize = fread(fid, 1, 'uint16');
|
||||
% get obj id (quint32 4 bytes)
|
||||
objID = fread(fid, 1, 'uint32');
|
||||
|
||||
|
||||
%% Read object
|
||||
switch objID
|
||||
$(SWITCHCODE)
|
||||
otherwise
|
||||
disp(['Unknown object ID: 0x' dec2hex(objID)]);
|
||||
msgBytesLeft = datasize - 1 - 1 - 2 - 4;
|
||||
fread(fid, msgBytesLeft, 'uint8');
|
||||
end
|
||||
|
||||
end
|
||||
|
||||
%% Clean Up and Save mat file
|
||||
fclose(fid);
|
||||
|
||||
matfile = strrep(logfile,'opl','mat');
|
||||
save(matfile $(SAVEOBJECTSCODE));
|
||||
|
||||
|
||||
|
||||
|
||||
%% Object reading functions
|
||||
$(FUNCTIONSCODE)
|
||||
|
@ -282,9 +282,15 @@ bool UAVTalk::processInputByte(quint8 rxbyte)
|
||||
|
||||
// Determine data length
|
||||
if (rxType == TYPE_OBJ_REQ || rxType == TYPE_ACK || rxType == TYPE_NACK)
|
||||
{
|
||||
rxLength = 0;
|
||||
rxInstanceLength = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
rxLength = rxObj->getNumBytes();
|
||||
rxInstanceLength = (rxObj->isSingleInstance() ? 0 : 2);
|
||||
}
|
||||
|
||||
// Check length and determine next state
|
||||
if (rxLength >= MAX_PAYLOAD_LENGTH)
|
||||
@ -295,7 +301,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte)
|
||||
}
|
||||
|
||||
// Check the lengths match
|
||||
if ((rxPacketLength + rxLength + (rxObj->isSingleInstance() ? 0 : 2)) != packetSize)
|
||||
if ((rxPacketLength + rxInstanceLength + rxLength) != packetSize)
|
||||
{ // packet error - mismatched packet size
|
||||
stats.rxErrors++;
|
||||
rxState = STATE_SYNC;
|
||||
|
@ -107,6 +107,7 @@ private:
|
||||
quint16 rxInstId;
|
||||
quint16 rxLength;
|
||||
quint16 rxPacketLength;
|
||||
quint8 rxInstanceLength;
|
||||
|
||||
quint8 rxCSPacket, rxCS;
|
||||
qint32 rxCount;
|
||||
|
@ -1017,3 +1017,43 @@ int DFUObject::receiveData(void * data,int size)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#define BOARD_ID_MB 1
|
||||
#define BOARD_ID_INS 2
|
||||
#define BOARD_ID_PIP 3
|
||||
#define BOARD_ID_CC 4
|
||||
//#define BOARD_ID_PRO ?
|
||||
|
||||
/**
|
||||
Gets the type of board connected
|
||||
*/
|
||||
OP_DFU::eBoardType DFUObject::GetBoardType(int boardNum)
|
||||
{
|
||||
OP_DFU::eBoardType brdType = eBoardUnkwn;
|
||||
|
||||
// First of all, check what Board type we are talking to
|
||||
int board = devices[boardNum].ID;
|
||||
qDebug() << "Board model: " << board;
|
||||
switch (board >> 8) {
|
||||
case BOARD_ID_MB: // Mainboard family
|
||||
brdType = eBoardMainbrd;
|
||||
break;
|
||||
case BOARD_ID_INS: // Inertial Nav
|
||||
brdType = eBoardINS;
|
||||
break;
|
||||
case BOARD_ID_PIP: // PIP RF Modem
|
||||
brdType = eBoardPip;
|
||||
break;
|
||||
case BOARD_ID_CC: // CopterControl family
|
||||
brdType = eBoardCC;
|
||||
break;
|
||||
#if 0 // Someday ;-)
|
||||
case BOARD_ID_PRO: // Pro board
|
||||
brdType = eBoardPro;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
return brdType;
|
||||
}
|
||||
|
||||
|
||||
|
@ -92,6 +92,16 @@ namespace OP_DFU {
|
||||
|
||||
};
|
||||
|
||||
enum eBoardType
|
||||
{
|
||||
eBoardUnkwn = 0,
|
||||
eBoardMainbrd = 1,
|
||||
eBoardINS,
|
||||
eBoardPip,
|
||||
eBoardCC,
|
||||
eBoardPro,
|
||||
};
|
||||
|
||||
struct device
|
||||
{
|
||||
int ID;
|
||||
@ -154,6 +164,7 @@ namespace OP_DFU {
|
||||
// Helper functions:
|
||||
QString StatusToString(OP_DFU::Status const & status);
|
||||
static quint32 CRC32WideFast(quint32 Crc, quint32 Size, quint32 *Buffer);
|
||||
OP_DFU::eBoardType GetBoardType(int boardNum);
|
||||
|
||||
|
||||
|
||||
|
@ -480,7 +480,7 @@ void UploaderGadgetWidget::systemRescue()
|
||||
m_config->rescueButton->setEnabled(true);
|
||||
return;
|
||||
}
|
||||
if(QMessageBox::question(this,tr("OpenPilot Uploader"),tr("If you want to search for other boards connect power now and press Yes"),QMessageBox::Yes,QMessageBox::No)==QMessageBox::Yes)
|
||||
if ((eBoardCC != dfu->GetBoardType(0)) && (QMessageBox::question(this,tr("OpenPilot Uploader"),tr("If you want to search for other boards connect power now and press Yes"),QMessageBox::Yes,QMessageBox::No)==QMessageBox::Yes))
|
||||
{
|
||||
log("\nWaiting...");
|
||||
QTimer::singleShot(3000, &m_eventloop, SLOT(quit()));
|
||||
|
@ -31,7 +31,7 @@
|
||||
#include "generator_io.h"
|
||||
|
||||
// These special chars (regexp) will be removed from C/java identifiers
|
||||
#define ENUM_SPECIAL_CHARS "[\\.\\-\\s\\+/]"
|
||||
#define ENUM_SPECIAL_CHARS "[\\.\\-\\s\\+/\\(\\)]"
|
||||
|
||||
void replaceCommonTags(QString& out, ObjectInfo* info);
|
||||
void replaceCommonTags(QString& out);
|
||||
|
@ -50,7 +50,7 @@ bool UAVObjectGeneratorMatlab::generate(UAVObjectParser* parser,QString template
|
||||
}
|
||||
|
||||
matlabCodeTemplate.replace( QString("$(ALLOCATIONCODE)"), matlabAllocationCode);
|
||||
matlabCodeTemplate.replace( QString("$(SWITCHCODE)"), matlabSwithCode);
|
||||
matlabCodeTemplate.replace( QString("$(SWITCHCODE)"), matlabSwitchCode);
|
||||
matlabCodeTemplate.replace( QString("$(SAVEOBJECTSCODE)"), matlabSaveObjectsCode);
|
||||
matlabCodeTemplate.replace( QString("$(FUNCTIONSCODE)"), matlabFunctionsCode);
|
||||
|
||||
@ -71,6 +71,7 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info)
|
||||
if (info == NULL)
|
||||
return false;
|
||||
|
||||
//Declare variables
|
||||
QString objectName(info->name);
|
||||
// QString objectTableName(objectName + "Objects");
|
||||
QString objectTableName(objectName);
|
||||
@ -80,39 +81,71 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info)
|
||||
QString objectID(QString().setNum(info->id));
|
||||
QString isSingleInst = boolTo01String( info->isSingleInst );
|
||||
|
||||
// Generate allocation code (will replace the $(ALLOCATIONCODE) tag)
|
||||
matlabAllocationCode.append("\n " + tableIdxName + " = 1;\n");
|
||||
matlabAllocationCode.append(" " + objectTableName + ".timestamp = 0;\n");
|
||||
QString type;
|
||||
QString allocfields;
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
// Determine type
|
||||
type = fieldTypeStrMatlab[info->fields[n]->type];
|
||||
// Append field
|
||||
if ( info->fields[n]->numElements > 1 )
|
||||
allocfields.append(" " + objectTableName + "(1)." + info->fields[n]->name + " = zeros(1," + QString::number(info->fields[n]->numElements, 10) + ");\n");
|
||||
else
|
||||
allocfields.append(" " + objectTableName + "(1)." + info->fields[n]->name + " = 0;\n");
|
||||
}
|
||||
|
||||
//===================================================================//
|
||||
// Generate allocation code (will replace the $(ALLOCATIONCODE) tag) //
|
||||
//===================================================================//
|
||||
// matlabSwitchCode.append("\t\tcase " + objectID + "\n");
|
||||
matlabAllocationCode.append("\n\t" + tableIdxName + " = 1;\n");
|
||||
QString type;
|
||||
QString allocfields;
|
||||
if (0){
|
||||
matlabAllocationCode.append("\t" + objectTableName + ".timestamp = 0;\n");
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
// Determine type
|
||||
type = fieldTypeStrMatlab[info->fields[n]->type];
|
||||
// Append field
|
||||
if ( info->fields[n]->numElements > 1 )
|
||||
allocfields.append("\t" + objectTableName + "(1)." + info->fields[n]->name + " = zeros(1," + QString::number(info->fields[n]->numElements, 10) + ");\n");
|
||||
else
|
||||
allocfields.append("\t" + objectTableName + "(1)." + info->fields[n]->name + " = 0;\n");
|
||||
}
|
||||
}
|
||||
else{
|
||||
matlabAllocationCode.append("\t" + objectTableName + "=struct('timestamp', 0");
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
// Determine type
|
||||
type = fieldTypeStrMatlab[info->fields[n]->type];
|
||||
// Append field
|
||||
if ( info->fields[n]->numElements > 1 )
|
||||
allocfields.append(",...\n\t\t '" + info->fields[n]->name + "', zeros(1," + QString::number(info->fields[n]->numElements, 10) + ")");
|
||||
else
|
||||
allocfields.append(",...\n\t\t '" + info->fields[n]->name + "', 0");
|
||||
}
|
||||
allocfields.append(");\n");
|
||||
}
|
||||
matlabAllocationCode.append(allocfields);
|
||||
matlabAllocationCode.append("\t" + objectTableName.toUpper() + "_OBJID=" + objectID + ";\n");
|
||||
|
||||
// Generate 'swith:' code (will replace the $(SWITCHCODE) tag)
|
||||
matlabSwithCode.append(" case " + objectID + "\n");
|
||||
matlabSwithCode.append(" " + objectTableName + "(" + tableIdxName +") = " + functionCall + ";\n");
|
||||
matlabSwithCode.append(" " + tableIdxName + " = " + tableIdxName +" + 1;\n");
|
||||
|
||||
// Generate objects saving code code (will replace the $(SAVEOBJECTSCODE) tag)
|
||||
//=============================================================//
|
||||
// Generate 'Switch:' code (will replace the $(SWITCHCODE) tag) //
|
||||
//=============================================================//
|
||||
matlabSwitchCode.append("\t\tcase " + objectTableName.toUpper() + "_OBJID\n");
|
||||
matlabSwitchCode.append("\t\t\t" + objectTableName + "(" + tableIdxName +") = " + functionCall + ";\n");
|
||||
matlabSwitchCode.append("\t\t\t" + tableIdxName + " = " + tableIdxName +" + 1;\n");
|
||||
|
||||
|
||||
//=============================================================================//
|
||||
// Generate objects saving code code (will replace the $(SAVEOBJECTSCODE) tag) //
|
||||
//=============================================================================//
|
||||
matlabSaveObjectsCode.append(",'"+objectTableName+"'");
|
||||
|
||||
// Generate functions code (will replace the $(FUNCTIONSCODE) tag)
|
||||
matlabFunctionsCode.append("%%\n% " + objectName + " read function\n");
|
||||
|
||||
|
||||
//=================================================================//
|
||||
// Generate functions code (will replace the $(FUNCTIONSCODE) tag) //
|
||||
//=================================================================//
|
||||
//Generate function description comment
|
||||
matlabFunctionsCode.append("function [" + objectName + "] = " + functionCall + "\n");
|
||||
matlabFunctionsCode.append(" if " + isSingleInst + "\n");
|
||||
matlabFunctionsCode.append(" headerSize = 8;\n");
|
||||
matlabFunctionsCode.append(" else\n");
|
||||
matlabFunctionsCode.append(" " + objectName + ".instanceID = fread(fid, 1, 'uint16');\n");
|
||||
matlabFunctionsCode.append(" headerSize = 10;\n");
|
||||
matlabFunctionsCode.append(" end\n\n");
|
||||
matlabFunctionsCode.append(" " + objectName + ".timestamp = timestamp;\n");
|
||||
matlabFunctionsCode.append("\tif " + isSingleInst + "\n");
|
||||
matlabFunctionsCode.append("\t\theaderSize = 8;\n");
|
||||
matlabFunctionsCode.append("\telse\n");
|
||||
matlabFunctionsCode.append("\t\t" + objectName + ".instanceID = fread(fid, 1, 'uint16');\n");
|
||||
matlabFunctionsCode.append("\t\theaderSize = 10;\n");
|
||||
matlabFunctionsCode.append("\tend\n\n");
|
||||
matlabFunctionsCode.append("\t" + objectName + ".timestamp = timestamp;\n");
|
||||
|
||||
// Generate functions code, actual fields of the object
|
||||
QString funcfields;
|
||||
@ -122,16 +155,16 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info)
|
||||
type = fieldTypeStrMatlab[info->fields[n]->type];
|
||||
// Append field
|
||||
if ( info->fields[n]->numElements > 1 )
|
||||
funcfields.append(" " + objectName + "." + info->fields[n]->name + " = double(fread(fid, " + QString::number(info->fields[n]->numElements, 10) + ", '" + type + "'));\n");
|
||||
funcfields.append("\t" + objectName + "." + info->fields[n]->name + " = double(fread(fid, " + QString::number(info->fields[n]->numElements, 10) + ", '" + type + "'));\n");
|
||||
else
|
||||
funcfields.append(" " + objectName + "." + info->fields[n]->name + " = double(fread(fid, 1, '" + type + "'));\n");
|
||||
funcfields.append("\t" + objectName + "." + info->fields[n]->name + " = double(fread(fid, 1, '" + type + "'));\n");
|
||||
}
|
||||
matlabFunctionsCode.append(funcfields);
|
||||
|
||||
matlabFunctionsCode.append(" % read CRC\n");
|
||||
matlabFunctionsCode.append(" fread(fid, 1, 'uint8');\n");
|
||||
matlabFunctionsCode.append("\t% read CRC\n");
|
||||
matlabFunctionsCode.append("\tfread(fid, 1, 'uint8');\n");
|
||||
|
||||
matlabFunctionsCode.append("end\n\n");
|
||||
matlabFunctionsCode.append("\n\n");
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -37,7 +37,7 @@ public:
|
||||
private:
|
||||
bool process_object(ObjectInfo* info);
|
||||
QString matlabAllocationCode;
|
||||
QString matlabSwithCode;
|
||||
QString matlabSwitchCode;
|
||||
QString matlabSaveObjectsCode;
|
||||
QString matlabFunctionsCode;
|
||||
QStringList fieldTypeStrMatlab;
|
||||
|
@ -1,7 +1,7 @@
|
||||
<xml>
|
||||
<object name="ActuatorCommand" singleinstance="true" settings="false">
|
||||
<description>Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule</description>
|
||||
<field name="Channel" units="us" type="int16" elements="8"/>
|
||||
<field name="Channel" units="us" type="int16" elements="10"/>
|
||||
<field name="UpdateTime" units="ms" type="uint8" elements="1"/>
|
||||
<field name="MaxUpdateTime" units="ms" type="uint16" elements="1"/>
|
||||
<field name="NumFailedUpdates" units="" type="uint8" elements="1"/>
|
||||
|
@ -1,27 +1,27 @@
|
||||
<xml>
|
||||
<object name="ActuatorSettings" singleinstance="true" settings="true">
|
||||
<description>Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType</description>
|
||||
<field name="FixedWingRoll1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="FixedWingRoll2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="FixedWingPitch1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="FixedWingPitch2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="FixedWingYaw1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="FixedWingYaw2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="FixedWingThrottle" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorN" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorNE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorSE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorS" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorSW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorNW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="FixedWingRoll1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="FixedWingRoll2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="FixedWingPitch1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="FixedWingPitch2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="FixedWingYaw1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="FixedWingYaw2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="FixedWingThrottle" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorN" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorNE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorSE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorS" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorSW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="VTOLMotorNW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
|
||||
<field name="ChannelUpdateFreq" units="Hz" type="uint16" elements="4" defaultvalue="50"/>
|
||||
<field name="ChannelMax" units="us" type="int16" elements="8" defaultvalue="1000"/>
|
||||
<field name="ChannelNeutral" units="us" type="int16" elements="8" defaultvalue="1000"/>
|
||||
<field name="ChannelMin" units="us" type="int16" elements="8" defaultvalue="1000"/>
|
||||
<field name="ChannelType" units="" type="enum" elements="8" options="PWM,MK,ASTEC4,PWM Alarm Buzzer" defaultvalue="PWM"/>
|
||||
<field name="ChannelAddr" units="" type="uint8" elements="8" defaultvalue="0,1,2,3,4,5,6,7"/>
|
||||
<field name="ChannelMax" units="us" type="int16" elements="10" defaultvalue="1000"/>
|
||||
<field name="ChannelNeutral" units="us" type="int16" elements="10" defaultvalue="1000"/>
|
||||
<field name="ChannelMin" units="us" type="int16" elements="10" defaultvalue="1000"/>
|
||||
<field name="ChannelType" units="" type="enum" elements="10" options="PWM,MK,ASTEC4,PWM Alarm Buzzer" defaultvalue="PWM"/>
|
||||
<field name="ChannelAddr" units="" type="uint8" elements="10" defaultvalue="0,1,2,3,4,5,6,7,8,9"/>
|
||||
<field name="MotorsSpinWhileArmed" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -1,15 +1,18 @@
|
||||
<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,Spektrum1,Spektrum2,ComAux,I2C" defaultvalue="Disabled"/>
|
||||
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,S.Bus,GPS,Spektrum1,Spektrum2,ComAux" defaultvalue="Telemetry"/>
|
||||
<field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM" defaultvalue="PWM"/>
|
||||
<field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+Servo,Servo" defaultvalue="PWM"/>
|
||||
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM2,DSMX (10bit),DSMX (11bit),ComAux" defaultvalue="Disabled"/>
|
||||
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM2,DSMX (10bit),DSMX (11bit),ComAux" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="OP_FlexiPort" units="function" type="enum" elements="1" options="Disabled,GPS" defaultvalue="GPS"/>
|
||||
<field name="OP_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,DSM2,DSMX (10bit),DSMX (11bit),Debug" defaultvalue="PWM"/>
|
||||
<field name="OP_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry" defaultvalue="Telemetry"/>
|
||||
<field name="OP_RcvrPort" units="function" type="enum" elements="1" options="Disabled,Debug,Spektrum1,PWM,PPM" defaultvalue="PWM"/>
|
||||
<field name="OP_FlexiPort" units="function" type="enum" elements="1" options="Disabled,GPS" defaultvalue="GPS"/>
|
||||
|
||||
<field name="OptionalModules" units="" type="enum" elementnames="CameraStabilization,GPS,TxPID" options="Disabled,Enabled" defaultvalue="Disabled"/>
|
||||
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="GPSSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
|
||||
<field name="OptionalModules" units="" type="enum" elementnames="CameraStab,GPS,TxPID" options="Disabled,Enabled" defaultvalue="Disabled"/>
|
||||
<field name="DSMxBind" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
|
@ -3,7 +3,7 @@
|
||||
<description>Settings to indicate how to decode receiver input by @ref ManualControlModule.</description>
|
||||
<field name="ChannelGroups" units="Channel Group" type="enum"
|
||||
elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2"
|
||||
options="PWM,PPM,Spektrum1,Spektrum2,S.Bus,GCS,None" defaultvalue="None"/>
|
||||
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),S.Bus,GCS,None" defaultvalue="None"/>
|
||||
<field name="ChannelNumber" units="channel" type="uint8" defaultvalue="0"
|
||||
elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2"/>
|
||||
<field name="ChannelMin" units="us" type="int16" defaultvalue="1000"
|
||||
|
@ -24,6 +24,10 @@
|
||||
<field name="Mixer7Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<field name="Mixer8Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer8Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<field name="Mixer9Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer9Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<field name="Mixer10Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer10Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -2,7 +2,7 @@
|
||||
<object name="ReceiverActivity" singleinstance="true" settings="false">
|
||||
<description>Monitors which receiver channels have been active within the last second.</description>
|
||||
<field name="ActiveGroup" units="Channel Group" type="enum" elements="1"
|
||||
options="PWM,PPM,Spektrum1,Spektrum2,SBus,GCS,None"
|
||||
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),S.Bus,GCS,None"
|
||||
defaultvalue="None"/>
|
||||
<field name="ActiveChannel" units="channel" type="uint8" elements="1"
|
||||
defaultvalue="255"/>
|
||||
|
@ -1,10 +0,0 @@
|
||||
<xml>
|
||||
<object name="TelemetrySettings" singleinstance="true" settings="true">
|
||||
<description>Select baud rate of telemetry. Warning - this must match your modem.</description>
|
||||
<field name="Speed" units="" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<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>
|
Loading…
x
Reference in New Issue
Block a user