1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-21 11:54:15 +01:00

Merge branch 'next' into LP-385_cameracontrol

This commit is contained in:
Alessio Morale 2016-08-29 21:04:55 +02:00
commit 44f1c76ef9
56 changed files with 2089 additions and 252 deletions

View File

@ -8,10 +8,10 @@ before_install:
- sudo add-apt-repository ppa:librepilot/tools -y - sudo add-apt-repository ppa:librepilot/tools -y
- sudo apt-get update -q - sudo apt-get update -q
- sudo apt-get install -y libc6-i386 libudev-dev libusb-1.0-0-dev libsdl1.2-dev python libopenscenegraph-dev libosgearth-dev qt56-meta-minimal qt56svg qt56script qt56serialport qt56multimedia qt56translations qt56tools - sudo apt-get install -y libc6-i386 libudev-dev libusb-1.0-0-dev libsdl1.2-dev python libopenscenegraph-dev libosgearth-dev qt56-meta-minimal qt56svg qt56script qt56serialport qt56multimedia qt56translations qt56tools
- make arm_sdk_install - make build_sdk_install
script: script:
- make config_new CCACHE=ccache GCS_EXTRA_CONF='osg osgearth' - make config_new CCACHE=ccache
- make all_flight - make all_flight
- make opfw_resource - make opfw_resource
- make gcs - make gcs

View File

@ -127,11 +127,20 @@ include $(ROOT_DIR)/make/tools.mk
# We almost need to consider autoconf/automake instead of this # We almost need to consider autoconf/automake instead of this
ifeq ($(UNAME), Linux) ifeq ($(UNAME), Linux)
UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator
GCS_WITH_OSG := 1
GCS_WITH_OSGEARTH := 1
GCS_COPY_OSG := 0
else ifeq ($(UNAME), Darwin) else ifeq ($(UNAME), Darwin)
UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator
GCS_WITH_OSG := 1
GCS_WITH_OSGEARTH := 0
GCS_COPY_OSG := 1
else ifeq ($(UNAME), Windows) else ifeq ($(UNAME), Windows)
UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator.exe UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator.exe
GCS_WITH_OSG := 1
GCS_WITH_OSGEARTH := 1
GCS_COPY_OSG := 1
endif endif
export UAVOBJGENERATOR export UAVOBJGENERATOR
@ -140,9 +149,14 @@ export UAVOBJGENERATOR
GCS_BUILD_CONF := release GCS_BUILD_CONF := release
# Set extra configuration # Set extra configuration
GCS_EXTRA_CONF += osg copy_osg ifeq ($(GCS_WITH_OSG), 1)
ifeq ($(UNAME), Windows) GCS_EXTRA_CONF += osg
GCS_EXTRA_CONF += osgearth ifeq ($(GCS_COPY_OSG), 1)
GCS_EXTRA_CONF += copy_osg
endif
ifeq ($(GCS_WITH_OSGEARTH), 1)
GCS_EXTRA_CONF += osgearth
endif
endif endif
############################## ##############################
@ -510,12 +524,59 @@ config_append:
.PHONY: config_show .PHONY: config_show
config_show: config_show:
@cat $(CONFIG_FILE) @cat $(CONFIG_FILE) | sed 's/override *//'
.PHONY: config_clean .PHONY: config_clean
config_clean: config_clean:
rm -f $(CONFIG_FILE) rm -f $(CONFIG_FILE)
.PHONY: config_help
config_help:
@$(ECHO) " The build system has a simple system for persistent configuration"
@$(ECHO)
@$(ECHO) " To set persistent configuration variables you, for example, do:"
@$(ECHO) " $(MAKE) config_new CCACHE=ccache GCS_WITH_OSG=0"
@$(ECHO)
@$(ECHO) " To add to the existing configuration do:"
@$(ECHO) " $(MAKE) config_append GCS_BUILD_CONF=debug"
@$(ECHO)
@$(ECHO) " To reset the configuration to defaults do:"
@$(ECHO) " $(MAKE) config_clean"
@$(ECHO)
@$(ECHO) " To show the current configuration:"
@$(ECHO) " $(MAKE) config_show"
@$(ECHO)
@$(ECHO) " You can override any make variable this way, but these are the useful ones"
@$(ECHO) " shown with their current (or default values):"
@$(ECHO)
@$(ECHO) " GCS_BUILD_CONF=$(GCS_BUILD_CONF)"
@$(ECHO) " GCS build type"
@$(ECHO) " Options: debug or release"
@$(ECHO)
@$(ECHO) " GCS_WITH_OSG=$(GCS_WITH_OSG)"
@$(ECHO) " Build the GCS with OpenSceneGraph support, this enables the PFD Model View"
@$(ECHO) " Options: 0 or 1"
@$(ECHO)
@$(ECHO) " GCS_WITH_OSGEARTH=$(GCS_WITH_OSGEARTH)"
@$(ECHO) " Build the GCS with osgEarth support, this enables extra PFD terrain views"
@$(ECHO) " Options: 0 or 1"
@$(ECHO)
@$(ECHO) " GCS_COPY_OSG=$(GCS_COPY_OSG)"
@$(ECHO) " Copy OpenSceneGraph/osgEarth libraries into the build"
@$(ECHO) " (Needed unless using system versions)"
@$(ECHO) " Options: 0 or 1"
@$(ECHO)
@$(ECHO) " CCACHE=$(CCACHE)"
@$(ECHO) " A prefix to compiler invocations, usually 'ccache' or 'path/to/ccache'"
@$(ECHO)
@$(ECHO) " QMAKE=$(QMAKE)"
@$(ECHO) " How to invoke qmake, usually 'qmake', 'qmake-qt5' or 'path/to/qmake'"
@$(ECHO)
@$(ECHO) " WITH_PREBUILT_FIRMWARE=$(WITH_PREBUILT_FIRMWARE)"
@$(ECHO) " Set to path of prebuilt firmware or empty to build firmware when needed"
# TODO: add other things like downloads and tools directories, linux make install parameters
############################## ##############################
# #
@ -669,6 +730,7 @@ help:
@$(ECHO) " docs_all_clean - Delete all generated documentation" @$(ECHO) " docs_all_clean - Delete all generated documentation"
@$(ECHO) @$(ECHO)
@$(ECHO) " [Configuration]" @$(ECHO) " [Configuration]"
@$(ECHO) " config_help - Show information on how to configure the build"
@$(ECHO) " config_new - Place your make arguments in the config file" @$(ECHO) " config_new - Place your make arguments in the config file"
@$(ECHO) " config_append - Place your make arguments in the config file but append" @$(ECHO) " config_append - Place your make arguments in the config file but append"
@$(ECHO) " config_clean - Removes the config file" @$(ECHO) " config_clean - Removes the config file"

View File

@ -5,8 +5,7 @@ pipelines:
- add-apt-repository ppa:librepilot/tools -y - add-apt-repository ppa:librepilot/tools -y
- apt-get update -q - apt-get update -q
- apt-get install -y libc6-i386 libudev-dev libusb-1.0-0-dev libsdl1.2-dev python libopenscenegraph-dev libosgearth-dev qt56-meta-minimal qt56svg qt56script qt56serialport qt56multimedia qt56translations qt56tools - apt-get install -y libc6-i386 libudev-dev libusb-1.0-0-dev libsdl1.2-dev python libopenscenegraph-dev libosgearth-dev qt56-meta-minimal qt56svg qt56script qt56serialport qt56multimedia qt56translations qt56tools
- make arm_sdk_install - make build_sdk_install
- make config_new GCS_EXTRA_CONF='osg osgearth'
- make all_flight - make all_flight
- make opfw_resource - make opfw_resource
- make gcs - make gcs

View File

@ -93,6 +93,7 @@ SRC += $(PIOSCOMMON)/pios_sbus.c
SRC += $(PIOSCOMMON)/pios_hott.c SRC += $(PIOSCOMMON)/pios_hott.c
SRC += $(PIOSCOMMON)/pios_srxl.c SRC += $(PIOSCOMMON)/pios_srxl.c
SRC += $(PIOSCOMMON)/pios_exbus.c SRC += $(PIOSCOMMON)/pios_exbus.c
SRC += $(PIOSCOMMON)/pios_ibus.c
SRC += $(PIOSCOMMON)/pios_sdcard.c SRC += $(PIOSCOMMON)/pios_sdcard.c
SRC += $(PIOSCOMMON)/pios_sensors.c SRC += $(PIOSCOMMON)/pios_sensors.c
SRC += $(PIOSCOMMON)/pios_openlrs.c SRC += $(PIOSCOMMON)/pios_openlrs.c

View File

@ -670,6 +670,9 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm
case MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL: case MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL:
group = RECEIVERACTIVITY_ACTIVEGROUP_SRXL; group = RECEIVERACTIVITY_ACTIVEGROUP_SRXL;
break; break;
case MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS:
group = RECEIVERACTIVITY_ACTIVEGROUP_IBUS;
break;
case MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS: case MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS:
group = RECEIVERACTIVITY_ACTIVEGROUP_GCS; group = RECEIVERACTIVITY_ACTIVEGROUP_GCS;
break; break;

View File

@ -32,6 +32,7 @@
#include "pios.h" #include "pios.h"
#include "uavobjectmanager.h" #include "uavobjectmanager.h"
#include "debuglogentry.h" #include "debuglogentry.h"
#include "callbackinfo.h"
// global definitions // global definitions
#ifdef PIOS_INCLUDE_DEBUGLOG #ifdef PIOS_INCLUDE_DEBUGLOG
@ -39,14 +40,9 @@
// Global variables // Global variables
extern uintptr_t pios_user_fs_id; // flash filesystem for logging extern uintptr_t pios_user_fs_id; // flash filesystem for logging
#if defined(PIOS_INCLUDE_FREERTOS)
static xSemaphoreHandle mutex = 0; static xSemaphoreHandle mutex = 0;
#define mutexlock() xSemaphoreTakeRecursive(mutex, portMAX_DELAY) #define mutexlock() xSemaphoreTakeRecursive(mutex, portMAX_DELAY)
#define mutexunlock() xSemaphoreGiveRecursive(mutex) #define mutexunlock() xSemaphoreGiveRecursive(mutex)
#else
#define mutexlock()
#define mutexunlock()
#endif
static bool logging_enabled = false; static bool logging_enabled = false;
#define MAX_CONSECUTIVE_FAILS_COUNT 10 #define MAX_CONSECUTIVE_FAILS_COUNT 10
@ -54,10 +50,12 @@ static bool log_is_full = false;
static uint8_t fails_count = 0; static uint8_t fails_count = 0;
static uint16_t flightnum = 0; static uint16_t flightnum = 0;
static uint16_t lognum = 0; static uint16_t lognum = 0;
static DebugLogEntryData *buffer = 0;
#if !defined(PIOS_INCLUDE_FREERTOS) #define BUFFERS_COUNT 2
static DebugLogEntryData staticbuffer; static DebugLogEntryData *current_buffer = 0;
#endif static DebugLogEntryData *buffers[BUFFERS_COUNT] = { 0, 0 };
static uint8_t current_write_buffer_index;
static uint8_t next_read_buffer_index;
#define LOG_ENTRY_MAX_DATA_SIZE (sizeof(((DebugLogEntryData *)0)->Data)) #define LOG_ENTRY_MAX_DATA_SIZE (sizeof(((DebugLogEntryData *)0)->Data))
#define LOG_ENTRY_HEADER_SIZE (sizeof(DebugLogEntryData) - LOG_ENTRY_MAX_DATA_SIZE) #define LOG_ENTRY_HEADER_SIZE (sizeof(DebugLogEntryData) - LOG_ENTRY_MAX_DATA_SIZE)
@ -66,23 +64,33 @@ static DebugLogEntryData staticbuffer;
static uint32_t used_buffer_space = 0; static uint32_t used_buffer_space = 0;
#define CBTASK_PRIORITY CALLBACK_TASK_AUXILIARY
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_LOW
#define CB_TIMEOUT 100
#define STACK_SIZE_BYTES 512
static DelayedCallbackInfo *callbackHandle;
/* Private Function Prototypes */ /* Private Function Prototypes */
static void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data); static void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data);
static bool write_current_buffer(); static bool write_current_buffer();
static void writeTask();
static uint8_t get_blocks_free();
/** /**
* @brief Initialize the log facility * @brief Initialize the log facility
*/ */
void PIOS_DEBUGLOG_Initialize() void PIOS_DEBUGLOG_Initialize()
{ {
#if defined(PIOS_INCLUDE_FREERTOS)
if (!mutex) { if (!mutex) {
mutex = xSemaphoreCreateRecursiveMutex(); mutex = xSemaphoreCreateRecursiveMutex();
buffer = pios_malloc(sizeof(DebugLogEntryData)); for (uint32_t i = 0; i < BUFFERS_COUNT; i++) {
buffers[i] = pios_malloc(sizeof(DebugLogEntryData));
}
current_write_buffer_index = 0;
next_read_buffer_index = 0;
current_buffer = buffers[current_write_buffer_index];
} }
#else
buffer = &staticbuffer; if (!current_buffer) {
#endif
if (!buffer) {
return; return;
} }
mutexlock(); mutexlock();
@ -91,10 +99,12 @@ void PIOS_DEBUGLOG_Initialize()
fails_count = 0; fails_count = 0;
used_buffer_space = 0; used_buffer_space = 0;
log_is_full = false; log_is_full = false;
while (PIOS_FLASHFS_ObjLoad(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) { while (PIOS_FLASHFS_ObjLoad(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)current_buffer, sizeof(DebugLogEntryData)) == 0) {
flightnum++; flightnum++;
} }
mutexunlock(); mutexunlock();
callbackHandle = PIOS_CALLBACKSCHEDULER_Create(&writeTask, CALLBACK_PRIORITY, CBTASK_PRIORITY, CALLBACKINFO_RUNNING_DEBUGLOG, STACK_SIZE_BYTES);
PIOS_CALLBACKSCHEDULER_Schedule(callbackHandle, CB_TIMEOUT, CALLBACK_UPDATEMODE_LATER);
} }
@ -122,7 +132,7 @@ void PIOS_DEBUGLOG_Enable(uint8_t enabled)
*/ */
void PIOS_DEBUGLOG_UAVObject(uint32_t objid, uint16_t instid, size_t size, uint8_t *data) void PIOS_DEBUGLOG_UAVObject(uint32_t objid, uint16_t instid, size_t size, uint8_t *data)
{ {
if (!logging_enabled || !buffer || log_is_full) { if (!logging_enabled || !current_buffer || log_is_full) {
return; return;
} }
mutexlock(); mutexlock();
@ -139,7 +149,7 @@ void PIOS_DEBUGLOG_UAVObject(uint32_t objid, uint16_t instid, size_t size, uint8
*/ */
void PIOS_DEBUGLOG_Printf(char *format, ...) void PIOS_DEBUGLOG_Printf(char *format, ...)
{ {
if (!logging_enabled || !buffer || log_is_full) { if (!logging_enabled || !current_buffer || log_is_full) {
return; return;
} }
@ -150,19 +160,19 @@ void PIOS_DEBUGLOG_Printf(char *format, ...)
if (used_buffer_space) { if (used_buffer_space) {
write_current_buffer(); write_current_buffer();
} }
memset(buffer->Data, 0xff, sizeof(buffer->Data)); memset(current_buffer->Data, 0xff, sizeof(current_buffer->Data));
vsnprintf((char *)buffer->Data, sizeof(buffer->Data), (char *)format, args); vsnprintf((char *)current_buffer->Data, sizeof(current_buffer->Data), (char *)format, args);
buffer->Flight = flightnum; current_buffer->Flight = flightnum;
buffer->FlightTime = PIOS_DELAY_GetuS(); current_buffer->FlightTime = PIOS_DELAY_GetuS();
buffer->Entry = lognum; current_buffer->Entry = lognum;
buffer->Type = DEBUGLOGENTRY_TYPE_TEXT; current_buffer->Type = DEBUGLOGENTRY_TYPE_TEXT;
buffer->ObjectID = 0; current_buffer->ObjectID = 0;
buffer->InstanceID = 0; current_buffer->InstanceID = 0;
buffer->Size = strlen((const char *)buffer->Data); current_buffer->Size = strlen((const char *)current_buffer->Data);
if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) { if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)current_buffer, sizeof(DebugLogEntryData)) == 0) {
lognum++; lognum++;
} }
mutexunlock(); mutexunlock();
@ -233,21 +243,21 @@ void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data)
// start a new block // start a new block
if (!used_buffer_space) { if (!used_buffer_space) {
entry = buffer; entry = current_buffer;
memset(buffer->Data, 0xff, sizeof(buffer->Data)); memset(current_buffer->Data, 0xff, sizeof(current_buffer->Data));
used_buffer_space += size; used_buffer_space += size;
} else { } else {
// if an instance is being filled and there is enough space, does enqueues new data. // if an instance is being filled and there is enough space, does enqueues new data.
if (used_buffer_space + size + LOG_ENTRY_HEADER_SIZE > LOG_ENTRY_MAX_DATA_SIZE) { if (used_buffer_space + size + LOG_ENTRY_HEADER_SIZE > LOG_ENTRY_MAX_DATA_SIZE) {
buffer->Type = DEBUGLOGENTRY_TYPE_MULTIPLEUAVOBJECTS; current_buffer->Type = DEBUGLOGENTRY_TYPE_MULTIPLEUAVOBJECTS;
if (!write_current_buffer()) { if (!write_current_buffer()) {
return; return;
} }
entry = buffer; entry = current_buffer;
memset(buffer->Data, 0xff, sizeof(buffer->Data)); memset(current_buffer->Data, 0xff, sizeof(current_buffer->Data));
used_buffer_space += size; used_buffer_space += size;
} else { } else {
entry = (DebugLogEntryData *)&buffer->Data[used_buffer_space]; entry = (DebugLogEntryData *)&current_buffer->Data[used_buffer_space];
used_buffer_space += size + LOG_ENTRY_HEADER_SIZE; used_buffer_space += size + LOG_ENTRY_HEADER_SIZE;
} }
} }
@ -258,8 +268,8 @@ void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data)
entry->Type = DEBUGLOGENTRY_TYPE_UAVOBJECT; entry->Type = DEBUGLOGENTRY_TYPE_UAVOBJECT;
entry->ObjectID = objid; entry->ObjectID = objid;
entry->InstanceID = instid; entry->InstanceID = instid;
if (size > sizeof(buffer->Data)) { if (size > sizeof(current_buffer->Data)) {
size = sizeof(buffer->Data); size = sizeof(current_buffer->Data);
} }
entry->Size = size; entry->Size = size;
@ -268,18 +278,46 @@ void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data)
bool write_current_buffer() bool write_current_buffer()
{ {
// not enough space, write the block and start a new one PIOS_CALLBACKSCHEDULER_Dispatch(callbackHandle);
if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) { // Check if queue is full
lognum++;
fails_count = 0; if (get_blocks_free() > 0) {
current_write_buffer_index = (current_write_buffer_index + 1) % BUFFERS_COUNT;
current_buffer = buffers[current_write_buffer_index];
used_buffer_space = 0; used_buffer_space = 0;
return true;
} else { } else {
if (fails_count++ > MAX_CONSECUTIVE_FAILS_COUNT) {
log_is_full = true;
}
return false; return false;
} }
return true; }
static uint8_t get_blocks_free()
{
uint8_t used_blocks = current_write_buffer_index - next_read_buffer_index;
if (current_write_buffer_index < next_read_buffer_index) {
used_blocks = (BUFFERS_COUNT - next_read_buffer_index) + current_write_buffer_index;
}
return (BUFFERS_COUNT - used_blocks) - 1;
}
static void writeTask()
{
if (current_write_buffer_index != next_read_buffer_index) {
// not enough space, write the block and start a new one
if (PIOS_FLASHFS_ObjSave(pios_user_fs_id,
LOG_GET_FLIGHT_OBJID(flightnum), lognum,
(uint8_t *)buffers[next_read_buffer_index],
sizeof(DebugLogEntryData)) == 0) {
next_read_buffer_index = (next_read_buffer_index + 1) % BUFFERS_COUNT;
lognum++;
fails_count = 0;
} else {
if (fails_count++ > MAX_CONSECUTIVE_FAILS_COUNT) {
log_is_full = true;
}
}
}
} }
#endif /* ifdef PIOS_INCLUDE_DEBUGLOG */ #endif /* ifdef PIOS_INCLUDE_DEBUGLOG */
/** /**

View File

@ -0,0 +1,255 @@
/**
******************************************************************************
* @file pios_ibus.c
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
* dRonin, http://dRonin.org/, Copyright (C) 2016
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_IBus PiOS IBus receiver driver
* @{
* @brief Receives and decodes IBus protocol reciever packets
*****************************************************************************/
/*
* 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
*
* Additional note on redistribution: The copyright and license notices above
* must be maintained in each individual source file that is a derivative work
* of this source file; otherwise redistribution is prohibited.
*/
#include "pios_ibus_priv.h"
#ifdef PIOS_INCLUDE_IBUS
// 1 sync byte, 1 unknown byte, 10x channels (uint16_t), 8 unknown bytes, 2 crc bytes
#define PIOS_IBUS_BUFLEN (1 + 1 + PIOS_IBUS_NUM_INPUTS * 2 + 8 + 2)
#define PIOS_IBUS_SYNCBYTE 0x20
#define PIOS_IBUS_MAGIC 0x84fd9a39
/**
* @brief IBus receiver driver internal state data
*/
struct pios_ibus_dev {
uint32_t magic;
int buf_pos;
int rx_timer;
int failsafe_timer;
uint16_t checksum;
uint16_t channel_data[PIOS_IBUS_NUM_INPUTS];
uint8_t rx_buf[PIOS_IBUS_BUFLEN];
};
/**
* @brief Allocates a driver instance
* @retval pios_ibus_dev pointer on success, NULL on failure
*/
static struct pios_ibus_dev *PIOS_IBUS_Alloc(void);
/**
* @brief Validate a driver instance
* @param[in] dev device driver instance pointer
* @retval true on success, false on failure
*/
static bool PIOS_IBUS_Validate(const struct pios_ibus_dev *ibus_dev);
/**
* @brief Read a channel from the last received frame
* @param[in] id Driver instance
* @param[in] channel 0-based channel index
* @retval raw channel value, or error value (see pios_rcvr.h)
*/
static int32_t PIOS_IBUS_Read(uint32_t id, uint8_t channel);
/**
* @brief Set all channels in the last frame buffer to a given value
* @param[in] dev Driver instance
* @param[in] value channel value
*/
static void PIOS_IBUS_SetAllChannels(struct pios_ibus_dev *ibus_dev, uint16_t value);
/**
* @brief Serial receive callback
* @param[in] context Driver instance handle
* @param[in] buf Receive buffer
* @param[in] buf_len Number of bytes available
* @param[out] headroom Number of bytes remaining in internal buffer
* @param[out] task_woken Did we awake a task?
* @retval Number of bytes consumed from the buffer
*/
static uint16_t PIOS_IBUS_Receive(uint32_t context, uint8_t *buf, uint16_t buf_len,
uint16_t *headroom, bool *task_woken);
/**
* @brief Reset the internal receive buffer state
* @param[in] ibus_dev device driver instance pointer
*/
static void PIOS_IBUS_ResetBuffer(struct pios_ibus_dev *ibus_dev);
/**
* @brief Unpack a frame from the internal receive buffer to the channel buffer
* @param[in] ibus_dev device driver instance pointer
*/
static void PIOS_IBUS_UnpackFrame(struct pios_ibus_dev *ibus_dev);
/**
* @brief RTC tick callback
* @param[in] context Driver instance handle
*/
static void PIOS_IBUS_Supervisor(uint32_t context);
// public
const struct pios_rcvr_driver pios_ibus_rcvr_driver = {
.read = PIOS_IBUS_Read,
};
static struct pios_ibus_dev *PIOS_IBUS_Alloc(void)
{
struct pios_ibus_dev *ibus_dev;
ibus_dev = (struct pios_ibus_dev *)pios_malloc(sizeof(*ibus_dev));
if (!ibus_dev) {
return NULL;
}
memset(ibus_dev, 0, sizeof(*ibus_dev));
ibus_dev->magic = PIOS_IBUS_MAGIC;
return ibus_dev;
}
static bool PIOS_IBUS_Validate(const struct pios_ibus_dev *ibus_dev)
{
return ibus_dev && ibus_dev->magic == PIOS_IBUS_MAGIC;
}
int32_t PIOS_IBUS_Init(uint32_t *ibus_id, const struct pios_com_driver *driver,
uint32_t lower_id)
{
struct pios_ibus_dev *ibus_dev = PIOS_IBUS_Alloc();
if (!ibus_dev) {
return -1;
}
*ibus_id = (uint32_t)ibus_dev;
PIOS_IBUS_SetAllChannels(ibus_dev, PIOS_RCVR_INVALID);
if (!PIOS_RTC_RegisterTickCallback(PIOS_IBUS_Supervisor, *ibus_id)) {
PIOS_Assert(0);
}
(driver->bind_rx_cb)(lower_id, PIOS_IBUS_Receive, *ibus_id);
return 0;
}
static int32_t PIOS_IBUS_Read(uint32_t context, uint8_t channel)
{
if (channel > PIOS_IBUS_NUM_INPUTS) {
return PIOS_RCVR_INVALID;
}
struct pios_ibus_dev *ibus_dev = (struct pios_ibus_dev *)context;
if (!PIOS_IBUS_Validate(ibus_dev)) {
return PIOS_RCVR_NODRIVER;
}
return ibus_dev->channel_data[channel];
}
static void PIOS_IBUS_SetAllChannels(struct pios_ibus_dev *ibus_dev, uint16_t value)
{
for (int i = 0; i < PIOS_IBUS_NUM_INPUTS; i++) {
ibus_dev->channel_data[i] = value;
}
}
static uint16_t PIOS_IBUS_Receive(uint32_t context, uint8_t *buf, uint16_t buf_len,
uint16_t *headroom, bool *task_woken)
{
struct pios_ibus_dev *ibus_dev = (struct pios_ibus_dev *)context;
if (!PIOS_IBUS_Validate(ibus_dev)) {
goto out_fail;
}
for (int i = 0; i < buf_len; i++) {
if (ibus_dev->buf_pos == 0 && buf[i] != PIOS_IBUS_SYNCBYTE) {
continue;
}
ibus_dev->rx_buf[ibus_dev->buf_pos++] = buf[i];
if (ibus_dev->buf_pos <= PIOS_IBUS_BUFLEN - 2) {
ibus_dev->checksum -= buf[i];
} else if (ibus_dev->buf_pos == PIOS_IBUS_BUFLEN) {
PIOS_IBUS_UnpackFrame(ibus_dev);
}
}
ibus_dev->rx_timer = 0;
*headroom = PIOS_IBUS_BUFLEN - ibus_dev->buf_pos;
*task_woken = false;
return buf_len;
out_fail:
*headroom = 0;
*task_woken = false;
return 0;
}
static void PIOS_IBUS_ResetBuffer(struct pios_ibus_dev *ibus_dev)
{
ibus_dev->checksum = 0xffff;
ibus_dev->buf_pos = 0;
}
static void PIOS_IBUS_UnpackFrame(struct pios_ibus_dev *ibus_dev)
{
uint16_t rxsum = ibus_dev->rx_buf[PIOS_IBUS_BUFLEN - 1] << 8 |
ibus_dev->rx_buf[PIOS_IBUS_BUFLEN - 2];
if (ibus_dev->checksum != rxsum) {
goto out_fail;
}
uint16_t *chan = (uint16_t *)&ibus_dev->rx_buf[2];
for (int i = 0; i < PIOS_IBUS_NUM_INPUTS; i++) {
ibus_dev->channel_data[i] = *chan++;
}
ibus_dev->failsafe_timer = 0;
out_fail:
PIOS_IBUS_ResetBuffer(ibus_dev);
}
static void PIOS_IBUS_Supervisor(uint32_t context)
{
struct pios_ibus_dev *ibus_dev = (struct pios_ibus_dev *)context;
PIOS_Assert(PIOS_IBUS_Validate(ibus_dev));
if (++ibus_dev->rx_timer > 3) {
PIOS_IBUS_ResetBuffer(ibus_dev);
}
if (++ibus_dev->failsafe_timer > 32) {
PIOS_IBUS_SetAllChannels(ibus_dev, PIOS_RCVR_TIMEOUT);
}
}
#endif // PIOS_INCLUDE_IBUS
/**
* @}
* @}
*/

View File

@ -0,0 +1,38 @@
/**
******************************************************************************
*
* @file pios_ibus.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
* dRonin, http://dRonin.org/, Copyright (C) 2016
* @brief FlySky IBus functions header.
* @see The GNU Public License (GPL) Version 3
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_IBUS_H
#define PIOS_IBUS_H
/* Global Types */
/* Public Functions */
#endif /* PIOS_IBUS_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,51 @@
/**
******************************************************************************
* @file pios_ibus_priv.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
* dRonin, http://dRonin.org/, Copyright (C) 2016
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_IBus IBus receiver functions
* @{
* @brief Receives and decodes IBus protocol receiver packets
*****************************************************************************/
/*
* 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
*
* Additional note on redistribution: The copyright and license notices above
* must be maintained in each individual source file that is a derivative work
* of this source file; otherwise redistribution is prohibited.
*/
#ifndef PIOS_IBUS_PRIV_H
#define PIOS_IBUS_PRIV_H
#include <pios.h>
#include <pios_usart_priv.h>
/* IBUS receiver instance configuration */
extern const struct pios_rcvr_driver pios_ibus_rcvr_driver;
extern int32_t PIOS_IBUS_Init(uint32_t *ibus_id,
const struct pios_com_driver *driver,
uint32_t lower_id);
#endif // PIOS_IBUS_PRIV_H
/**
* @}
* @}
*/

View File

@ -241,6 +241,10 @@ extern "C" {
#include <pios_srxl.h> #include <pios_srxl.h>
#endif #endif
#ifdef PIOS_INCLUDE_IBUS
#include <pios_ibus.h>
#endif
/* PIOS abstract receiver interface */ /* PIOS abstract receiver interface */
#ifdef PIOS_INCLUDE_RCVR #ifdef PIOS_INCLUDE_RCVR
#include <pios_rcvr.h> #include <pios_rcvr.h>

View File

@ -1151,6 +1151,50 @@ static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = {
#endif /* PIOS_INCLUDE_SRXL */ #endif /* PIOS_INCLUDE_SRXL */
#if defined(PIOS_INCLUDE_IBUS)
/*
* IBUS USART
*/
#include <pios_ibus_priv.h>
static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = {
.regs = USART3,
.init = {
.USART_BaudRate = 115200,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
#endif /* PIOS_INCLUDE_IBUS */
#if defined(PIOS_INCLUDE_SBUS) #if defined(PIOS_INCLUDE_SBUS)
/* /*
* S.Bus USART * S.Bus USART

View File

@ -106,6 +106,7 @@
#define PIOS_INCLUDE_EXBUS #define PIOS_INCLUDE_EXBUS
#define PIOS_INCLUDE_SRXL #define PIOS_INCLUDE_SRXL
#define PIOS_INCLUDE_HOTT #define PIOS_INCLUDE_HOTT
#define PIOS_INCLUDE_IBUS
/* #define PIOS_INCLUDE_GCSRCVR */ /* #define PIOS_INCLUDE_GCSRCVR */
/* #define PIOS_INCLUDE_OPLINKRCVR */ /* #define PIOS_INCLUDE_OPLINKRCVR */

View File

@ -156,6 +156,26 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm
pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id;
} }
static void PIOS_Board_configure_ibus(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_ibus_id;
if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_id;
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_rcvr_id;
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id;
}
/** /**
* Configuration for MPU6000 chip * Configuration for MPU6000 chip
@ -382,7 +402,6 @@ void PIOS_Board_Init(void)
break; break;
case HWSETTINGS_USB_VCPPORT_USBTELEMETRY: case HWSETTINGS_USB_VCPPORT_USBTELEMETRY:
#if defined(PIOS_INCLUDE_COM) #if defined(PIOS_INCLUDE_COM)
{ {
uint32_t pios_usb_cdc_id; uint32_t pios_usb_cdc_id;
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
@ -670,6 +689,12 @@ void PIOS_Board_Init(void)
#endif /* PIOS_INCLUDE_SRXL */ #endif /* PIOS_INCLUDE_SRXL */
break; break;
case HWSETTINGS_CC_FLEXIPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg);
#endif /* PIOS_INCLUDE_IBUS */
break;
case HWSETTINGS_CC_FLEXIPORT_DEBUGCONSOLE: case HWSETTINGS_CC_FLEXIPORT_DEBUGCONSOLE:
#if defined(PIOS_INCLUDE_COM) #if defined(PIOS_INCLUDE_COM)
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) #if defined(PIOS_INCLUDE_DEBUG_CONSOLE)

View File

@ -272,6 +272,12 @@ extern uint32_t pios_com_mavlink_id;
#define PIOS_SRXL_MAX_DEVS 1 #define PIOS_SRXL_MAX_DEVS 1
#define PIOS_SRXL_NUM_INPUTS 16 #define PIOS_SRXL_NUM_INPUTS 16
// -------------------------
// Receiver FlySky IBus input
// -------------------------
#define PIOS_IBUS_MAX_DEVS 1
#define PIOS_IBUS_NUM_INPUTS 10
// ------------------------- // -------------------------
// Servo outputs // Servo outputs
// ------------------------- // -------------------------

View File

@ -973,6 +973,64 @@ static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = {
}, },
}; };
static const struct pios_usart_cfg pios_usart_rcvrport_cfg = {
.regs = USART6,
.remap = GPIO_AF_USART6,
.init = {
.USART_BaudRate = 57600,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART6_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.dtr = {
// FlexIO pin 9
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
.tx = {
// * 7: PC6 = TIM8 CH1, USART6 TX
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource6,
},
.rx = {
// * 8: PC7 = TIM8 CH2, USART6 RX
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource7,
}
};
#if defined(PIOS_INCLUDE_COM) #if defined(PIOS_INCLUDE_COM)
#include <pios_com_priv.h> #include <pios_com_priv.h>

View File

@ -235,7 +235,8 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 #define PIOS_COM_TELEM_RF_RX_BUF_LEN 512
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 #define PIOS_COM_TELEM_RF_TX_BUF_LEN 512
#define PIOS_COM_GPS_RX_BUF_LEN 32 #define PIOS_COM_GPS_RX_BUF_LEN 128
#define PIOS_COM_GPS_TX_BUF_LEN 32
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 #define PIOS_COM_TELEM_USB_RX_BUF_LEN 65
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 #define PIOS_COM_TELEM_USB_TX_BUF_LEN 65
@ -626,7 +627,7 @@ void PIOS_Board_Init(void)
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
break; break;
case HWSETTINGS_RM_MAINPORT_GPS: case HWSETTINGS_RM_MAINPORT_GPS:
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
break; break;
case HWSETTINGS_RM_MAINPORT_SBUS: case HWSETTINGS_RM_MAINPORT_SBUS:
#if defined(PIOS_INCLUDE_SBUS) #if defined(PIOS_INCLUDE_SBUS)
@ -731,7 +732,7 @@ void PIOS_Board_Init(void)
#endif /* PIOS_INCLUDE_I2C */ #endif /* PIOS_INCLUDE_I2C */
break; break;
case HWSETTINGS_RM_FLEXIPORT_GPS: case HWSETTINGS_RM_FLEXIPORT_GPS:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
break; break;
case HWSETTINGS_RM_FLEXIPORT_DSM: case HWSETTINGS_RM_FLEXIPORT_DSM:
// TODO: Define the various Channelgroup for Revo dsm inputs and handle here // TODO: Define the various Channelgroup for Revo dsm inputs and handle here
@ -895,6 +896,12 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PPM: case HWSETTINGS_RM_RCVRPORT_PPM:
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS: case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
case HWSETTINGS_RM_RCVRPORT_PPMPWM: case HWSETTINGS_RM_RCVRPORT_PPMPWM:
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
#if defined(PIOS_INCLUDE_PPM) #if defined(PIOS_INCLUDE_PPM)
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) { if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
// configure servo outputs and the remaining 5 inputs as outputs // configure servo outputs and the remaining 5 inputs as outputs
@ -916,6 +923,35 @@ void PIOS_Board_Init(void)
break; break;
} }
// Configure rcvrport usart
switch (hwsettings_rcvrport) {
case HWSETTINGS_RM_RCVRPORT_TELEMETRY:
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
break;
case HWSETTINGS_RM_RCVRPORT_DEBUGCONSOLE:
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
break;
case HWSETTINGS_RM_RCVRPORT_COMBRIDGE:
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break;
case HWSETTINGS_RM_RCVRPORT_MSP:
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RM_RCVRPORT_MAVLINK:
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
case HWSETTINGS_RM_RCVRPORT_GPS:
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
break;
}
#if defined(PIOS_INCLUDE_GCSRCVR) #if defined(PIOS_INCLUDE_GCSRCVR)
GCSReceiverInitialize(); GCSReceiverInitialize();

View File

@ -1171,6 +1171,55 @@ static const struct pios_usart_cfg pios_usart_hott_flexi_cfg = {
#endif /* PIOS_INCLUDE_HOTT */ #endif /* PIOS_INCLUDE_HOTT */
#if defined(PIOS_INCLUDE_IBUS)
/*
* IBUS USART
*/
#include <pios_ibus_priv.h>
static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = {
.regs = USART3,
.remap = GPIO_AF_USART3,
.init = {
.USART_BaudRate = 115200,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_IBUS */
#if defined(PIOS_INCLUDE_EXBUS) #if defined(PIOS_INCLUDE_EXBUS)
/* /*
* EXBUS USART * EXBUS USART

View File

@ -107,6 +107,7 @@
#define PIOS_INCLUDE_SRXL #define PIOS_INCLUDE_SRXL
#define PIOS_INCLUDE_HOTT #define PIOS_INCLUDE_HOTT
#define PIOS_INCLUDE_EXBUS #define PIOS_INCLUDE_EXBUS
#define PIOS_INCLUDE_IBUS
#define PIOS_INCLUDE_GCSRCVR #define PIOS_INCLUDE_GCSRCVR
#define PIOS_INCLUDE_OPLINKRCVR #define PIOS_INCLUDE_OPLINKRCVR
#define PIOS_INCLUDE_OPENLRS_RCVR #define PIOS_INCLUDE_OPENLRS_RCVR

View File

@ -341,6 +341,27 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm
pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id;
} }
static void PIOS_Board_configure_ibus(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_ibus_id;
if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_id;
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_rcvr_id;
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id;
}
static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg) static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg)
{ {
/* Set up the receiver port. Later this should be optional */ /* Set up the receiver port. Later this should be optional */
@ -586,6 +607,12 @@ void PIOS_Board_Init(void)
#endif /* PIOS_INCLUDE_SRXL */ #endif /* PIOS_INCLUDE_SRXL */
break; break;
case HWSETTINGS_RM_FLEXIPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg);
#endif /* PIOS_INCLUDE_IBUS */
break;
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD: case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD:
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMH: case HWSETTINGS_RM_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT) #if defined(PIOS_INCLUDE_HOTT)
@ -985,10 +1012,9 @@ void PIOS_Board_Init(void)
/* Configure the receiver port*/ /* Configure the receiver port*/
uint8_t hwsettings_rcvrport; uint8_t hwsettings_rcvrport;
HwSettingsRM_RcvrPortGet(&hwsettings_rcvrport); HwSettingsRM_RcvrPortGet(&hwsettings_rcvrport);
//
// Configure rcvrport PPM/PWM/OUTPUTS
switch (hwsettings_rcvrport) { switch (hwsettings_rcvrport) {
case HWSETTINGS_RM_RCVRPORT_DISABLED:
break;
case HWSETTINGS_RM_RCVRPORT_PWM: case HWSETTINGS_RM_RCVRPORT_PWM:
#if defined(PIOS_INCLUDE_PWM) #if defined(PIOS_INCLUDE_PWM)
/* Set up the receiver port. Later this should be optional */ /* Set up the receiver port. Later this should be optional */
@ -999,6 +1025,11 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS: case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
case HWSETTINGS_RM_RCVRPORT_PPMPWM: case HWSETTINGS_RM_RCVRPORT_PPMPWM:
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY: case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
#if defined(PIOS_INCLUDE_PPM) #if defined(PIOS_INCLUDE_PPM)
PIOS_Board_configure_ppm(&pios_ppm_cfg); PIOS_Board_configure_ppm(&pios_ppm_cfg);
@ -1012,28 +1043,42 @@ void PIOS_Board_Init(void)
PIOS_Board_configure_pwm(&pios_pwm_ppm_cfg); PIOS_Board_configure_pwm(&pios_pwm_ppm_cfg);
} }
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY) {
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
}
break; break;
#endif /* PIOS_INCLUDE_PPM */ #endif /* PIOS_INCLUDE_PPM */
case HWSETTINGS_RM_RCVRPORT_OUTPUTS: case HWSETTINGS_RM_RCVRPORT_OUTPUTS:
// configure only the servo outputs // configure only the servo outputs
pios_servo_cfg = &pios_servo_cfg_out_in; pios_servo_cfg = &pios_servo_cfg_out_in;
break; break;
}
// Configure rcvrport usart
switch (hwsettings_rcvrport) {
case HWSETTINGS_RM_RCVRPORT_TELEMETRY: case HWSETTINGS_RM_RCVRPORT_TELEMETRY:
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
break; break;
case HWSETTINGS_RM_RCVRPORT_DEBUGCONSOLE:
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
break;
case HWSETTINGS_RM_RCVRPORT_COMBRIDGE: case HWSETTINGS_RM_RCVRPORT_COMBRIDGE:
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break; break;
case HWSETTINGS_RM_RCVRPORT_MSP: case HWSETTINGS_RM_RCVRPORT_MSP:
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id); PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break; break;
case HWSETTINGS_RM_RCVRPORT_MAVLINK: case HWSETTINGS_RM_RCVRPORT_MAVLINK:
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break; break;
case HWSETTINGS_RM_RCVRPORT_GPS:
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
break;
} }
#if defined(PIOS_INCLUDE_GCSRCVR) #if defined(PIOS_INCLUDE_GCSRCVR)

View File

@ -287,6 +287,12 @@ extern uint32_t pios_packet_handler;
#define PIOS_DSM_MAX_DEVS 2 #define PIOS_DSM_MAX_DEVS 2
#define PIOS_DSM_NUM_INPUTS 12 #define PIOS_DSM_NUM_INPUTS 12
// -------------------------
// Receiver FlySky IBus input
// -------------------------
#define PIOS_IBUS_MAX_DEVS 1
#define PIOS_IBUS_NUM_INPUTS 10
// ------------------------- // -------------------------
// Servo outputs // Servo outputs
// ------------------------- // -------------------------

View File

@ -634,6 +634,55 @@ static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = {
#endif /* PIOS_INCLUDE_SRXL */ #endif /* PIOS_INCLUDE_SRXL */
#if defined(PIOS_INCLUDE_IBUS)
/*
* IBUS USART
*/
#include <pios_ibus_priv.h>
static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = {
.regs = FLEXI_USART_REGS,
.remap = FLEXI_USART_REMAP,
.init = {
.USART_BaudRate = 115200,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.init = {
.NVIC_IRQChannel = FLEXI_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = FLEXI_USART_RX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_RX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = FLEXI_USART_TX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_TX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_IBUS */
#if defined(PIOS_INCLUDE_EXBUS) #if defined(PIOS_INCLUDE_EXBUS)
/* /*
* EXBUS USART * EXBUS USART
@ -681,8 +730,8 @@ static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = {
}, },
}; };
#endif /* PIOS_INCLUDE_EXBUS */ #endif /* PIOS_INCLUDE_EXBUS */
/* /*
* HK OSD * HK OSD
*/ */

View File

@ -111,6 +111,7 @@
#define PIOS_INCLUDE_SRXL #define PIOS_INCLUDE_SRXL
#define PIOS_INCLUDE_HOTT #define PIOS_INCLUDE_HOTT
#define PIOS_INCLUDE_EXBUS #define PIOS_INCLUDE_EXBUS
#define PIOS_INCLUDE_IBUS
#define PIOS_INCLUDE_GCSRCVR #define PIOS_INCLUDE_GCSRCVR
// #define PIOS_INCLUDE_OPLINKRCVR // #define PIOS_INCLUDE_OPLINKRCVR

View File

@ -288,6 +288,27 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm
pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id;
} }
static void PIOS_Board_configure_ibus(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_ibus_id;
if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_id;
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_rcvr_id;
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id;
}
static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg) static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg)
{ {
/* Set up the receiver port. Later this should be optional */ /* Set up the receiver port. Later this should be optional */
@ -733,7 +754,13 @@ void PIOS_Board_Init(void)
} }
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id; pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id;
} }
#endif #endif /* PIOS_INCLUDE_SRXL */
break;
case HWSETTINGS_RM_FLEXIPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg);
#endif /* PIOS_INCLUDE_IBUS */
break; break;
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD: case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD:

View File

@ -287,6 +287,12 @@ extern uint32_t pios_packet_handler;
#define PIOS_DSM_MAX_DEVS 2 #define PIOS_DSM_MAX_DEVS 2
#define PIOS_DSM_NUM_INPUTS 12 #define PIOS_DSM_NUM_INPUTS 12
// -------------------------
// Receiver FlySky IBus input
// -------------------------
#define PIOS_IBUS_MAX_DEVS 1
#define PIOS_IBUS_NUM_INPUTS 10
// ------------------------- // -------------------------
// Servo outputs // Servo outputs
// ------------------------- // -------------------------

View File

@ -838,6 +838,86 @@ static const struct pios_usart_cfg pios_usart_srxl_rcvr_cfg = {
#endif /* PIOS_INCLUDE_SRXL */ #endif /* PIOS_INCLUDE_SRXL */
#if defined(PIOS_INCLUDE_IBUS)
/*
* IBUS USART
*/
#include <pios_ibus_priv.h>
static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = {
.regs = USART3,
.remap = GPIO_AF_USART3,
.init = {
.USART_BaudRate = 115200,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
static const struct pios_usart_cfg pios_usart_ibus_rcvr_cfg = {
.regs = USART6,
.remap = GPIO_AF_USART6,
.init = {
.USART_BaudRate = 115200,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART6_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_IBUS */
// these were copied from Revo support // these were copied from Revo support
// they might need to be further modified for Sparky2 support // they might need to be further modified for Sparky2 support
#if defined(PIOS_INCLUDE_HOTT) #if defined(PIOS_INCLUDE_HOTT)

View File

@ -111,6 +111,7 @@
#define PIOS_INCLUDE_SRXL #define PIOS_INCLUDE_SRXL
#define PIOS_INCLUDE_HOTT #define PIOS_INCLUDE_HOTT
#define PIOS_INCLUDE_EXBUS #define PIOS_INCLUDE_EXBUS
#define PIOS_INCLUDE_IBUS
#define PIOS_INCLUDE_GCSRCVR #define PIOS_INCLUDE_GCSRCVR
#define PIOS_INCLUDE_OPLINKRCVR #define PIOS_INCLUDE_OPLINKRCVR
#define PIOS_INCLUDE_OPENLRS_RCVR #define PIOS_INCLUDE_OPENLRS_RCVR

View File

@ -327,6 +327,27 @@ static void PIOS_Board_configure_srxl(const struct pios_usart_cfg *usart_cfg)
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id; pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id;
} }
static void PIOS_Board_configure_ibus(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_ibus_id;
if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_id;
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_rcvr_id;
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id;
}
static void PIOS_Board_configure_exbus(const struct pios_usart_cfg *usart_cfg) static void PIOS_Board_configure_exbus(const struct pios_usart_cfg *usart_cfg)
{ {
@ -582,6 +603,12 @@ void PIOS_Board_Init(void)
#endif /* PIOS_INCLUDE_SRXL */ #endif /* PIOS_INCLUDE_SRXL */
break; break;
case HWSETTINGS_SPK2_FLEXIPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg);
#endif /* PIOS_INCLUDE_IBUS */
break;
case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD: case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD:
case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMH: case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT) #if defined(PIOS_INCLUDE_HOTT)
@ -926,7 +953,7 @@ void PIOS_Board_Init(void)
// Configure the receiver port // Configure the receiver port
// Sparky2 receiver input on PC7 TIM8 CH2 // Sparky2 receiver input on PC7 TIM8 CH2
// include PPM,S.Bus,DSM,SRXL,EX.Bus,HoTT SUMD,HoTT SUMH // include PPM,S.Bus,DSM,SRXL,IBus,EX.Bus,HoTT SUMD,HoTT SUMH
uint8_t hwsettings_rcvrport; uint8_t hwsettings_rcvrport;
HwSettingsSPK2_RcvrPortGet(&hwsettings_rcvrport); HwSettingsSPK2_RcvrPortGet(&hwsettings_rcvrport);
@ -962,6 +989,11 @@ void PIOS_Board_Init(void)
PIOS_Board_configure_srxl(&pios_usart_srxl_rcvr_cfg); PIOS_Board_configure_srxl(&pios_usart_srxl_rcvr_cfg);
#endif /* PIOS_INCLUDE_SRXL */ #endif /* PIOS_INCLUDE_SRXL */
break; break;
case HWSETTINGS_SPK2_RCVRPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_rcvr_cfg);
#endif /* PIOS_INCLUDE_IBUS */
break;
case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMD: case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMD:
case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMH: case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT) #if defined(PIOS_INCLUDE_HOTT)

View File

@ -289,6 +289,12 @@ extern uint32_t pios_packet_handler;
#define PIOS_DSM_MAX_DEVS 2 #define PIOS_DSM_MAX_DEVS 2
#define PIOS_DSM_NUM_INPUTS 12 #define PIOS_DSM_NUM_INPUTS 12
// -------------------------
// Receiver FlySky IBus input
// -------------------------
#define PIOS_IBUS_MAX_DEVS 1
#define PIOS_IBUS_NUM_INPUTS 10
// ------------------------- // -------------------------
// Servo outputs // Servo outputs
// ------------------------- // -------------------------
@ -304,13 +310,14 @@ extern uint32_t pios_packet_handler;
// ADC // ADC
// PIOS_ADC_PinGet(0) = Current sensor // PIOS_ADC_PinGet(0) = Current sensor
// PIOS_ADC_PinGet(1) = Voltage sensor // PIOS_ADC_PinGet(1) = Voltage sensor
// PIOS_ADC_PinGet(4) = VREF // PIOS_ADC_PinGet(7) = VREF
// PIOS_ADC_PinGet(5) = Temperature sensor // PIOS_ADC_PinGet(8) = Temperature sensor
// ------------------------- // -------------------------
#define PIOS_DMA_PIN_CONFIG \ #define PIOS_DMA_PIN_CONFIG \
{ \ { \
{ GPIOC, GPIO_Pin_3, ADC_Channel_13, false }, /* batt/sonar pin 3 */ \ { GPIOC, GPIO_Pin_2, ADC_Channel_12, false }, /* Analog port pin 3 */ \
{ GPIOC, GPIO_Pin_2, ADC_Channel_12, false }, /* batt/sonar pin 4 */ \ { GPIOC, GPIO_Pin_3, ADC_Channel_13, false }, /* Analog port pin 4 */ \
{ GPIOA, GPIO_Pin_4, ADC_Channel_4, false }, /* Analog port pin2 (DAC) */ \
{ GPIOA, GPIO_Pin_3, ADC_Channel_3, false }, /* Servo pin 3 */ \ { GPIOA, GPIO_Pin_3, ADC_Channel_3, false }, /* Servo pin 3 */ \
{ GPIOA, GPIO_Pin_2, ADC_Channel_2, false }, /* Servo pin 4 */ \ { GPIOA, GPIO_Pin_2, ADC_Channel_2, false }, /* Servo pin 4 */ \
{ GPIOA, GPIO_Pin_1, ADC_Channel_1, false }, /* Servo pin 5 */ \ { GPIOA, GPIO_Pin_1, ADC_Channel_1, false }, /* Servo pin 5 */ \
@ -322,12 +329,12 @@ extern uint32_t pios_packet_handler;
/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */ /* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */
/* which is annoying because this then determines the rate at which we generate buffer turnover events */ /* which is annoying because this then determines the rate at which we generate buffer turnover events */
/* the objective here is to get enough buffer space to support 100Hz averaging rate */ /* the objective here is to get enough buffer space to support 100Hz averaging rate */
#define PIOS_ADC_NUM_CHANNELS 8 #define PIOS_ADC_NUM_CHANNELS 9
#define PIOS_ADC_MAX_OVERSAMPLING 2 #define PIOS_ADC_MAX_OVERSAMPLING 2
#define PIOS_ADC_USE_ADC2 0 #define PIOS_ADC_USE_ADC2 0
#define PIOS_ADC_USE_TEMP_SENSOR #define PIOS_ADC_USE_TEMP_SENSOR
#define PIOS_ADC_TEMPERATURE_PIN 7 #define PIOS_ADC_TEMPERATURE_PIN 8
// ------------------------- // -------------------------
// USB // USB

View File

@ -196,7 +196,7 @@ void ConfigGadgetWidget::onAutopilotConnect()
// Revolution family // Revolution family
QWidget *qwd = new ConfigRevoWidget(this); QWidget *qwd = new ConfigRevoWidget(this);
stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd); stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd);
if (board == 0x0903) { if (board == 0x0903 || board == 0x0904) {
qwd = new ConfigRevoHWWidget(this); qwd = new ConfigRevoHWWidget(this);
} else if (board == 0x0905) { } else if (board == 0x0905) {
qwd = new ConfigRevoNanoHWWidget(this); qwd = new ConfigRevoNanoHWWidget(this);

View File

@ -203,6 +203,10 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
connect(wizardUi->wzCancel, SIGNAL(clicked()), this, SLOT(wzCancel())); connect(wizardUi->wzCancel, SIGNAL(clicked()), this, SLOT(wzCancel()));
connect(wizardUi->wzBack, SIGNAL(clicked()), this, SLOT(wzBack())); connect(wizardUi->wzBack, SIGNAL(clicked()), this, SLOT(wzBack()));
connect(ReceiverActivity::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateReceiverActivityStatus()));
ui->receiverActivityStatus->setStyleSheet("QLabel { background-color: darkGreen; color: rgb(255, 255, 255); \
border: 1px solid grey; border-radius: 5; margin:1px; font:bold;}");
ui->stackedWidget->setCurrentIndex(0); ui->stackedWidget->setCurrentIndex(0);
QList<QWidget *> widgets = QList<QWidget *>() << ui->fmsModePos1 << ui->fmsModePos2 << ui->fmsModePos3 << QList<QWidget *> widgets = QList<QWidget *>() << ui->fmsModePos1 << ui->fmsModePos2 << ui->fmsModePos3 <<
ui->fmsModePos4 << ui->fmsModePos5 << ui->fmsModePos6; ui->fmsModePos4 << ui->fmsModePos5 << ui->fmsModePos6;
@ -2117,6 +2121,32 @@ void ConfigInputWidget::forceOneFlightMode()
manualSettingsObj->setData(manualSettingsData); manualSettingsObj->setData(manualSettingsData);
} }
void ConfigInputWidget::updateReceiverActivityStatus()
{
ReceiverActivity *receiverActivity = ReceiverActivity::GetInstance(getObjectManager());
Q_ASSERT(receiverActivity);
UAVObjectField *activeGroup = receiverActivity->getField(QString("ActiveGroup"));
Q_ASSERT(activeGroup);
UAVObjectField *activeChannel = receiverActivity->getField(QString("ActiveChannel"));
Q_ASSERT(activeChannel);
QString activeGroupText = activeGroup->getValue().toString();
QString activeChannelText = activeChannel->getValue().toString();
if (activeGroupText != "None") {
ui->receiverActivityStatus->setText(tr("%1 input - Channel %2").arg(activeGroupText).arg(activeChannelText));
ui->receiverActivityStatus->setStyleSheet("QLabel { background-color: green; color: rgb(255, 255, 255); \
border: 1px solid grey; border-radius: 5; margin:1px; font:bold;}");
} else {
ui->receiverActivityStatus->setText(tr("No activity"));
ui->receiverActivityStatus->setStyleSheet("QLabel { background-color: darkGreen; color: rgb(255, 255, 255); \
border: 1px solid grey; border-radius: 5; margin:1px; font:bold;}");
}
}
void ConfigInputWidget::failsafeFlightModeChanged(int index) void ConfigInputWidget::failsafeFlightModeChanged(int index)
{ {
ui->failsafeFlightMode->setEnabled(index != -1); ui->failsafeFlightMode->setEnabled(index != -1);

View File

@ -230,6 +230,7 @@ private slots:
void resetFlightModeSettings(); void resetFlightModeSettings();
void resetActuatorSettings(); void resetActuatorSettings();
void forceOneFlightMode(); void forceOneFlightMode();
void updateReceiverActivityStatus();
void failsafeFlightModeChanged(int index); void failsafeFlightModeChanged(int index);
void failsafeFlightModeCbToggled(bool checked); void failsafeFlightModeCbToggled(bool checked);

View File

@ -70,11 +70,13 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed); addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed); addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed);
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbRcvrGPSSpeed);
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbRcvrComSpeed); addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbRcvrComSpeed);
// Add Gps protocol configuration // Add Gps protocol configuration
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol); addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol); addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbRcvrGPSProtocol);
connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp())); connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
@ -158,7 +160,12 @@ void ConfigRevoHWWidget::usbVCPPortChanged(int index)
if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) { if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
} }
if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE, vcpComBridgeEnabled); enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE, vcpComBridgeEnabled);
enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE, vcpComBridgeEnabled);
// _DEBUGCONSOLE modes are mutual exclusive // _DEBUGCONSOLE modes are mutual exclusive
if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) { if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
@ -168,6 +175,12 @@ void ConfigRevoHWWidget::usbVCPPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) { if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
} }
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
} }
// _USBTELEMETRY modes are mutual exclusive // _USBTELEMETRY modes are mutual exclusive
@ -207,8 +220,10 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) { if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
} }
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY) if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)) {
|| isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) { setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
} }
break; break;
@ -221,6 +236,13 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) { if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
} }
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMGPS)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
break; break;
case HwSettings::RM_FLEXIPORT_COMBRIDGE: case HwSettings::RM_FLEXIPORT_COMBRIDGE:
m_ui->cbFlexiComSpeed->setVisible(true); m_ui->cbFlexiComSpeed->setVisible(true);
@ -230,6 +252,9 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) { if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
} }
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break; break;
case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE: case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE:
m_ui->cbFlexiComSpeed->setVisible(true); m_ui->cbFlexiComSpeed->setVisible(true);
@ -239,6 +264,42 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) { if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED); setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
} }
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
break;
case HwSettings::RM_FLEXIPORT_OSDHK:
m_ui->lblFlexiSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_OSDHK)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
break;
case HwSettings::RM_FLEXIPORT_MSP:
m_ui->lblFlexiSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMSP)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break;
case HwSettings::RM_FLEXIPORT_MAVLINK:
m_ui->lblFlexiSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMAVLINK)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break; break;
default: default:
m_ui->lblFlexiSpeed->setVisible(false); m_ui->lblFlexiSpeed->setVisible(false);
@ -265,8 +326,10 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) { if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
} }
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY) if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)) {
|| isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) { setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
} }
break; break;
@ -279,6 +342,12 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) { if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
} }
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMGPS)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
break; break;
case HwSettings::RM_MAINPORT_COMBRIDGE: case HwSettings::RM_MAINPORT_COMBRIDGE:
m_ui->cbMainComSpeed->setVisible(true); m_ui->cbMainComSpeed->setVisible(true);
@ -288,6 +357,9 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) { if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
} }
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break; break;
case HwSettings::RM_MAINPORT_DEBUGCONSOLE: case HwSettings::RM_MAINPORT_DEBUGCONSOLE:
m_ui->cbMainComSpeed->setVisible(true); m_ui->cbMainComSpeed->setVisible(true);
@ -297,6 +369,42 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) { if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED); setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
} }
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
break;
case HwSettings::RM_MAINPORT_OSDHK:
m_ui->lblMainSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_OSDHK)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
break;
case HwSettings::RM_MAINPORT_MSP:
m_ui->lblMainSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMSP)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break;
case HwSettings::RM_MAINPORT_MAVLINK:
m_ui->lblMainSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMAVLINK)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break; break;
default: default:
m_ui->lblMainSpeed->setVisible(false); m_ui->lblMainSpeed->setVisible(false);
@ -310,6 +418,12 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index)
m_ui->lblRcvrSpeed->setVisible(true); m_ui->lblRcvrSpeed->setVisible(true);
m_ui->cbRcvrTelemSpeed->setVisible(false); m_ui->cbRcvrTelemSpeed->setVisible(false);
m_ui->cbRcvrComSpeed->setVisible(false); m_ui->cbRcvrComSpeed->setVisible(false);
m_ui->cbRcvrGPSSpeed->setVisible(false);
// Add Gps protocol configuration
m_ui->cbRcvrGPSProtocol->setVisible(false);
m_ui->lblRcvrGPSProtocol->setVisible(false);
switch (getComboboxSelectedOption(m_ui->cbRcvr)) { switch (getComboboxSelectedOption(m_ui->cbRcvr)) {
case HwSettings::RM_RCVRPORT_TELEMETRY: case HwSettings::RM_RCVRPORT_TELEMETRY:
@ -324,6 +438,7 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index)
} }
break; break;
case HwSettings::RM_RCVRPORT_COMBRIDGE: case HwSettings::RM_RCVRPORT_COMBRIDGE:
case HwSettings::RM_RCVRPORT_PPMCOMBRIDGE:
m_ui->cbRcvrComSpeed->setVisible(true); m_ui->cbRcvrComSpeed->setVisible(true);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) { if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
@ -332,6 +447,51 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index)
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
} }
break; break;
case HwSettings::RM_RCVRPORT_DEBUGCONSOLE:
case HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE:
m_ui->cbRcvrComSpeed->setVisible(true);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
break;
case HwSettings::RM_RCVRPORT_GPS:
case HwSettings::RM_RCVRPORT_PPMGPS:
// Add Gps protocol configuration
m_ui->cbRcvrGPSProtocol->setVisible(true);
m_ui->lblRcvrGPSProtocol->setVisible(true);
m_ui->cbRcvrGPSSpeed->setVisible(true);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
break;
case HwSettings::RM_RCVRPORT_MSP:
case HwSettings::RM_RCVRPORT_PPMMSP:
m_ui->lblRcvrSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
break;
case HwSettings::RM_RCVRPORT_MAVLINK:
case HwSettings::RM_RCVRPORT_PPMMAVLINK:
m_ui->lblRcvrSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
break;
default: default:
m_ui->lblRcvrSpeed->setVisible(false); m_ui->lblRcvrSpeed->setVisible(false);
break; break;

View File

@ -655,6 +655,28 @@
<item> <item>
<widget class="QComboBox" name="cbRcvrComSpeed"/> <widget class="QComboBox" name="cbRcvrComSpeed"/>
</item> </item>
<item>
<widget class="QComboBox" name="cbRcvrGPSSpeed"/>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QLabel" name="lblRcvrGPSProtocol">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Protocol</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="cbRcvrGPSProtocol"/>
</item>
</layout> </layout>
</item> </item>
</layout> </layout>

View File

@ -136,7 +136,7 @@
<property name="verticalSpacing"> <property name="verticalSpacing">
<number>6</number> <number>6</number>
</property> </property>
<item row="1" column="0"> <item row="3" column="0">
<widget class="QGroupBox" name="groupBox_5"> <widget class="QGroupBox" name="groupBox_5">
<property name="title"> <property name="title">
<string>Input Channel Configuration</string> <string>Input Channel Configuration</string>
@ -281,114 +281,171 @@
</widget> </widget>
</item> </item>
<item row="0" column="0"> <item row="0" column="0">
<widget class="QGroupBox" name="groupBox_3"> <layout class="QHBoxLayout" name="horizontalLayout_8">
<property name="title"> <property name="topMargin">
<string>Calibration and Configuration Options</string> <number>0</number>
</property> </property>
<layout class="QHBoxLayout" name="horizontalLayout_7"> <item>
<item> <widget class="QGroupBox" name="groupBox_3">
<spacer name="horizontalSpacer_10"> <property name="title">
<property name="orientation"> <string>Calibration and Configuration Options</string>
<enum>Qt::Horizontal</enum> </property>
</property> <layout class="QHBoxLayout" name="horizontalLayout_7">
<property name="sizeHint" stdset="0"> <item>
<size> <spacer name="horizontalSpacer_10">
<width>40</width> <property name="orientation">
<height>20</height> <enum>Qt::Horizontal</enum>
</size> </property>
</property> <property name="sizeHint" stdset="0">
</spacer> <size>
</item> <width>40</width>
<item> <height>20</height>
<widget class="QPushButton" name="configurationWizard"> </size>
<property name="sizePolicy"> </property>
<sizepolicy hsizetype="Minimum" vsizetype="Preferred"> </spacer>
<horstretch>0</horstretch> </item>
<verstretch>0</verstretch> <item>
</sizepolicy> <widget class="QPushButton" name="configurationWizard">
</property> <property name="sizePolicy">
<property name="minimumSize"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<size> <horstretch>0</horstretch>
<width>210</width> <verstretch>0</verstretch>
<height>0</height> </sizepolicy>
</size> </property>
</property> <property name="minimumSize">
<property name="text"> <size>
<string>Start Transmitter Setup Wizard</string> <width>240</width>
</property> <height>0</height>
<property name="checkable"> </size>
<bool>false</bool> </property>
</property> <property name="text">
<property name="checked"> <string>Start Transmitter Setup Wizard</string>
<bool>false</bool> </property>
</property> <property name="checkable">
<property name="autoDefault"> <bool>false</bool>
<bool>false</bool> </property>
</property> <property name="checked">
<property name="default"> <bool>false</bool>
<bool>false</bool> </property>
</property> <property name="autoDefault">
<property name="flat"> <bool>false</bool>
<bool>false</bool> </property>
</property> <property name="default">
</widget> <bool>false</bool>
</item> </property>
<item> <property name="flat">
<spacer name="horizontalSpacer_7"> <bool>false</bool>
<property name="orientation"> </property>
<enum>Qt::Horizontal</enum> </widget>
</property> </item>
<property name="sizeHint" stdset="0"> <item>
<size> <spacer name="horizontalSpacer_7">
<width>40</width> <property name="orientation">
<height>20</height> <enum>Qt::Horizontal</enum>
</size> </property>
</property> <property name="sizeHint" stdset="0">
</spacer> <size>
</item> <width>40</width>
<item> <height>20</height>
<widget class="QPushButton" name="runCalibration"> </size>
<property name="enabled"> </property>
<bool>true</bool> </spacer>
</property> </item>
<property name="sizePolicy"> <item>
<sizepolicy hsizetype="Minimum" vsizetype="Preferred"> <widget class="QPushButton" name="runCalibration">
<horstretch>0</horstretch> <property name="enabled">
<verstretch>0</verstretch> <bool>true</bool>
</sizepolicy> </property>
</property> <property name="sizePolicy">
<property name="minimumSize"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<size> <horstretch>0</horstretch>
<width>210</width> <verstretch>0</verstretch>
<height>0</height> </sizepolicy>
</size> </property>
</property> <property name="minimumSize">
<property name="autoFillBackground"> <size>
<bool>false</bool> <width>240</width>
</property> <height>0</height>
<property name="text"> </size>
<string>Start Manual Calibration</string> </property>
</property> <property name="autoFillBackground">
<property name="checkable"> <bool>false</bool>
<bool>true</bool> </property>
</property> <property name="text">
</widget> <string>Start Manual Calibration</string>
</item> </property>
<item> <property name="checkable">
<spacer name="horizontalSpacer_9"> <bool>true</bool>
<property name="orientation"> </property>
<enum>Qt::Horizontal</enum> </widget>
</property> </item>
<property name="sizeHint" stdset="0"> <item>
<size> <spacer name="horizontalSpacer_9">
<width>40</width> <property name="orientation">
<height>20</height> <enum>Qt::Horizontal</enum>
</size> </property>
</property> <property name="sizeHint" stdset="0">
</spacer> <size>
</item> <width>40</width>
</layout> <height>20</height>
</widget> </size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_4">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="title">
<string>Receiver Activity</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_9">
<item>
<widget class="QLabel" name="receiverActivityStatus">
<property name="enabled">
<bool>true</bool>
</property>
<property name="minimumSize">
<size>
<width>300</width>
<height>30</height>
</size>
</property>
<property name="toolTip">
<string>Show receiver activity, input and channel
while moving one stick or switch at once.</string>
</property>
<property name="styleSheet">
<string notr="true">border: 1px solid grey;
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>No activity</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item> </item>
</layout> </layout>
</widget> </widget>

View File

@ -146,6 +146,9 @@ void InputChannelForm::groupUpdated()
case ManualControlSettings::CHANNELGROUPS_OPLINK: case ManualControlSettings::CHANNELGROUPS_OPLINK:
count = 8; // Need to make this 6 for CC count = 8; // Need to make this 6 for CC
break; break;
case ManualControlSettings::CHANNELGROUPS_IBUS:
count = 10;
break;
case ManualControlSettings::CHANNELGROUPS_DSMMAINPORT: case ManualControlSettings::CHANNELGROUPS_DSMMAINPORT:
case ManualControlSettings::CHANNELGROUPS_DSMFLEXIPORT: case ManualControlSettings::CHANNELGROUPS_DSMFLEXIPORT:
case ManualControlSettings::CHANNELGROUPS_DSMRCVRPORT: case ManualControlSettings::CHANNELGROUPS_DSMRCVRPORT:

View File

@ -213,6 +213,9 @@ void ConnectionDiagram::setupGraphicsScene()
case VehicleConfigurationSource::INPUT_EXBUS: case VehicleConfigurationSource::INPUT_EXBUS:
elementsToShow << QString("%1exbus").arg(prefix); elementsToShow << QString("%1exbus").arg(prefix);
break; break;
case VehicleConfigurationSource::INPUT_IBUS:
elementsToShow << QString("%1ibus").arg(prefix);
break;
default: default:
break; break;
} }

View File

@ -46,6 +46,7 @@ void AirSpeedPage::initializePage(VehicleConfigurationSource *settings)
settings->getInputType() == VehicleConfigurationSource::INPUT_DSM || settings->getInputType() == VehicleConfigurationSource::INPUT_DSM ||
settings->getInputType() == VehicleConfigurationSource::INPUT_SRXL || settings->getInputType() == VehicleConfigurationSource::INPUT_SRXL ||
settings->getInputType() == VehicleConfigurationSource::INPUT_HOTT_SUMD || settings->getInputType() == VehicleConfigurationSource::INPUT_HOTT_SUMD ||
settings->getInputType() == VehicleConfigurationSource::INPUT_IBUS ||
settings->getInputType() == VehicleConfigurationSource::INPUT_EXBUS)) || settings->getInputType() == VehicleConfigurationSource::INPUT_EXBUS)) ||
settings->getGpsType() == VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG) { settings->getGpsType() == VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG) {
// Disable non estimated sensors if ports are taken by receivers or I2C Mag // Disable non estimated sensors if ports are taken by receivers or I2C Mag

View File

@ -46,6 +46,7 @@ void GpsPage::initializePage(VehicleConfigurationSource *settings)
settings->getInputType() == VehicleConfigurationSource::INPUT_DSM || settings->getInputType() == VehicleConfigurationSource::INPUT_DSM ||
settings->getInputType() == VehicleConfigurationSource::INPUT_SRXL || settings->getInputType() == VehicleConfigurationSource::INPUT_SRXL ||
settings->getInputType() == VehicleConfigurationSource::INPUT_HOTT_SUMD || settings->getInputType() == VehicleConfigurationSource::INPUT_HOTT_SUMD ||
settings->getInputType() == VehicleConfigurationSource::INPUT_IBUS ||
settings->getInputType() == VehicleConfigurationSource::INPUT_EXBUS)) { settings->getInputType() == VehicleConfigurationSource::INPUT_EXBUS)) {
// Disable GPS+I2C Mag // Disable GPS+I2C Mag
setItemDisabled(VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG, true); setItemDisabled(VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG, true);

View File

@ -69,6 +69,8 @@ bool InputPage::validatePage()
getWizard()->setInputType(SetupWizard::INPUT_HOTT_SUMD); getWizard()->setInputType(SetupWizard::INPUT_HOTT_SUMD);
} else if (ui->jetiButton->isChecked()) { } else if (ui->jetiButton->isChecked()) {
getWizard()->setInputType(SetupWizard::INPUT_EXBUS); getWizard()->setInputType(SetupWizard::INPUT_EXBUS);
} else if (ui->flyskyButton->isChecked()) {
getWizard()->setInputType(SetupWizard::INPUT_IBUS);
} else if (ui->spectrumButton->isChecked()) { } else if (ui->spectrumButton->isChecked()) {
getWizard()->setInputType(SetupWizard::INPUT_DSM); getWizard()->setInputType(SetupWizard::INPUT_DSM);
} else if (ui->multiplexButton->isChecked()) { } else if (ui->multiplexButton->isChecked()) {
@ -112,6 +114,9 @@ bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedTyp
case VehicleConfigurationSource::INPUT_EXBUS: case VehicleConfigurationSource::INPUT_EXBUS:
return data.CC_FlexiPort != HwSettings::CC_FLEXIPORT_EXBUS; return data.CC_FlexiPort != HwSettings::CC_FLEXIPORT_EXBUS;
case VehicleConfigurationSource::INPUT_IBUS:
return data.CC_FlexiPort != HwSettings::CC_FLEXIPORT_IBUS;
case VehicleConfigurationSource::INPUT_DSM: case VehicleConfigurationSource::INPUT_DSM:
// TODO: Handle all of the DSM types ?? Which is most common? // TODO: Handle all of the DSM types ?? Which is most common?
return data.CC_MainPort != HwSettings::CC_MAINPORT_DSM; return data.CC_MainPort != HwSettings::CC_MAINPORT_DSM;
@ -140,6 +145,9 @@ bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedTyp
case VehicleConfigurationSource::INPUT_EXBUS: case VehicleConfigurationSource::INPUT_EXBUS:
return data.RM_FlexiPort != HwSettings::RM_FLEXIPORT_EXBUS; return data.RM_FlexiPort != HwSettings::RM_FLEXIPORT_EXBUS;
case VehicleConfigurationSource::INPUT_IBUS:
return data.RM_FlexiPort != HwSettings::RM_FLEXIPORT_IBUS;
case VehicleConfigurationSource::INPUT_SRXL: case VehicleConfigurationSource::INPUT_SRXL:
return data.RM_FlexiPort != HwSettings::RM_FLEXIPORT_SRXL; return data.RM_FlexiPort != HwSettings::RM_FLEXIPORT_SRXL;
@ -173,6 +181,9 @@ bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedTyp
case VehicleConfigurationSource::INPUT_EXBUS: case VehicleConfigurationSource::INPUT_EXBUS:
return data.SPK2_RcvrPort != HwSettings::SPK2_RCVRPORT_EXBUS; return data.SPK2_RcvrPort != HwSettings::SPK2_RCVRPORT_EXBUS;
case VehicleConfigurationSource::INPUT_IBUS:
return data.SPK2_RcvrPort != HwSettings::SPK2_RCVRPORT_IBUS;
default: return true; default: return true;
} }
break; break;

View File

@ -139,13 +139,6 @@ p, li { white-space: pre-wrap; }
</property> </property>
</widget> </widget>
</item> </item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>2</number>
</property>
<item> <item>
<widget class="QToolButton" name="sbusButton"> <widget class="QToolButton" name="sbusButton">
<property name="font"> <property name="font">
@ -187,6 +180,13 @@ p, li { white-space: pre-wrap; }
</property> </property>
</widget> </widget>
</item> </item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>2</number>
</property>
<item> <item>
<widget class="QToolButton" name="spectrumButton"> <widget class="QToolButton" name="spectrumButton">
<property name="font"> <property name="font">
@ -351,6 +351,47 @@ p, li { white-space: pre-wrap; }
</property> </property>
</widget> </widget>
</item> </item>
<item>
<widget class="QToolButton" name="flyskyButton">
<property name="font">
<font>
<pointsize>10</pointsize>
</font>
</property>
<property name="toolTip">
<string>FlySky IBus</string>
</property>
<property name="styleSheet">
<string notr="true">QToolButton { border: none }</string>
</property>
<property name="text">
<string>IBus</string>
</property>
<property name="icon">
<iconset resource="../wizardResources.qrc">
<normaloff>:/setupwizard/resources/bttn-ibus-up.png</normaloff>
<normalon>:/setupwizard/resources/bttn-ibus-down.png</normalon>:/setupwizard/resources/bttn-ibus-up.png</iconset>
</property>
<property name="iconSize">
<size>
<width>100</width>
<height>100</height>
</size>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="autoExclusive">
<bool>true</bool>
</property>
<property name="toolButtonStyle">
<enum>Qt::ToolButtonTextUnderIcon</enum>
</property>
<property name="autoRaise">
<bool>true</bool>
</property>
</widget>
</item>
</layout> </layout>
</item> </item>
</layout> </layout>

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.1 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.7 KiB

View File

@ -36,7 +36,7 @@
inkscape:window-x="0" inkscape:window-x="0"
inkscape:window-y="27" inkscape:window-y="27"
inkscape:window-maximized="1" inkscape:window-maximized="1"
inkscape:current-layer="layer81" inkscape:current-layer="layer79"
fit-margin-top="15" fit-margin-top="15"
fit-margin-left="15" fit-margin-left="15"
fit-margin-right="15" fit-margin-right="15"
@ -19218,6 +19218,46 @@
y1="431.8125" y1="431.8125"
x2="276" x2="276"
y2="513.56134" /> y2="513.56134" />
<linearGradient
inkscape:collect="always"
xlink:href="#linearGradient6587-8-2-7"
id="linearGradient16665"
gradientUnits="userSpaceOnUse"
gradientTransform="translate(-172.71554,-1032.0795)"
x1="1250"
y1="1450"
x2="1490"
y2="1450" />
<linearGradient
inkscape:collect="always"
xlink:href="#linearGradient6587-8-2-7"
id="linearGradient17268"
gradientUnits="userSpaceOnUse"
gradientTransform="translate(-151.00134,-881.62884)"
x1="1250"
y1="1450"
x2="1490"
y2="1450" />
<linearGradient
inkscape:collect="always"
xlink:href="#linearGradient6587-8-2-7"
id="linearGradient17425"
gradientUnits="userSpaceOnUse"
gradientTransform="translate(-151.00134,-881.62884)"
x1="1250"
y1="1450"
x2="1490"
y2="1450" />
<linearGradient
inkscape:collect="always"
xlink:href="#linearGradient6587-8-2-7"
id="linearGradient17568"
gradientUnits="userSpaceOnUse"
gradientTransform="translate(-151.00134,-881.62884)"
x1="1250"
y1="1450"
x2="1490"
y2="1450" />
</defs> </defs>
<metadata <metadata
id="metadata12656"> id="metadata12656">
@ -20041,6 +20081,115 @@
</g> </g>
</g> </g>
</g> </g>
<g
inkscape:groupmode="layer"
id="layer93"
inkscape:label="cc-ibus"
style="display:none"
sodipodi:insensitive="true">
<g
style="display:inline"
id="cc-ibus"
transform="matrix(0,0.4,-0.4,0,931.4684,-115.45414)">
<path
id="path9857-8-8-1-1-4-0-9-91"
d="M 1430.6302,1592 C 1424.6602,1656.9 1487.6898,1787.8293 1662.8577,1689.9523"
stroke-miterlimit="4"
inkscape:connector-curvature="0"
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
sodipodi:nodetypes="cc" />
<path
sodipodi:nodetypes="ccc"
style="fill:none;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1392.571,1323.8556 L 1392.571,1037.0524 L 1109.0353,1037.0524"
id="path8856-5-1-7-1-9-5-4-3-7-0-7-7" />
<path
sodipodi:nodetypes="ccc"
style="fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1362.571,1323.8556 L 1362.5703,1071.9612 L 1109.0353,1072.1435"
id="path8856-1-2-1-9-0-9-7-4-7" />
<path
sodipodi:nodetypes="ccc"
style="fill:none;stroke:#000000;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1347.571,1323.8556 L 1347.571,1087.0524 L 1109.0353,1087.0524"
id="path8856-1-5-7-7-2-9-3-2-3-1" />
<path
sodipodi:nodetypes="cc"
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
stroke-miterlimit="4"
d="M 1308.744,1592 C 1314.714,1656.9 1251.6844,1787.8293 1076.5165,1689.9523"
id="path21749-5-7-5-15" />
<rect
rx="11.5"
id="rect8853-6-8-6-6-4-6-7-97"
style="color:#000000;fill:url(#linearGradient17568);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
ry="11.5"
height="272"
width="237"
stroke-miterlimit="4"
y="1320"
x="1250" />
<g
transform="matrix(0,1,-1,0,2674.3512,108.4981)"
style="display:inline"
id="g17270-0">
<g
id="text17069-3-8"
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:41.27642822px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;fill:#fdfdfd;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
transform="scale(-1,-1)">
<path
inkscape:connector-curvature="0"
id="path17087-6-8"
d="M -1412.1475,-1323.0706 L -1412.1475,-1352.6171 L -1391.8922,-1352.6171 L -1391.8922,-1347.6187 L -1406.1817,-1347.6187 L -1406.1817,-1340.6251 L -1393.8472,-1340.6251 L -1393.8472,-1335.6268 L -1406.1817,-1335.6268 L -1406.1817,-1323.0706 L -1412.1475,-1323.0706 Z" />
<path
inkscape:connector-curvature="0"
id="path17089-1-5"
d="M -1386.9946,-1323.0706 L -1386.9946,-1352.6171 L -1381.3312,-1352.6171 L -1381.3312,-1323.0706 L -1386.9946,-1323.0706 Z" />
<path
inkscape:connector-curvature="0"
id="path17091-2-0"
d="M -1378.2274,-1344.4746 L -1372.2012,-1344.4746 L -1367.082,-1329.2781 L -1362.0837,-1344.4746 L -1356.2187,-1344.4746 L -1363.7767,-1323.8767 L -1365.127,-1320.1482 Q -1365.8727,-1318.2738 -1366.558,-1317.2862 Q -1367.2231,-1316.2986 -1368.1099,-1315.694 Q -1368.9765,-1315.0692 -1370.2664,-1314.7266 Q -1371.5361,-1314.384 -1373.1485,-1314.384 Q -1374.781,-1314.384 -1376.3531,-1314.7266 L -1376.8569,-1319.1606 Q -1375.5267,-1318.8986 -1374.4585,-1318.8986 Q -1372.4834,-1318.8986 -1371.5361,-1320.0675 Q -1370.5889,-1321.2163 -1370.085,-1323.0101 L -1378.2274,-1344.4746 Z" />
<path
inkscape:connector-curvature="0"
id="path17093-9-9"
d="M -1354.2033,-1332.6843 L -1348.3988,-1333.2486 Q -1347.8747,-1330.3262 -1346.2825,-1328.9557 Q -1344.6702,-1327.5852 -1341.9493,-1327.5852 Q -1339.0672,-1327.5852 -1337.6161,-1328.7944 Q -1336.1448,-1330.0239 -1336.1448,-1331.6564 Q -1336.1448,-1332.7044 -1336.7696,-1333.43 Q -1337.3742,-1334.1757 -1338.906,-1334.7199 Q -1339.954,-1335.0826 -1343.6826,-1336.0097 Q -1348.4794,-1337.1989 -1350.4142,-1338.9322 Q -1353.1351,-1341.3708 -1353.1351,-1344.8777 Q -1353.1351,-1347.135 -1351.8653,-1349.09 Q -1350.5755,-1351.0652 -1348.1771,-1352.093 Q -1345.7585,-1353.1209 -1342.3524,-1353.1209 Q -1336.7898,-1353.1209 -1333.9883,-1350.6822 Q -1331.1667,-1348.2435 -1331.0256,-1344.1723 L -1336.9913,-1343.9103 Q -1337.3742,-1346.1878 -1338.644,-1347.1753 Q -1339.8936,-1348.1831 -1342.4129,-1348.1831 Q -1345.0128,-1348.1831 -1346.4841,-1347.1149 Q -1347.4313,-1346.4296 -1347.4313,-1345.2808 Q -1347.4313,-1344.2328 -1346.5445,-1343.4871 Q -1345.4159,-1342.5398 -1341.0625,-1341.5119 Q -1336.7091,-1340.484 -1334.6332,-1339.3756 Q -1332.5372,-1338.2872 -1331.3682,-1336.3725 Q -1330.1791,-1334.478 -1330.1791,-1331.6765 Q -1330.1791,-1329.1371 -1331.5899,-1326.9201 Q -1333.0007,-1324.7031 -1335.5805,-1323.6147 Q -1338.1603,-1322.5465 -1342.0098,-1322.5465 Q -1347.6127,-1322.5465 -1350.6158,-1325.1263 Q -1353.6188,-1327.7262 -1354.2033,-1332.6843 Z" />
<path
inkscape:connector-curvature="0"
id="path17095-3-63"
d="M -1325.3622,-1323.0706 L -1325.3622,-1352.6171 L -1319.6987,-1352.6171 L -1319.6987,-1336.9369 L -1313.0679,-1344.4746 L -1306.0945,-1344.4746 L -1313.4105,-1336.6547 L -1305.5704,-1323.0706 L -1311.6773,-1323.0706 L -1317.0585,-1332.6843 L -1319.6987,-1329.9231 L -1319.6987,-1323.0706 L -1325.3622,-1323.0706 Z" />
<path
inkscape:connector-curvature="0"
id="path17097-1-8"
d="M -1304.865,-1344.4746 L -1298.8388,-1344.4746 L -1293.7196,-1329.2781 L -1288.7213,-1344.4746 L -1282.8563,-1344.4746 L -1290.4143,-1323.8767 L -1291.7646,-1320.1482 Q -1292.5103,-1318.2738 -1293.1956,-1317.2862 Q -1293.8607,-1316.2986 -1294.7475,-1315.694 Q -1295.6141,-1315.0692 -1296.904,-1314.7266 Q -1298.1737,-1314.384 -1299.7861,-1314.384 Q -1301.4186,-1314.384 -1302.9907,-1314.7266 L -1303.4945,-1319.1606 Q -1302.1643,-1318.8986 -1301.0961,-1318.8986 Q -1299.121,-1318.8986 -1298.1737,-1320.0675 Q -1297.2265,-1321.2163 -1296.7226,-1323.0101 L -1304.865,-1344.4746 Z" />
</g>
<g
id="text17073-9-5"
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:56.25px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;fill:#fdfdfd;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
transform="scale(-1,-1)">
<path
inkscape:connector-curvature="0"
id="path17078-4-61"
d="M -1402.5568,-1259.2407 L -1402.5568,-1299.5056 L -1394.4269,-1299.5056 L -1394.4269,-1259.2407 L -1402.5568,-1259.2407 Z" />
<path
inkscape:connector-curvature="0"
id="path17080-7-15"
d="M -1386.6815,-1299.5056 L -1370.5865,-1299.5056 Q -1365.8075,-1299.5056 -1363.4729,-1299.0936 Q -1361.1108,-1298.7091 -1359.2706,-1297.4457 Q -1357.403,-1296.1823 -1356.167,-1294.0674 Q -1354.931,-1291.98 -1354.931,-1289.3707 Q -1354.931,-1286.5417 -1356.4691,-1284.1797 Q -1357.9797,-1281.8176 -1360.589,-1280.6366 Q -1356.9086,-1279.5654 -1354.931,-1276.9836 Q -1352.9535,-1274.4019 -1352.9535,-1270.9137 Q -1352.9535,-1268.1671 -1354.2444,-1265.5579 Q -1355.5078,-1262.9761 -1357.7325,-1261.4105 Q -1359.9298,-1259.8724 -1363.1708,-1259.5154 Q -1365.2032,-1259.2957 -1372.9761,-1259.2407 L -1386.6815,-1259.2407 L -1386.6815,-1299.5056 Z M -1378.5516,-1292.804 L -1378.5516,-1283.493 L -1373.2233,-1283.493 Q -1368.4717,-1283.493 -1367.3181,-1283.6304 Q -1365.2307,-1283.8776 -1364.0497,-1285.0586 Q -1362.8412,-1286.2671 -1362.8412,-1288.2172 Q -1362.8412,-1290.0848 -1363.8849,-1291.2384 Q -1364.9011,-1292.4194 -1366.9336,-1292.6666 Q -1368.1421,-1292.804 -1373.8824,-1292.804 L -1378.5516,-1292.804 Z M -1378.5516,-1276.7914 L -1378.5516,-1266.0248 L -1371.026,-1266.0248 Q -1366.6315,-1266.0248 -1365.4504,-1266.272 Q -1363.6377,-1266.6016 -1362.5116,-1267.865 Q -1361.358,-1269.1559 -1361.358,-1271.2982 Q -1361.358,-1273.111 -1362.2369,-1274.3744 Q -1363.1158,-1275.6378 -1364.7913,-1276.2146 Q -1366.4392,-1276.7914 -1371.9873,-1276.7914 L -1378.5516,-1276.7914 Z" />
<path
inkscape:connector-curvature="0"
id="path17082-8-9"
d="M -1326.9159,-1259.2407 L -1326.9159,-1263.6078 Q -1328.5089,-1261.2732 -1331.1182,-1259.9274 Q -1333.7,-1258.5815 -1336.5839,-1258.5815 Q -1339.5227,-1258.5815 -1341.8573,-1259.8724 Q -1344.1919,-1261.1633 -1345.2356,-1263.4979 Q -1346.2793,-1265.8325 -1346.2793,-1269.9524 L -1346.2793,-1288.4094 L -1338.5614,-1288.4094 L -1338.5614,-1275.0061 Q -1338.5614,-1268.8538 -1338.1494,-1267.453 Q -1337.71,-1266.0797 -1336.5839,-1265.2557 Q -1335.4578,-1264.4592 -1333.7274,-1264.4592 Q -1331.7499,-1264.4592 -1330.1843,-1265.5304 Q -1328.6188,-1266.629 -1328.042,-1268.222 Q -1327.4652,-1269.8425 -1327.4652,-1276.1047 L -1327.4652,-1288.4094 L -1319.7473,-1288.4094 L -1319.7473,-1259.2407 L -1326.9159,-1259.2407 Z" />
<path
inkscape:connector-curvature="0"
id="path17084-4-8"
d="M -1314.4464,-1267.5629 L -1306.701,-1268.7439 Q -1306.2067,-1266.4917 -1304.696,-1265.3107 Q -1303.1854,-1264.1571 -1300.4663,-1264.1571 Q -1297.4725,-1264.1571 -1295.9619,-1265.2557 Q -1294.9457,-1266.0248 -1294.9457,-1267.3157 Q -1294.9457,-1268.1946 -1295.495,-1268.7714 Q -1296.0718,-1269.3207 -1298.0768,-1269.7876 Q -1307.4152,-1271.8475 -1309.9146,-1273.5504 Q -1313.3752,-1275.9125 -1313.3752,-1280.1147 Q -1313.3752,-1283.905 -1310.3815,-1286.4868 Q -1307.3877,-1289.0686 -1301.098,-1289.0686 Q -1295.1105,-1289.0686 -1292.1991,-1287.1185 Q -1289.2877,-1285.1685 -1288.1891,-1281.3507 L -1295.4675,-1280.0049 Q -1295.9344,-1281.7078 -1297.2528,-1282.6141 Q -1298.5437,-1283.5205 -1300.9607,-1283.5205 Q -1304.0094,-1283.5205 -1305.3278,-1282.6691 Q -1306.2067,-1282.0648 -1306.2067,-1281.1035 Q -1306.2067,-1280.2795 -1305.4376,-1279.7028 Q -1304.3939,-1278.9337 -1298.2416,-1277.533 Q -1292.0618,-1276.1322 -1289.6173,-1274.0997 Q -1287.2003,-1272.0398 -1287.2003,-1268.3594 Q -1287.2003,-1264.3494 -1290.5511,-1261.4655 Q -1293.902,-1258.5815 -1300.4663,-1258.5815 Q -1306.4264,-1258.5815 -1309.9146,-1260.9985 Q -1313.3752,-1263.4155 -1314.4464,-1267.5629 Z" />
</g>
</g>
</g>
</g>
<g <g
inkscape:groupmode="layer" inkscape:groupmode="layer"
id="layer61" id="layer61"
@ -21044,6 +21193,115 @@
</g> </g>
</g> </g>
</g> </g>
<g
inkscape:groupmode="layer"
id="layer92"
inkscape:label="revo-ibus"
sodipodi:insensitive="true"
style="display:none">
<g
style="display:inline"
id="revo-ibus"
transform="matrix(0,0.4,-0.4,0,929.4684,-117.45414)">
<path
id="path9857-8-8-1-1-4-0-9-3-6"
d="M 1430.6302,1592 C 1424.6602,1656.9 1487.6898,1787.8293 1662.8577,1689.9523"
stroke-miterlimit="4"
inkscape:connector-curvature="0"
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
sodipodi:nodetypes="cc" />
<path
sodipodi:nodetypes="ccc"
style="fill:none;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1392.571,1323.8556 L 1392.571,1037.0524 L 1104.0353,1037.0524"
id="path8856-5-1-7-1-9-5-4-3-7-0-7-0-8" />
<path
sodipodi:nodetypes="ccc"
style="fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1362.571,1323.8556 L 1362.5703,1071.9612 L 1104.0353,1072.1435"
id="path8856-1-2-1-9-0-9-7-4-5-8" />
<path
sodipodi:nodetypes="ccc"
style="fill:none;stroke:#000000;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1347.571,1323.8556 L 1347.571,1087.0524 L 1104.0353,1087.0524"
id="path8856-1-5-7-7-2-9-3-2-3-5-4" />
<path
sodipodi:nodetypes="cc"
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
stroke-miterlimit="4"
d="M 1308.744,1592 C 1314.714,1656.9 1251.6844,1787.8293 1076.5165,1689.9523"
id="path21749-5-7-5-1-3" />
<rect
rx="11.5"
id="rect8853-6-8-6-6-4-6-7-9-14"
style="color:#000000;fill:url(#linearGradient17425);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
ry="11.5"
height="272"
width="237"
stroke-miterlimit="4"
y="1320"
x="1250" />
<g
transform="matrix(0,1,-1,0,2674.3512,108.4981)"
style="display:inline"
id="g17270-1">
<g
id="text17069-3-7"
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:41.27642822px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;fill:#fdfdfd;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
transform="scale(-1,-1)">
<path
inkscape:connector-curvature="0"
id="path17087-6-2"
d="M -1412.1475,-1323.0706 L -1412.1475,-1352.6171 L -1391.8922,-1352.6171 L -1391.8922,-1347.6187 L -1406.1817,-1347.6187 L -1406.1817,-1340.6251 L -1393.8472,-1340.6251 L -1393.8472,-1335.6268 L -1406.1817,-1335.6268 L -1406.1817,-1323.0706 L -1412.1475,-1323.0706 Z" />
<path
inkscape:connector-curvature="0"
id="path17089-1-7"
d="M -1386.9946,-1323.0706 L -1386.9946,-1352.6171 L -1381.3312,-1352.6171 L -1381.3312,-1323.0706 L -1386.9946,-1323.0706 Z" />
<path
inkscape:connector-curvature="0"
id="path17091-2-2"
d="M -1378.2274,-1344.4746 L -1372.2012,-1344.4746 L -1367.082,-1329.2781 L -1362.0837,-1344.4746 L -1356.2187,-1344.4746 L -1363.7767,-1323.8767 L -1365.127,-1320.1482 Q -1365.8727,-1318.2738 -1366.558,-1317.2862 Q -1367.2231,-1316.2986 -1368.1099,-1315.694 Q -1368.9765,-1315.0692 -1370.2664,-1314.7266 Q -1371.5361,-1314.384 -1373.1485,-1314.384 Q -1374.781,-1314.384 -1376.3531,-1314.7266 L -1376.8569,-1319.1606 Q -1375.5267,-1318.8986 -1374.4585,-1318.8986 Q -1372.4834,-1318.8986 -1371.5361,-1320.0675 Q -1370.5889,-1321.2163 -1370.085,-1323.0101 L -1378.2274,-1344.4746 Z" />
<path
inkscape:connector-curvature="0"
id="path17093-9-2"
d="M -1354.2033,-1332.6843 L -1348.3988,-1333.2486 Q -1347.8747,-1330.3262 -1346.2825,-1328.9557 Q -1344.6702,-1327.5852 -1341.9493,-1327.5852 Q -1339.0672,-1327.5852 -1337.6161,-1328.7944 Q -1336.1448,-1330.0239 -1336.1448,-1331.6564 Q -1336.1448,-1332.7044 -1336.7696,-1333.43 Q -1337.3742,-1334.1757 -1338.906,-1334.7199 Q -1339.954,-1335.0826 -1343.6826,-1336.0097 Q -1348.4794,-1337.1989 -1350.4142,-1338.9322 Q -1353.1351,-1341.3708 -1353.1351,-1344.8777 Q -1353.1351,-1347.135 -1351.8653,-1349.09 Q -1350.5755,-1351.0652 -1348.1771,-1352.093 Q -1345.7585,-1353.1209 -1342.3524,-1353.1209 Q -1336.7898,-1353.1209 -1333.9883,-1350.6822 Q -1331.1667,-1348.2435 -1331.0256,-1344.1723 L -1336.9913,-1343.9103 Q -1337.3742,-1346.1878 -1338.644,-1347.1753 Q -1339.8936,-1348.1831 -1342.4129,-1348.1831 Q -1345.0128,-1348.1831 -1346.4841,-1347.1149 Q -1347.4313,-1346.4296 -1347.4313,-1345.2808 Q -1347.4313,-1344.2328 -1346.5445,-1343.4871 Q -1345.4159,-1342.5398 -1341.0625,-1341.5119 Q -1336.7091,-1340.484 -1334.6332,-1339.3756 Q -1332.5372,-1338.2872 -1331.3682,-1336.3725 Q -1330.1791,-1334.478 -1330.1791,-1331.6765 Q -1330.1791,-1329.1371 -1331.5899,-1326.9201 Q -1333.0007,-1324.7031 -1335.5805,-1323.6147 Q -1338.1603,-1322.5465 -1342.0098,-1322.5465 Q -1347.6127,-1322.5465 -1350.6158,-1325.1263 Q -1353.6188,-1327.7262 -1354.2033,-1332.6843 Z" />
<path
inkscape:connector-curvature="0"
id="path17095-3-6"
d="M -1325.3622,-1323.0706 L -1325.3622,-1352.6171 L -1319.6987,-1352.6171 L -1319.6987,-1336.9369 L -1313.0679,-1344.4746 L -1306.0945,-1344.4746 L -1313.4105,-1336.6547 L -1305.5704,-1323.0706 L -1311.6773,-1323.0706 L -1317.0585,-1332.6843 L -1319.6987,-1329.9231 L -1319.6987,-1323.0706 L -1325.3622,-1323.0706 Z" />
<path
inkscape:connector-curvature="0"
id="path17097-1-1"
d="M -1304.865,-1344.4746 L -1298.8388,-1344.4746 L -1293.7196,-1329.2781 L -1288.7213,-1344.4746 L -1282.8563,-1344.4746 L -1290.4143,-1323.8767 L -1291.7646,-1320.1482 Q -1292.5103,-1318.2738 -1293.1956,-1317.2862 Q -1293.8607,-1316.2986 -1294.7475,-1315.694 Q -1295.6141,-1315.0692 -1296.904,-1314.7266 Q -1298.1737,-1314.384 -1299.7861,-1314.384 Q -1301.4186,-1314.384 -1302.9907,-1314.7266 L -1303.4945,-1319.1606 Q -1302.1643,-1318.8986 -1301.0961,-1318.8986 Q -1299.121,-1318.8986 -1298.1737,-1320.0675 Q -1297.2265,-1321.2163 -1296.7226,-1323.0101 L -1304.865,-1344.4746 Z" />
</g>
<g
id="text17073-9-0"
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:56.25px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;fill:#fdfdfd;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
transform="scale(-1,-1)">
<path
inkscape:connector-curvature="0"
id="path17078-4-6"
d="M -1402.5568,-1259.2407 L -1402.5568,-1299.5056 L -1394.4269,-1299.5056 L -1394.4269,-1259.2407 L -1402.5568,-1259.2407 Z" />
<path
inkscape:connector-curvature="0"
id="path17080-7-1"
d="M -1386.6815,-1299.5056 L -1370.5865,-1299.5056 Q -1365.8075,-1299.5056 -1363.4729,-1299.0936 Q -1361.1108,-1298.7091 -1359.2706,-1297.4457 Q -1357.403,-1296.1823 -1356.167,-1294.0674 Q -1354.931,-1291.98 -1354.931,-1289.3707 Q -1354.931,-1286.5417 -1356.4691,-1284.1797 Q -1357.9797,-1281.8176 -1360.589,-1280.6366 Q -1356.9086,-1279.5654 -1354.931,-1276.9836 Q -1352.9535,-1274.4019 -1352.9535,-1270.9137 Q -1352.9535,-1268.1671 -1354.2444,-1265.5579 Q -1355.5078,-1262.9761 -1357.7325,-1261.4105 Q -1359.9298,-1259.8724 -1363.1708,-1259.5154 Q -1365.2032,-1259.2957 -1372.9761,-1259.2407 L -1386.6815,-1259.2407 L -1386.6815,-1299.5056 Z M -1378.5516,-1292.804 L -1378.5516,-1283.493 L -1373.2233,-1283.493 Q -1368.4717,-1283.493 -1367.3181,-1283.6304 Q -1365.2307,-1283.8776 -1364.0497,-1285.0586 Q -1362.8412,-1286.2671 -1362.8412,-1288.2172 Q -1362.8412,-1290.0848 -1363.8849,-1291.2384 Q -1364.9011,-1292.4194 -1366.9336,-1292.6666 Q -1368.1421,-1292.804 -1373.8824,-1292.804 L -1378.5516,-1292.804 Z M -1378.5516,-1276.7914 L -1378.5516,-1266.0248 L -1371.026,-1266.0248 Q -1366.6315,-1266.0248 -1365.4504,-1266.272 Q -1363.6377,-1266.6016 -1362.5116,-1267.865 Q -1361.358,-1269.1559 -1361.358,-1271.2982 Q -1361.358,-1273.111 -1362.2369,-1274.3744 Q -1363.1158,-1275.6378 -1364.7913,-1276.2146 Q -1366.4392,-1276.7914 -1371.9873,-1276.7914 L -1378.5516,-1276.7914 Z" />
<path
inkscape:connector-curvature="0"
id="path17082-8-5"
d="M -1326.9159,-1259.2407 L -1326.9159,-1263.6078 Q -1328.5089,-1261.2732 -1331.1182,-1259.9274 Q -1333.7,-1258.5815 -1336.5839,-1258.5815 Q -1339.5227,-1258.5815 -1341.8573,-1259.8724 Q -1344.1919,-1261.1633 -1345.2356,-1263.4979 Q -1346.2793,-1265.8325 -1346.2793,-1269.9524 L -1346.2793,-1288.4094 L -1338.5614,-1288.4094 L -1338.5614,-1275.0061 Q -1338.5614,-1268.8538 -1338.1494,-1267.453 Q -1337.71,-1266.0797 -1336.5839,-1265.2557 Q -1335.4578,-1264.4592 -1333.7274,-1264.4592 Q -1331.7499,-1264.4592 -1330.1843,-1265.5304 Q -1328.6188,-1266.629 -1328.042,-1268.222 Q -1327.4652,-1269.8425 -1327.4652,-1276.1047 L -1327.4652,-1288.4094 L -1319.7473,-1288.4094 L -1319.7473,-1259.2407 L -1326.9159,-1259.2407 Z" />
<path
inkscape:connector-curvature="0"
id="path17084-4-9"
d="M -1314.4464,-1267.5629 L -1306.701,-1268.7439 Q -1306.2067,-1266.4917 -1304.696,-1265.3107 Q -1303.1854,-1264.1571 -1300.4663,-1264.1571 Q -1297.4725,-1264.1571 -1295.9619,-1265.2557 Q -1294.9457,-1266.0248 -1294.9457,-1267.3157 Q -1294.9457,-1268.1946 -1295.495,-1268.7714 Q -1296.0718,-1269.3207 -1298.0768,-1269.7876 Q -1307.4152,-1271.8475 -1309.9146,-1273.5504 Q -1313.3752,-1275.9125 -1313.3752,-1280.1147 Q -1313.3752,-1283.905 -1310.3815,-1286.4868 Q -1307.3877,-1289.0686 -1301.098,-1289.0686 Q -1295.1105,-1289.0686 -1292.1991,-1287.1185 Q -1289.2877,-1285.1685 -1288.1891,-1281.3507 L -1295.4675,-1280.0049 Q -1295.9344,-1281.7078 -1297.2528,-1282.6141 Q -1298.5437,-1283.5205 -1300.9607,-1283.5205 Q -1304.0094,-1283.5205 -1305.3278,-1282.6691 Q -1306.2067,-1282.0648 -1306.2067,-1281.1035 Q -1306.2067,-1280.2795 -1305.4376,-1279.7028 Q -1304.3939,-1278.9337 -1298.2416,-1277.533 Q -1292.0618,-1276.1322 -1289.6173,-1274.0997 Q -1287.2003,-1272.0398 -1287.2003,-1268.3594 Q -1287.2003,-1264.3494 -1290.5511,-1261.4655 Q -1293.902,-1258.5815 -1300.4663,-1258.5815 Q -1306.4264,-1258.5815 -1309.9146,-1260.9985 Q -1313.3752,-1263.4155 -1314.4464,-1267.5629 Z" />
</g>
</g>
</g>
</g>
<g <g
inkscape:groupmode="layer" inkscape:groupmode="layer"
id="layer21" id="layer21"
@ -21828,6 +22086,115 @@
</g> </g>
</g> </g>
</g> </g>
<g
inkscape:groupmode="layer"
id="layer91"
inkscape:label="nano-ibus"
style="display:none"
sodipodi:insensitive="true">
<g
style="display:inline"
id="nano-ibus"
transform="matrix(-0.4,0,0,-0.4,1078.3424,590.20822)">
<path
id="path9857-8-8-1-1-4-0-9-3-2-61"
d="M 1430.6302,1592 C 1424.6602,1656.9 1487.6898,1787.8293 1662.8577,1689.9523"
stroke-miterlimit="4"
inkscape:connector-curvature="0"
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
sodipodi:nodetypes="cc" />
<path
sodipodi:nodetypes="cc"
style="fill:none;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1392.571,1323.8556 L 1392.571,1152.8337"
id="path8856-5-1-7-1-9-5-4-3-7-0-7-0-6-0" />
<path
sodipodi:nodetypes="cc"
style="fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1362.571,1323.8556 L 1362.571,1152.8347"
id="path8856-1-2-1-9-0-9-7-4-5-2-6" />
<path
sodipodi:nodetypes="cc"
style="fill:none;stroke:#000000;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1347.571,1323.8556 L 1347.571,1152.8347"
id="path8856-1-5-7-7-2-9-3-2-3-5-1-3" />
<path
sodipodi:nodetypes="cc"
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
stroke-miterlimit="4"
d="M 1308.744,1592 C 1314.714,1656.9 1251.6844,1787.8293 1076.5165,1689.9523"
id="path21749-5-7-5-1-7-2" />
<rect
rx="11.5"
id="rect8853-6-8-6-6-4-6-7-9-8-0"
style="color:#000000;fill:url(#linearGradient17268);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
ry="11.5"
height="272"
width="237"
stroke-miterlimit="4"
y="1320"
x="1250" />
<g
transform="translate(20.9981,150.1488)"
style="display:inline"
id="g17270">
<g
id="text17069-3"
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:41.27642822px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;fill:#fdfdfd;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
transform="scale(-1,-1)">
<path
inkscape:connector-curvature="0"
id="path17087-6"
d="M -1412.1475,-1323.0706 L -1412.1475,-1352.6171 L -1391.8922,-1352.6171 L -1391.8922,-1347.6187 L -1406.1817,-1347.6187 L -1406.1817,-1340.6251 L -1393.8472,-1340.6251 L -1393.8472,-1335.6268 L -1406.1817,-1335.6268 L -1406.1817,-1323.0706 L -1412.1475,-1323.0706 Z" />
<path
inkscape:connector-curvature="0"
id="path17089-1"
d="M -1386.9946,-1323.0706 L -1386.9946,-1352.6171 L -1381.3312,-1352.6171 L -1381.3312,-1323.0706 L -1386.9946,-1323.0706 Z" />
<path
inkscape:connector-curvature="0"
id="path17091-2"
d="M -1378.2274,-1344.4746 L -1372.2012,-1344.4746 L -1367.082,-1329.2781 L -1362.0837,-1344.4746 L -1356.2187,-1344.4746 L -1363.7767,-1323.8767 L -1365.127,-1320.1482 Q -1365.8727,-1318.2738 -1366.558,-1317.2862 Q -1367.2231,-1316.2986 -1368.1099,-1315.694 Q -1368.9765,-1315.0692 -1370.2664,-1314.7266 Q -1371.5361,-1314.384 -1373.1485,-1314.384 Q -1374.781,-1314.384 -1376.3531,-1314.7266 L -1376.8569,-1319.1606 Q -1375.5267,-1318.8986 -1374.4585,-1318.8986 Q -1372.4834,-1318.8986 -1371.5361,-1320.0675 Q -1370.5889,-1321.2163 -1370.085,-1323.0101 L -1378.2274,-1344.4746 Z" />
<path
inkscape:connector-curvature="0"
id="path17093-9"
d="M -1354.2033,-1332.6843 L -1348.3988,-1333.2486 Q -1347.8747,-1330.3262 -1346.2825,-1328.9557 Q -1344.6702,-1327.5852 -1341.9493,-1327.5852 Q -1339.0672,-1327.5852 -1337.6161,-1328.7944 Q -1336.1448,-1330.0239 -1336.1448,-1331.6564 Q -1336.1448,-1332.7044 -1336.7696,-1333.43 Q -1337.3742,-1334.1757 -1338.906,-1334.7199 Q -1339.954,-1335.0826 -1343.6826,-1336.0097 Q -1348.4794,-1337.1989 -1350.4142,-1338.9322 Q -1353.1351,-1341.3708 -1353.1351,-1344.8777 Q -1353.1351,-1347.135 -1351.8653,-1349.09 Q -1350.5755,-1351.0652 -1348.1771,-1352.093 Q -1345.7585,-1353.1209 -1342.3524,-1353.1209 Q -1336.7898,-1353.1209 -1333.9883,-1350.6822 Q -1331.1667,-1348.2435 -1331.0256,-1344.1723 L -1336.9913,-1343.9103 Q -1337.3742,-1346.1878 -1338.644,-1347.1753 Q -1339.8936,-1348.1831 -1342.4129,-1348.1831 Q -1345.0128,-1348.1831 -1346.4841,-1347.1149 Q -1347.4313,-1346.4296 -1347.4313,-1345.2808 Q -1347.4313,-1344.2328 -1346.5445,-1343.4871 Q -1345.4159,-1342.5398 -1341.0625,-1341.5119 Q -1336.7091,-1340.484 -1334.6332,-1339.3756 Q -1332.5372,-1338.2872 -1331.3682,-1336.3725 Q -1330.1791,-1334.478 -1330.1791,-1331.6765 Q -1330.1791,-1329.1371 -1331.5899,-1326.9201 Q -1333.0007,-1324.7031 -1335.5805,-1323.6147 Q -1338.1603,-1322.5465 -1342.0098,-1322.5465 Q -1347.6127,-1322.5465 -1350.6158,-1325.1263 Q -1353.6188,-1327.7262 -1354.2033,-1332.6843 Z" />
<path
inkscape:connector-curvature="0"
id="path17095-3"
d="M -1325.3622,-1323.0706 L -1325.3622,-1352.6171 L -1319.6987,-1352.6171 L -1319.6987,-1336.9369 L -1313.0679,-1344.4746 L -1306.0945,-1344.4746 L -1313.4105,-1336.6547 L -1305.5704,-1323.0706 L -1311.6773,-1323.0706 L -1317.0585,-1332.6843 L -1319.6987,-1329.9231 L -1319.6987,-1323.0706 L -1325.3622,-1323.0706 Z" />
<path
inkscape:connector-curvature="0"
id="path17097-1"
d="M -1304.865,-1344.4746 L -1298.8388,-1344.4746 L -1293.7196,-1329.2781 L -1288.7213,-1344.4746 L -1282.8563,-1344.4746 L -1290.4143,-1323.8767 L -1291.7646,-1320.1482 Q -1292.5103,-1318.2738 -1293.1956,-1317.2862 Q -1293.8607,-1316.2986 -1294.7475,-1315.694 Q -1295.6141,-1315.0692 -1296.904,-1314.7266 Q -1298.1737,-1314.384 -1299.7861,-1314.384 Q -1301.4186,-1314.384 -1302.9907,-1314.7266 L -1303.4945,-1319.1606 Q -1302.1643,-1318.8986 -1301.0961,-1318.8986 Q -1299.121,-1318.8986 -1298.1737,-1320.0675 Q -1297.2265,-1321.2163 -1296.7226,-1323.0101 L -1304.865,-1344.4746 Z" />
</g>
<g
id="text17073-9"
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:56.25px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;fill:#fdfdfd;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
transform="scale(-1,-1)">
<path
inkscape:connector-curvature="0"
id="path17078-4"
d="M -1402.5568,-1259.2407 L -1402.5568,-1299.5056 L -1394.4269,-1299.5056 L -1394.4269,-1259.2407 L -1402.5568,-1259.2407 Z" />
<path
inkscape:connector-curvature="0"
id="path17080-7"
d="M -1386.6815,-1299.5056 L -1370.5865,-1299.5056 Q -1365.8075,-1299.5056 -1363.4729,-1299.0936 Q -1361.1108,-1298.7091 -1359.2706,-1297.4457 Q -1357.403,-1296.1823 -1356.167,-1294.0674 Q -1354.931,-1291.98 -1354.931,-1289.3707 Q -1354.931,-1286.5417 -1356.4691,-1284.1797 Q -1357.9797,-1281.8176 -1360.589,-1280.6366 Q -1356.9086,-1279.5654 -1354.931,-1276.9836 Q -1352.9535,-1274.4019 -1352.9535,-1270.9137 Q -1352.9535,-1268.1671 -1354.2444,-1265.5579 Q -1355.5078,-1262.9761 -1357.7325,-1261.4105 Q -1359.9298,-1259.8724 -1363.1708,-1259.5154 Q -1365.2032,-1259.2957 -1372.9761,-1259.2407 L -1386.6815,-1259.2407 L -1386.6815,-1299.5056 Z M -1378.5516,-1292.804 L -1378.5516,-1283.493 L -1373.2233,-1283.493 Q -1368.4717,-1283.493 -1367.3181,-1283.6304 Q -1365.2307,-1283.8776 -1364.0497,-1285.0586 Q -1362.8412,-1286.2671 -1362.8412,-1288.2172 Q -1362.8412,-1290.0848 -1363.8849,-1291.2384 Q -1364.9011,-1292.4194 -1366.9336,-1292.6666 Q -1368.1421,-1292.804 -1373.8824,-1292.804 L -1378.5516,-1292.804 Z M -1378.5516,-1276.7914 L -1378.5516,-1266.0248 L -1371.026,-1266.0248 Q -1366.6315,-1266.0248 -1365.4504,-1266.272 Q -1363.6377,-1266.6016 -1362.5116,-1267.865 Q -1361.358,-1269.1559 -1361.358,-1271.2982 Q -1361.358,-1273.111 -1362.2369,-1274.3744 Q -1363.1158,-1275.6378 -1364.7913,-1276.2146 Q -1366.4392,-1276.7914 -1371.9873,-1276.7914 L -1378.5516,-1276.7914 Z" />
<path
inkscape:connector-curvature="0"
id="path17082-8"
d="M -1326.9159,-1259.2407 L -1326.9159,-1263.6078 Q -1328.5089,-1261.2732 -1331.1182,-1259.9274 Q -1333.7,-1258.5815 -1336.5839,-1258.5815 Q -1339.5227,-1258.5815 -1341.8573,-1259.8724 Q -1344.1919,-1261.1633 -1345.2356,-1263.4979 Q -1346.2793,-1265.8325 -1346.2793,-1269.9524 L -1346.2793,-1288.4094 L -1338.5614,-1288.4094 L -1338.5614,-1275.0061 Q -1338.5614,-1268.8538 -1338.1494,-1267.453 Q -1337.71,-1266.0797 -1336.5839,-1265.2557 Q -1335.4578,-1264.4592 -1333.7274,-1264.4592 Q -1331.7499,-1264.4592 -1330.1843,-1265.5304 Q -1328.6188,-1266.629 -1328.042,-1268.222 Q -1327.4652,-1269.8425 -1327.4652,-1276.1047 L -1327.4652,-1288.4094 L -1319.7473,-1288.4094 L -1319.7473,-1259.2407 L -1326.9159,-1259.2407 Z" />
<path
inkscape:connector-curvature="0"
id="path17084-4"
d="M -1314.4464,-1267.5629 L -1306.701,-1268.7439 Q -1306.2067,-1266.4917 -1304.696,-1265.3107 Q -1303.1854,-1264.1571 -1300.4663,-1264.1571 Q -1297.4725,-1264.1571 -1295.9619,-1265.2557 Q -1294.9457,-1266.0248 -1294.9457,-1267.3157 Q -1294.9457,-1268.1946 -1295.495,-1268.7714 Q -1296.0718,-1269.3207 -1298.0768,-1269.7876 Q -1307.4152,-1271.8475 -1309.9146,-1273.5504 Q -1313.3752,-1275.9125 -1313.3752,-1280.1147 Q -1313.3752,-1283.905 -1310.3815,-1286.4868 Q -1307.3877,-1289.0686 -1301.098,-1289.0686 Q -1295.1105,-1289.0686 -1292.1991,-1287.1185 Q -1289.2877,-1285.1685 -1288.1891,-1281.3507 L -1295.4675,-1280.0049 Q -1295.9344,-1281.7078 -1297.2528,-1282.6141 Q -1298.5437,-1283.5205 -1300.9607,-1283.5205 Q -1304.0094,-1283.5205 -1305.3278,-1282.6691 Q -1306.2067,-1282.0648 -1306.2067,-1281.1035 Q -1306.2067,-1280.2795 -1305.4376,-1279.7028 Q -1304.3939,-1278.9337 -1298.2416,-1277.533 Q -1292.0618,-1276.1322 -1289.6173,-1274.0997 Q -1287.2003,-1272.0398 -1287.2003,-1268.3594 Q -1287.2003,-1264.3494 -1290.5511,-1261.4655 Q -1293.902,-1258.5815 -1300.4663,-1258.5815 Q -1306.4264,-1258.5815 -1309.9146,-1260.9985 Q -1313.3752,-1263.4155 -1314.4464,-1267.5629 Z" />
</g>
</g>
</g>
</g>
<g <g
inkscape:groupmode="layer" inkscape:groupmode="layer"
id="layer63" id="layer63"
@ -22128,6 +22495,110 @@
id="tspan12026">Satellite</tspan></text> id="tspan12026">Satellite</tspan></text>
</g> </g>
</g> </g>
<g
inkscape:groupmode="layer"
id="layer90"
inkscape:label="sparky2-ibus"
sodipodi:insensitive="true"
style="display:inline">
<g
style="display:inline"
id="sparky2-ibus"
transform="matrix(-0.4,0,0,-0.4,1133.7231,497.55198)">
<path
id="path9857-8-8-1-1-4-0-9-3-2-6-5"
d="M 1408.916,1441.5493 C 1402.946,1506.4493 1465.9756,1637.3786 1641.1435,1539.5016"
stroke-miterlimit="4"
inkscape:connector-curvature="0"
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
sodipodi:nodetypes="cc" />
<path
sodipodi:nodetypes="cc"
style="fill:none;stroke:#777777;stroke-width:14.5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
stroke-miterlimit="4"
d="M 1287.0298,1441.5493 C 1292.9998,1506.4493 1229.9702,1637.3786 1054.8023,1539.5016"
id="path21749-5-7-5-1-7-6-3" />
<rect
rx="11.5"
id="rect8853-6-8-6-6-4-6-7-9-8-6-5"
style="color:#000000;fill:url(#linearGradient16665);fill-rule:nonzero;stroke:#000000;stroke-width:5.76999998;stroke-miterlimit:4;stroke-dasharray:none;enable-background:accumulate"
ry="11.5"
height="272"
width="237"
stroke-miterlimit="4"
y="1169.5493"
x="1228.2858" />
<path
sodipodi:nodetypes="cc"
style="display:inline;fill:#cccccc;stroke:#ec6004;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1386.7858,1166.6643 L 1386.7858,995.64237"
id="path8856-5-1-7-1-9-5-4-3-3-4-1-2" />
<path
sodipodi:nodetypes="cc"
style="display:inline;fill:none;stroke:#d81900;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1346.7858,1166.6643 L 1346.7858,995.64337"
id="path8856-1-2-1-9-0-3-26-2-0" />
<path
sodipodi:nodetypes="cc"
style="display:inline;fill:#cccccc;stroke:#000000;stroke-width:15.29999924;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"
inkscape:connector-curvature="0"
d="M 1309.2858,1166.6643 L 1309.2858,995.64337"
id="path8856-1-5-7-7-2-9-1-6-3-2" />
<g
transform="scale(-1,-1)"
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:41.27642822px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;fill:#fdfdfd;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
id="text17069">
<path
d="M -1412.1475,-1323.0706 L -1412.1475,-1352.6171 L -1391.8922,-1352.6171 L -1391.8922,-1347.6187 L -1406.1817,-1347.6187 L -1406.1817,-1340.6251 L -1393.8472,-1340.6251 L -1393.8472,-1335.6268 L -1406.1817,-1335.6268 L -1406.1817,-1323.0706 L -1412.1475,-1323.0706 Z"
id="path17087"
inkscape:connector-curvature="0" />
<path
d="M -1386.9946,-1323.0706 L -1386.9946,-1352.6171 L -1381.3312,-1352.6171 L -1381.3312,-1323.0706 L -1386.9946,-1323.0706 Z"
id="path17089"
inkscape:connector-curvature="0" />
<path
d="M -1378.2274,-1344.4746 L -1372.2012,-1344.4746 L -1367.082,-1329.2781 L -1362.0837,-1344.4746 L -1356.2187,-1344.4746 L -1363.7767,-1323.8767 L -1365.127,-1320.1482 Q -1365.8727,-1318.2738 -1366.558,-1317.2862 Q -1367.2231,-1316.2986 -1368.1099,-1315.694 Q -1368.9765,-1315.0692 -1370.2664,-1314.7266 Q -1371.5361,-1314.384 -1373.1485,-1314.384 Q -1374.781,-1314.384 -1376.3531,-1314.7266 L -1376.8569,-1319.1606 Q -1375.5267,-1318.8986 -1374.4585,-1318.8986 Q -1372.4834,-1318.8986 -1371.5361,-1320.0675 Q -1370.5889,-1321.2163 -1370.085,-1323.0101 L -1378.2274,-1344.4746 Z"
id="path17091"
inkscape:connector-curvature="0" />
<path
d="M -1354.2033,-1332.6843 L -1348.3988,-1333.2486 Q -1347.8747,-1330.3262 -1346.2825,-1328.9557 Q -1344.6702,-1327.5852 -1341.9493,-1327.5852 Q -1339.0672,-1327.5852 -1337.6161,-1328.7944 Q -1336.1448,-1330.0239 -1336.1448,-1331.6564 Q -1336.1448,-1332.7044 -1336.7696,-1333.43 Q -1337.3742,-1334.1757 -1338.906,-1334.7199 Q -1339.954,-1335.0826 -1343.6826,-1336.0097 Q -1348.4794,-1337.1989 -1350.4142,-1338.9322 Q -1353.1351,-1341.3708 -1353.1351,-1344.8777 Q -1353.1351,-1347.135 -1351.8653,-1349.09 Q -1350.5755,-1351.0652 -1348.1771,-1352.093 Q -1345.7585,-1353.1209 -1342.3524,-1353.1209 Q -1336.7898,-1353.1209 -1333.9883,-1350.6822 Q -1331.1667,-1348.2435 -1331.0256,-1344.1723 L -1336.9913,-1343.9103 Q -1337.3742,-1346.1878 -1338.644,-1347.1753 Q -1339.8936,-1348.1831 -1342.4129,-1348.1831 Q -1345.0128,-1348.1831 -1346.4841,-1347.1149 Q -1347.4313,-1346.4296 -1347.4313,-1345.2808 Q -1347.4313,-1344.2328 -1346.5445,-1343.4871 Q -1345.4159,-1342.5398 -1341.0625,-1341.5119 Q -1336.7091,-1340.484 -1334.6332,-1339.3756 Q -1332.5372,-1338.2872 -1331.3682,-1336.3725 Q -1330.1791,-1334.478 -1330.1791,-1331.6765 Q -1330.1791,-1329.1371 -1331.5899,-1326.9201 Q -1333.0007,-1324.7031 -1335.5805,-1323.6147 Q -1338.1603,-1322.5465 -1342.0098,-1322.5465 Q -1347.6127,-1322.5465 -1350.6158,-1325.1263 Q -1353.6188,-1327.7262 -1354.2033,-1332.6843 Z"
id="path17093"
inkscape:connector-curvature="0" />
<path
d="M -1325.3622,-1323.0706 L -1325.3622,-1352.6171 L -1319.6987,-1352.6171 L -1319.6987,-1336.9369 L -1313.0679,-1344.4746 L -1306.0945,-1344.4746 L -1313.4105,-1336.6547 L -1305.5704,-1323.0706 L -1311.6773,-1323.0706 L -1317.0585,-1332.6843 L -1319.6987,-1329.9231 L -1319.6987,-1323.0706 L -1325.3622,-1323.0706 Z"
id="path17095"
inkscape:connector-curvature="0" />
<path
d="M -1304.865,-1344.4746 L -1298.8388,-1344.4746 L -1293.7196,-1329.2781 L -1288.7213,-1344.4746 L -1282.8563,-1344.4746 L -1290.4143,-1323.8767 L -1291.7646,-1320.1482 Q -1292.5103,-1318.2738 -1293.1956,-1317.2862 Q -1293.8607,-1316.2986 -1294.7475,-1315.694 Q -1295.6141,-1315.0692 -1296.904,-1314.7266 Q -1298.1737,-1314.384 -1299.7861,-1314.384 Q -1301.4186,-1314.384 -1302.9907,-1314.7266 L -1303.4945,-1319.1606 Q -1302.1643,-1318.8986 -1301.0961,-1318.8986 Q -1299.121,-1318.8986 -1298.1737,-1320.0675 Q -1297.2265,-1321.2163 -1296.7226,-1323.0101 L -1304.865,-1344.4746 Z"
id="path17097"
inkscape:connector-curvature="0" />
</g>
<g
transform="scale(-1,-1)"
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:56.25px;line-height:125%;font-family:Arial;-inkscape-font-specification:'Sans Bold';letter-spacing:0px;word-spacing:0px;fill:#fdfdfd;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
id="text17073">
<path
d="M -1402.5568,-1259.2407 L -1402.5568,-1299.5056 L -1394.4269,-1299.5056 L -1394.4269,-1259.2407 L -1402.5568,-1259.2407 Z"
id="path17078"
inkscape:connector-curvature="0" />
<path
d="M -1386.6815,-1299.5056 L -1370.5865,-1299.5056 Q -1365.8075,-1299.5056 -1363.4729,-1299.0936 Q -1361.1108,-1298.7091 -1359.2706,-1297.4457 Q -1357.403,-1296.1823 -1356.167,-1294.0674 Q -1354.931,-1291.98 -1354.931,-1289.3707 Q -1354.931,-1286.5417 -1356.4691,-1284.1797 Q -1357.9797,-1281.8176 -1360.589,-1280.6366 Q -1356.9086,-1279.5654 -1354.931,-1276.9836 Q -1352.9535,-1274.4019 -1352.9535,-1270.9137 Q -1352.9535,-1268.1671 -1354.2444,-1265.5579 Q -1355.5078,-1262.9761 -1357.7325,-1261.4105 Q -1359.9298,-1259.8724 -1363.1708,-1259.5154 Q -1365.2032,-1259.2957 -1372.9761,-1259.2407 L -1386.6815,-1259.2407 L -1386.6815,-1299.5056 Z M -1378.5516,-1292.804 L -1378.5516,-1283.493 L -1373.2233,-1283.493 Q -1368.4717,-1283.493 -1367.3181,-1283.6304 Q -1365.2307,-1283.8776 -1364.0497,-1285.0586 Q -1362.8412,-1286.2671 -1362.8412,-1288.2172 Q -1362.8412,-1290.0848 -1363.8849,-1291.2384 Q -1364.9011,-1292.4194 -1366.9336,-1292.6666 Q -1368.1421,-1292.804 -1373.8824,-1292.804 L -1378.5516,-1292.804 Z M -1378.5516,-1276.7914 L -1378.5516,-1266.0248 L -1371.026,-1266.0248 Q -1366.6315,-1266.0248 -1365.4504,-1266.272 Q -1363.6377,-1266.6016 -1362.5116,-1267.865 Q -1361.358,-1269.1559 -1361.358,-1271.2982 Q -1361.358,-1273.111 -1362.2369,-1274.3744 Q -1363.1158,-1275.6378 -1364.7913,-1276.2146 Q -1366.4392,-1276.7914 -1371.9873,-1276.7914 L -1378.5516,-1276.7914 Z"
id="path17080"
inkscape:connector-curvature="0" />
<path
d="M -1326.9159,-1259.2407 L -1326.9159,-1263.6078 Q -1328.5089,-1261.2732 -1331.1182,-1259.9274 Q -1333.7,-1258.5815 -1336.5839,-1258.5815 Q -1339.5227,-1258.5815 -1341.8573,-1259.8724 Q -1344.1919,-1261.1633 -1345.2356,-1263.4979 Q -1346.2793,-1265.8325 -1346.2793,-1269.9524 L -1346.2793,-1288.4094 L -1338.5614,-1288.4094 L -1338.5614,-1275.0061 Q -1338.5614,-1268.8538 -1338.1494,-1267.453 Q -1337.71,-1266.0797 -1336.5839,-1265.2557 Q -1335.4578,-1264.4592 -1333.7274,-1264.4592 Q -1331.7499,-1264.4592 -1330.1843,-1265.5304 Q -1328.6188,-1266.629 -1328.042,-1268.222 Q -1327.4652,-1269.8425 -1327.4652,-1276.1047 L -1327.4652,-1288.4094 L -1319.7473,-1288.4094 L -1319.7473,-1259.2407 L -1326.9159,-1259.2407 Z"
id="path17082"
inkscape:connector-curvature="0" />
<path
d="M -1314.4464,-1267.5629 L -1306.701,-1268.7439 Q -1306.2067,-1266.4917 -1304.696,-1265.3107 Q -1303.1854,-1264.1571 -1300.4663,-1264.1571 Q -1297.4725,-1264.1571 -1295.9619,-1265.2557 Q -1294.9457,-1266.0248 -1294.9457,-1267.3157 Q -1294.9457,-1268.1946 -1295.495,-1268.7714 Q -1296.0718,-1269.3207 -1298.0768,-1269.7876 Q -1307.4152,-1271.8475 -1309.9146,-1273.5504 Q -1313.3752,-1275.9125 -1313.3752,-1280.1147 Q -1313.3752,-1283.905 -1310.3815,-1286.4868 Q -1307.3877,-1289.0686 -1301.098,-1289.0686 Q -1295.1105,-1289.0686 -1292.1991,-1287.1185 Q -1289.2877,-1285.1685 -1288.1891,-1281.3507 L -1295.4675,-1280.0049 Q -1295.9344,-1281.7078 -1297.2528,-1282.6141 Q -1298.5437,-1283.5205 -1300.9607,-1283.5205 Q -1304.0094,-1283.5205 -1305.3278,-1282.6691 Q -1306.2067,-1282.0648 -1306.2067,-1281.1035 Q -1306.2067,-1280.2795 -1305.4376,-1279.7028 Q -1304.3939,-1278.9337 -1298.2416,-1277.533 Q -1292.0618,-1276.1322 -1289.6173,-1274.0997 Q -1287.2003,-1272.0398 -1287.2003,-1268.3594 Q -1287.2003,-1264.3494 -1290.5511,-1261.4655 Q -1293.902,-1258.5815 -1300.4663,-1258.5815 Q -1306.4264,-1258.5815 -1309.9146,-1260.9985 Q -1313.3752,-1263.4155 -1314.4464,-1267.5629 Z"
id="path17084"
inkscape:connector-curvature="0" />
</g>
</g>
</g>
<g <g
inkscape:groupmode="layer" inkscape:groupmode="layer"
id="layer81" id="layer81"
@ -22732,7 +23203,7 @@
inkscape:groupmode="layer" inkscape:groupmode="layer"
id="layer72" id="layer72"
inkscape:label="sparky2-sbus" inkscape:label="sparky2-sbus"
style="display:inline" style="display:none"
sodipodi:insensitive="true"> sodipodi:insensitive="true">
<g <g
style="display:inline" style="display:inline"
@ -41290,7 +41761,8 @@
inkscape:groupmode="layer" inkscape:groupmode="layer"
id="layer79" id="layer79"
inkscape:label="sparky2" inkscape:label="sparky2"
style="display:inline"> style="display:inline"
sodipodi:insensitive="true">
<g <g
style="display:inline" style="display:inline"
transform="matrix(0.96887293,0,0,0.96887293,339.82738,-361.5986)" transform="matrix(0.96887293,0,0,0.96887293,339.82738,-361.5986)"

Before

Width:  |  Height:  |  Size: 4.6 MiB

After

Width:  |  Height:  |  Size: 4.6 MiB

View File

@ -394,6 +394,9 @@ QString SetupWizard::getSummaryText()
case INPUT_EXBUS: case INPUT_EXBUS:
summary.append(tr("Jeti EX.Bus")); summary.append(tr("Jeti EX.Bus"));
break; break;
case INPUT_IBUS:
summary.append(tr("FlySky IBus"));
break;
default: default:
summary.append(tr("Unknown")); summary.append(tr("Unknown"));
} }

View File

@ -180,6 +180,9 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
case VehicleConfigurationSource::INPUT_EXBUS: case VehicleConfigurationSource::INPUT_EXBUS:
data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_EXBUS; data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_EXBUS;
break; break;
case VehicleConfigurationSource::INPUT_IBUS:
data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_IBUS;
break;
default: default:
break; break;
} }
@ -261,6 +264,13 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_EXBUS; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_EXBUS;
} }
break; break;
case VehicleConfigurationSource::INPUT_IBUS:
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_SPARKY2) {
data.SPK2_RcvrPort = HwSettings::SPK2_RCVRPORT_IBUS;
} else {
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_IBUS;
}
break;
default: default:
break; break;
} }
@ -999,6 +1009,9 @@ void VehicleConfigurationHelper::applyManualControlDefaults()
case VehicleConfigurationSource::INPUT_EXBUS: case VehicleConfigurationSource::INPUT_EXBUS:
channelType = ManualControlSettings::CHANNELGROUPS_EXBUS; channelType = ManualControlSettings::CHANNELGROUPS_EXBUS;
break; break;
case VehicleConfigurationSource::INPUT_IBUS:
channelType = ManualControlSettings::CHANNELGROUPS_IBUS;
break;
default: default:
break; break;
} }

View File

@ -66,7 +66,7 @@ public:
GROUNDVEHICLE_MOTORCYCLE, GROUNDVEHICLE_CAR, GROUNDVEHICLE_DIFFERENTIAL }; GROUNDVEHICLE_MOTORCYCLE, GROUNDVEHICLE_CAR, GROUNDVEHICLE_DIFFERENTIAL };
enum ESC_TYPE { ESC_ONESHOT, ESC_SYNCHED, ESC_RAPID, ESC_STANDARD, ESC_UNKNOWN }; enum ESC_TYPE { ESC_ONESHOT, ESC_SYNCHED, ESC_RAPID, ESC_STANDARD, ESC_UNKNOWN };
enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN }; enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN };
enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSM, INPUT_SRXL, INPUT_HOTT_SUMD, INPUT_EXBUS, INPUT_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSM, INPUT_SRXL, INPUT_HOTT_SUMD, INPUT_EXBUS, INPUT_IBUS, INPUT_UNKNOWN };
enum AIRSPEED_TYPE { AIRSPEED_ESTIMATE, AIRSPEED_EAGLETREE, AIRSPEED_MS4525, AIRSPEED_DISABLED }; enum AIRSPEED_TYPE { AIRSPEED_ESTIMATE, AIRSPEED_EAGLETREE, AIRSPEED_MS4525, AIRSPEED_DISABLED };
enum GPS_TYPE { GPS_PLATINUM, GPS_NAZA, GPS_UBX_FLEXI_I2CMAG, GPS_UBX, GPS_NMEA, GPS_DISABLED }; enum GPS_TYPE { GPS_PLATINUM, GPS_NAZA, GPS_UBX_FLEXI_I2CMAG, GPS_UBX, GPS_NMEA, GPS_DISABLED };
enum RADIO_SETTING { RADIO_TELEMETRY, RADIO_DISABLED }; enum RADIO_SETTING { RADIO_TELEMETRY, RADIO_DISABLED };

View File

@ -60,5 +60,7 @@
<file>resources/bttn-hott-up.png</file> <file>resources/bttn-hott-up.png</file>
<file>resources/bttn-exbus-down.png</file> <file>resources/bttn-exbus-down.png</file>
<file>resources/bttn-exbus-up.png</file> <file>resources/bttn-exbus-up.png</file>
<file>resources/bttn-ibus-down.png</file>
<file>resources/bttn-ibus-up.png</file>
</qresource> </qresource>
</RCC> </RCC>

View File

@ -32,6 +32,7 @@
.import UAVTalk.TakeOffLocation 1.0 as TakeOffLocation .import UAVTalk.TakeOffLocation 1.0 as TakeOffLocation
// Sensors // Sensors
.import UAVTalk.AuxMagSettings 1.0 as AuxMagSettings
.import UAVTalk.FlightBatterySettings 1.0 as FlightBatterySettings .import UAVTalk.FlightBatterySettings 1.0 as FlightBatterySettings
// State // State
@ -152,9 +153,15 @@ function isCC3D() {
} }
function frameType() { function frameType() {
return ["FixedWing", "FixedWingElevon", "FixedWingVtail", "VTOL", "HeliCP", "QuadX", "QuadP", var frameTypeText = ["FixedWing", "FixedWingElevon", "FixedWingVtail", "VTOL", "HeliCP", "QuadX", "QuadP",
"Hexa+", "Octo+", "Custom", "HexaX", "HexaH", "OctoV", "OctoCoaxP", "OctoCoaxX", "OctoX", "HexaCoax", "Hexa+", "Octo+", "Custom", "HexaX", "HexaH", "OctoV", "OctoCoaxP", "OctoCoaxX", "OctoX", "HexaCoax",
"Tricopter", "GroundVehicleCar", "GroundVehicleDiff", "GroundVehicleMoto"][systemSettings.airframeType] "Tricopter", "GroundVehicleCar", "GroundVehicleDiff", "GroundVehicleMoto"];
if (frameTypeText.length != SystemSettings.SystemSettingsConstants.AirframeTypeCount) {
console.log("uav.js: frameType() do not match systemSettings.airframeType uavo");
return "FixMe"
}
return frameTypeText[systemSettings.airframeType]
} }
function isVtolOrMultirotor() { function isVtolOrMultirotor() {
@ -223,12 +230,25 @@ function isOplmConnected() {
} }
function magSourceName() { function magSourceName() {
return [magState.source == MagState.Source.Aux ? ["GPSv9", "Flexi", "I2C", "DJI"][auxMagSettings.type] + " " : ""] + var auxMagTypeText = ["GPSv9", "Flexi", "I2C", "DJI"];
["Invalid", "OnBoard", "ExtMag"][magState.source]; var magStateSourceText = ["Invalid", "OnBoard", "ExtMag"];
if ((auxMagTypeText.length != AuxMagSettings.AuxMagSettingsConstants.TypeCount) ||
(magStateSourceText.length != MagState.MagStateConstants.SourceCount)) {
console.log("uav.js: magSourceName() do not match magState.source or auxMagSettings.type uavo");
return "FixMe"
}
return [magState.source == MagState.Source.Aux ? auxMagTypeText[auxMagSettings.type] + " " : ""] + magStateSourceText[magState.source];
} }
function gpsSensorType() { function gpsSensorType() {
return ["Unknown", "NMEA", "UBX", "UBX7", "UBX8", "DJI"][gpsPositionSensor.sensorType] var gpsSensorTypeText = ["Unknown", "NMEA", "UBX", "UBX7", "UBX8", "DJI"];
if (gpsSensorTypeText.length != GPSPositionSensor.GPSPositionSensorConstants.SensorTypeCount) {
console.log("uav.js: gpsSensorType() do not match gpsPositionSensor.sensorType uavo");
return "FixMe"
}
return gpsSensorTypeText[gpsPositionSensor.sensorType];
} }
function gpsNumSat() { function gpsNumSat() {
@ -248,11 +268,23 @@ function gpsAltitude() {
} }
function gpsStatus() { function gpsStatus() {
return ["NO GPS", "NO FIX", "2D", "3D"][gpsPositionSensor.status]; var gpsStatusText = ["NO GPS", "NO FIX", "2D", "3D"];
if (gpsStatusText.length != GPSPositionSensor.GPSPositionSensorConstants.StatusCount) {
console.log("uav.js: gpsStatus() do not match gpsPositionSensor.status uavo");
return "FixMe"
}
return gpsStatusText[gpsPositionSensor.status];
} }
function fusionAlgorithm() { function fusionAlgorithm() {
return ["None", "Basic (No Nav)", "CompMag", "Comp+Mag+GPS", "EKFIndoor", "GPSNav (INS13)"][revoSettings.fusionAlgorithm]; var fusionAlgorithmText = ["None", "Basic (No Nav)", "CompMag", "Comp+Mag+GPS", "EKFIndoor", "GPSNav (INS13)"];
if (fusionAlgorithmText.length != RevoSettings.RevoSettingsConstants.FusionAlgorithmCount) {
console.log("uav.js: fusionAlgorithm() do not match revoSettings.fusionAlgorithm uavo");
return "FixMe"
}
return fusionAlgorithmText[revoSettings.fusionAlgorithm];
} }
function receiverQuality() { function receiverQuality() {
@ -260,7 +292,13 @@ function receiverQuality() {
} }
function oplmLinkState() { function oplmLinkState() {
return ["Disabled", "Enabled", "Disconnected", "Connecting", "Connected"][opLinkStatus.linkState]; var oplmLinkStateText = ["Disabled", "Enabled", "Binding", "Bound", "Disconnected", "Connecting", "Connected"];
if (oplmLinkStateText.length != OPLinkStatus.OPLinkStatusConstants.LinkStateCount) {
console.log("uav.js: oplmLinkState() do not match opLinkStatus.linkState uavo");
return "FixMe"
}
return oplmLinkStateText[opLinkStatus.linkState];
} }
/* /*
@ -305,6 +343,10 @@ function estimatedTimeAlarmColor() {
* Pathplan and Waypoints * Pathplan and Waypoints
* *
*/ */
function isPathPlanEnabled() {
return (flightStatus.flightMode == FlightStatus.FlightMode.PathPlanner);
}
function isPathPlanValid() { function isPathPlanValid() {
return (systemAlarms.alarmPathPlan == SystemAlarms.Alarm.OK); return (systemAlarms.alarmPathPlan == SystemAlarms.Alarm.OK);
} }
@ -318,8 +360,14 @@ function isTakeOffLocationValid() {
} }
function pathModeDesired() { function pathModeDesired() {
return ["GOTO ENDPOINT","FOLLOW VECTOR","CIRCLE RIGHT","CIRCLE LEFT","FIXED ATTITUDE", var pathModeDesiredText = ["GOTO ENDPOINT","FOLLOW VECTOR","CIRCLE RIGHT","CIRCLE LEFT","FIXED ATTITUDE",
"SET ACCESSORY","DISARM ALARM","LAND","BRAKE","VELOCITY","AUTO TAKEOFF"][pathDesired.mode] "SET ACCESSORY","DISARM ALARM","LAND","BRAKE","VELOCITY","AUTO TAKEOFF"];
if (pathModeDesiredText.length != PathDesired.PathDesiredConstants.ModeCount) {
console.log("uav.js: pathModeDesired() do not match pathDesired.mode uavo");
return "FixMe"
}
return pathModeDesiredText[pathDesired.mode];
} }
function velocityDesiredDown() { function velocityDesiredDown() {
@ -377,15 +425,27 @@ function isVtolPathFollowerSettingsThrustAuto() {
} }
function flightModeName() { function flightModeName() {
return ["MANUAL", "STAB 1", "STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6", var flightModeNameText = ["MANUAL", "STAB 1", "STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6",
"POS HOLD", "COURSELOCK", "VEL ROAM", "HOME LEASH", "ABS POS", "RTB", "POS HOLD", "COURSELOCK", "VEL ROAM", "HOME LEASH", "ABS POS", "RTB",
"LAND", "PATHPLAN", "POI", "AUTOCRUISE", "AUTOTAKEOFF"][flightStatus.flightMode]; "LAND", "PATHPLAN", "POI", "AUTOCRUISE", "AUTOTAKEOFF", "AUTOTUNE"];
if (flightModeNameText.length != FlightStatus.FlightStatusConstants.FlightModeCount) {
console.log("uav.js: flightModeName() do not match flightStatus.flightMode uavo");
return "FixMe"
}
return flightModeNameText[flightStatus.flightMode];
} }
function flightModeColor() { function flightModeColor() {
return ["gray", "green", "green", "green", "green", "green", "green", var flightModeColorText = ["gray", "green", "green", "green", "green", "green", "green",
"cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan",
"cyan", "cyan", "cyan", "cyan", "cyan"][flightStatus.flightMode]; "cyan", "cyan", "cyan", "cyan", "cyan", "cyan"];
if (flightModeColorText.length != FlightStatus.FlightStatusConstants.FlightModeCount) {
console.log("uav.js: flightModeColor() do not match flightStatus.flightMode uavo");
return "gray"
}
return flightModeColorText[flightStatus.flightMode];
} }
function thrustMode() { function thrustMode() {
@ -396,23 +456,52 @@ function thrustMode() {
} }
function thrustModeName() { function thrustModeName() {
// Last "Auto" Thrust mode is added to UAVO enum list
// Lower case modes are never displayed/used for Thrust // Lower case modes are never displayed/used for Thrust
return ["MANUAL", "rate", "ratetrainer", "attitude", "axislock", "weakleveling", "virtualbar", "acro+ ", "rattitude", var thrustModeNameText = ["MANUAL", "rate", "ratetrainer", "attitude", "axislock", "weakleveling", "virtualbar", "acro+ ", "rattitude",
"ALT HOLD", "ALT VARIO", "CRUISECTRL", "AUTO"][thrustMode()] "ALT HOLD", "ALT VARIO", "CRUISECTRL", "systemident"];
// Last "Auto" Thrust mode is added to current UAVO enum list for display.
thrustModeNameText.push("AUTO");
if (thrustModeNameText.length != StabilizationDesired.StabilizationDesiredConstants.StabilizationModeCount + 1) {
console.log("uav.js: thrustModeName() do not match stabilizationDesired.StabilizationMode uavo");
return "FixMe"
}
return thrustModeNameText[thrustMode()];
} }
function thrustModeColor() { function thrustModeColor() {
return ["green", "grey", "grey", "grey", "grey", "grey", "grey", "grey", "grey", var thrustModeColorText = ["green", "grey", "grey", "grey", "grey", "grey", "grey", "grey", "grey",
"green", "green", "green", "cyan"][thrustMode()]; "green", "green", "green", "grey"];
// Add the cyan color for AUTO
thrustModeColorText.push("cyan");
if (thrustModeColorText.length != StabilizationDesired.StabilizationDesiredConstants.StabilizationModeCount + 1) {
console.log("uav.js: thrustModeColor() do not match stabilizationDesired.StabilizationMode uavo");
return "gray"
}
return thrustModeColorText[thrustMode()];
} }
function armStatusName() { function armStatusName() {
return ["DISARMED","ARMING","ARMED"][flightStatus.armed]; var armStatusNameText = ["DISARMED","ARMING","ARMED"];
if (armStatusNameText.length != FlightStatus.FlightStatusConstants.ArmedCount) {
console.log("uav.js: armStatusName() do not match flightStatus.armed uavo");
return "FixMe"
}
return armStatusNameText[flightStatus.armed];
} }
function armStatusColor() { function armStatusColor() {
return ["gray", "orange", "green"][flightStatus.armed]; var armStatusColorText = ["gray", "orange", "green"];
if (armStatusColorText.length != FlightStatus.FlightStatusConstants.ArmedCount) {
console.log("uav.js: armStatusColor() do not match flightStatus.armed uavo");
return "gray"
}
return armStatusColorText[flightStatus.armed];
} }
/* /*

View File

@ -134,7 +134,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: Math.floor(scaledBounds.y * sceneItem.height) y: Math.floor(scaledBounds.y * sceneItem.height)
visible: UAV.isPathPlanValid() visible: UAV.isPathPlanEnabled()
} }
SvgElementPositionItem { SvgElementPositionItem {
@ -143,7 +143,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: Math.floor(scaledBounds.y * sceneItem.height) y: Math.floor(scaledBounds.y * sceneItem.height)
visible: UAV.isPathPlanValid() visible: UAV.isPathPlanEnabled()
Text { Text {
text: UAV.isPathPlanValid() ? " " + UAV.waypointHeading().toFixed(1) + "°" : " 0°" text: UAV.isPathPlanValid() ? " " + UAV.waypointHeading().toFixed(1) + "°" : " 0°"
@ -164,7 +164,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: Math.floor(scaledBounds.y * sceneItem.height) y: Math.floor(scaledBounds.y * sceneItem.height)
visible: UAV.isPathPlanValid() visible: UAV.isPathPlanEnabled()
Text { Text {
text: UAV.isPathPlanValid() ? " " + UAV.waypointDistance().toFixed(0) + " m" : " 0 m" text: UAV.isPathPlanValid() ? " " + UAV.waypointDistance().toFixed(0) + " m" : " 0 m"
@ -185,7 +185,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: Math.floor(scaledBounds.y * sceneItem.height) y: Math.floor(scaledBounds.y * sceneItem.height)
visible: UAV.isPathPlanValid() visible: UAV.isPathPlanEnabled()
MouseArea { id: total_dist_mouseArea; anchors.fill: parent; cursorShape: Qt.PointingHandCursor; onClicked: reset_distance()} MouseArea { id: total_dist_mouseArea; anchors.fill: parent; cursorShape: Qt.PointingHandCursor; onClicked: reset_distance()}
@ -213,7 +213,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: Math.floor(scaledBounds.y * sceneItem.height) y: Math.floor(scaledBounds.y * sceneItem.height)
visible: UAV.isPathPlanValid() visible: UAV.isPathPlanEnabled()
Text { Text {
text: UAV.isPathPlanValid() ? Utils.estimatedTimeOfArrival(UAV.waypointDistance(), UAV.currentVelocity()) : "00:00:00" text: UAV.isPathPlanValid() ? Utils.estimatedTimeOfArrival(UAV.waypointDistance(), UAV.currentVelocity()) : "00:00:00"
@ -234,7 +234,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: Math.floor(scaledBounds.y * sceneItem.height) y: Math.floor(scaledBounds.y * sceneItem.height)
visible: UAV.isPathPlanValid() visible: UAV.isPathPlanEnabled()
Text { Text {
text: UAV.isPathPlanValid() ? UAV.currentWaypointActive() + " / " + UAV.waypointCount() : "0 / 0" text: UAV.isPathPlanValid() ? UAV.currentWaypointActive() + " / " + UAV.waypointCount() : "0 / 0"
@ -255,7 +255,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: Math.floor(scaledBounds.y * sceneItem.height) y: Math.floor(scaledBounds.y * sceneItem.height)
visible: UAV.isPathPlanValid() visible: UAV.isPathPlanEnabled()
Text { Text {
text: UAV.isPathPlanValid() ? UAV.pathModeDesired() : "" text: UAV.isPathPlanValid() ? UAV.pathModeDesired() : ""
@ -281,7 +281,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: scaledBounds.y * sceneItem.height y: scaledBounds.y * sceneItem.height
visible: (!UAV.isPathPlanValid() && UAV.batteryModuleEnabled()) visible: (!UAV.isPathPlanEnabled() && UAV.batteryModuleEnabled())
Rectangle { Rectangle {
anchors.fill: parent anchors.fill: parent
@ -296,7 +296,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: Math.floor(scaledBounds.y * sceneItem.height) y: Math.floor(scaledBounds.y * sceneItem.height)
visible: (!UAV.isPathPlanValid() && UAV.batteryModuleEnabled()) visible: (!UAV.isPathPlanEnabled() && UAV.batteryModuleEnabled())
} }
SvgElementPositionItem { SvgElementPositionItem {
@ -307,7 +307,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: scaledBounds.y * sceneItem.height y: scaledBounds.y * sceneItem.height
visible: (!UAV.isPathPlanValid() && UAV.batteryModuleEnabled()) visible: (!UAV.isPathPlanEnabled() && UAV.batteryModuleEnabled())
Rectangle { Rectangle {
anchors.fill: parent anchors.fill: parent
@ -334,7 +334,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: scaledBounds.y * sceneItem.height y: scaledBounds.y * sceneItem.height
visible: (!UAV.isPathPlanValid() && UAV.batteryModuleEnabled()) visible: (!UAV.isPathPlanEnabled() && UAV.batteryModuleEnabled())
Rectangle { Rectangle {
anchors.fill: parent anchors.fill: parent
@ -361,7 +361,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: scaledBounds.y * sceneItem.height y: scaledBounds.y * sceneItem.height
visible: (!UAV.isPathPlanValid() && UAV.batteryModuleEnabled()) visible: (!UAV.isPathPlanEnabled() && UAV.batteryModuleEnabled())
Rectangle { Rectangle {
anchors.fill: parent anchors.fill: parent
@ -406,7 +406,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: Math.floor(scaledBounds.y * sceneItem.height) y: Math.floor(scaledBounds.y * sceneItem.height)
visible: !UAV.isPathPlanValid() visible: !UAV.isPathPlanEnabled()
} }
SvgElementPositionItem { SvgElementPositionItem {
@ -415,7 +415,7 @@ Item {
width: scaledBounds.width * sceneItem.width width: scaledBounds.width * sceneItem.width
height: scaledBounds.height * sceneItem.height height: scaledBounds.height * sceneItem.height
y: Math.floor(scaledBounds.y * sceneItem.height) y: Math.floor(scaledBounds.y * sceneItem.height)
visible: !UAV.isPathPlanValid() visible: !UAV.isPathPlanEnabled()
TooltipArea { TooltipArea {
text: "Reset distance counter" text: "Reset distance counter"

View File

@ -165,7 +165,8 @@ endif
BUILD_SDK_TARGETS := arm_sdk BUILD_SDK_TARGETS := arm_sdk
ifeq ($(UNAME), Windows) ifeq ($(UNAME), Windows)
BUILD_SDK_TARGETS += nsis mesawin BUILD_SDK_TARGETS += nsis mesawin
else endif
ifeq ($(UNAME), Darwin)
BUILD_SDK_TARGETS += qt_sdk osg BUILD_SDK_TARGETS += qt_sdk osg
endif endif
ALL_SDK_TARGETS := $(BUILD_SDK_TARGETS) gtest uncrustify doxygen ALL_SDK_TARGETS := $(BUILD_SDK_TARGETS) gtest uncrustify doxygen
@ -829,7 +830,7 @@ ifeq ($(shell [ -d "$(OSG_SDK_DIR)" ] && $(ECHO) "exists"), exists)
export OSG_SDK_DIR := $(OSG_SDK_DIR) export OSG_SDK_DIR := $(OSG_SDK_DIR)
else else
# not installed, hope it's in the path... # not installed, hope it's in the path...
$(info $(EMPTY) WARNING $(call toprel, $(OSG_SDK_DIR)) not found (make osg_install), using system PATH) # $(info $(EMPTY) WARNING $(call toprel, $(OSG_SDK_DIR)) not found (make osg_install), using system PATH)
endif endif
.PHONY: osg_version .PHONY: osg_version
@ -852,7 +853,7 @@ ifeq ($(shell [ -d "$(OSGEARTH_SDK_DIR)" ] && $(ECHO) "exists"), exists)
export OSGEARTH_SDK_DIR := $(OSGEARTH_SDK_DIR) export OSGEARTH_SDK_DIR := $(OSGEARTH_SDK_DIR)
else else
# not installed, hope it's in the path... # not installed, hope it's in the path...
$(info $(EMPTY) WARNING $(call toprel, $(OSGEARTH_SDK_DIR)) not found (make osgearth_install), using system PATH) # $(info $(EMPTY) WARNING $(call toprel, $(OSGEARTH_SDK_DIR)) not found (make osgearth_install), using system PATH)
endif endif
.PHONY: osgearth_version .PHONY: osgearth_version

View File

@ -12,7 +12,7 @@ export DH_OPTIONS
dh $@ dh $@
override_dh_auto_configure: override_dh_auto_configure:
$(MAKE) config_new GCS_EXTRA_CONF='osg osgearth' WITH_PREBUILT_FW=$(CURDIR)/firmware $(MAKE) config_new WITH_PREBUILT_FW=$(CURDIR)/firmware
override_dh_auto_build: override_dh_auto_build:
dh_auto_build -- opfw_resource gcs dh_auto_build -- opfw_resource gcs

View File

@ -25,7 +25,7 @@ BuildRequires: qt5-qtsvg-devel
BuildRequires: qt5-qttools-devel BuildRequires: qt5-qttools-devel
BuildRequires: qt5-qttranslations BuildRequires: qt5-qttranslations
BuildRequires: OpenSceneGraph-devel BuildRequires: OpenSceneGraph-devel
%{!?fc22:BuildRequires: osgearth-devel} BuildRequires: osgearth-devel
BuildRequires: dwz BuildRequires: dwz
BuildRequires: pkgconfig BuildRequires: pkgconfig
BuildRequires: python BuildRequires: python
@ -41,7 +41,7 @@ Requires: qt5-qtscript
Requires: qt5-qtserialport Requires: qt5-qtserialport
Requires: qt5-qtsvg Requires: qt5-qtsvg
Requires: OpenSceneGraph-libs Requires: OpenSceneGraph-libs
%{!?fc22:Requires: osgearth} Requires: osgearth
%description %description
@ -59,8 +59,7 @@ make config_new \
prefix=%{_prefix} \ prefix=%{_prefix} \
QMAKE=qmake-qt5 \ QMAKE=qmake-qt5 \
udevrulesdir=%{_udevrulesdir} \ udevrulesdir=%{_udevrulesdir} \
WITH_PREBUILT_FW=$(pwd)/build/firmware \ WITH_PREBUILT_FW=$(pwd)/build/firmware
GCS_EXTRA_CONF='osg%{!?fc22: osgearth}'
make %{?_smp_mflags} opfw_resource gcs make %{?_smp_mflags} opfw_resource gcs

View File

@ -13,6 +13,7 @@
<elementname>PathPlanner1</elementname> <elementname>PathPlanner1</elementname>
<elementname>ManualControl</elementname> <elementname>ManualControl</elementname>
<elementname>CameraControl</elementname> <elementname>CameraControl</elementname>
<elementname>DebugLog</elementname>
</elementnames> </elementnames>
</field> </field>
<field name="Running" units="bool" type="enum"> <field name="Running" units="bool" type="enum">
@ -27,6 +28,7 @@
<elementname>PathPlanner1</elementname> <elementname>PathPlanner1</elementname>
<elementname>ManualControl</elementname> <elementname>ManualControl</elementname>
<elementname>CameraControl</elementname> <elementname>CameraControl</elementname>
<elementname>DebugLog</elementname>
</elementnames> </elementnames>
<options> <options>
<option>False</option> <option>False</option>
@ -45,6 +47,7 @@
<elementname>PathPlanner1</elementname> <elementname>PathPlanner1</elementname>
<elementname>ManualControl</elementname> <elementname>ManualControl</elementname>
<elementname>CameraControl</elementname> <elementname>CameraControl</elementname>
<elementname>DebugLog</elementname>
</elementnames> </elementnames>
</field> </field>
<access gcs="readonly" flight="readwrite"/> <access gcs="readonly" flight="readwrite"/>

View File

@ -3,7 +3,7 @@
<description>Selection of optional hardware configurations.</description> <description>Selection of optional hardware configurations.</description>
<field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled+OneShot,PWM+NoOneShot,PPM+NoOneShot,PPM+PWM+NoOneShot,PPM+Outputs+NoOneShot,PPM_PIN8+OneShot, Outputs+OneShot" defaultvalue="PWM+NoOneShot"/> <field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled+OneShot,PWM+NoOneShot,PPM+NoOneShot,PPM+PWM+NoOneShot,PPM+Outputs+NoOneShot,PPM_PIN8+OneShot, Outputs+OneShot" defaultvalue="PWM+NoOneShot"/>
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Telemetry"/> <field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Telemetry"/>
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,PPM,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/> <field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,PPM,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="RV_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+Outputs,Outputs" defaultvalue="PWM"/> <field name="RV_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+Outputs,Outputs" defaultvalue="PWM"/>
<field name="RV_AuxPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,DSM,ComAux,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/> <field name="RV_AuxPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,DSM,ComAux,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="RV_AuxSBusPort" units="function" type="enum" elements="1" options="Disabled,S.Bus,DSM,ComAux,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/> <field name="RV_AuxSBusPort" units="function" type="enum" elements="1" options="Disabled,S.Bus,DSM,ComAux,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
@ -11,15 +11,15 @@
<field name="RV_TelemetryPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,ComAux,ComBridge,MSP,MAVLink" defaultvalue="Telemetry"/> <field name="RV_TelemetryPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,ComAux,ComBridge,MSP,MAVLink" defaultvalue="Telemetry"/>
<field name="RV_GPSPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,ComAux,ComBridge,MSP,MAVLink" defaultvalue="GPS"/> <field name="RV_GPSPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,ComAux,ComBridge,MSP,MAVLink" defaultvalue="GPS"/>
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Telemetry,PPM+Outputs,Outputs,Telemetry,ComBridge,MSP,MAVLink" <field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Outputs,PPM+Telemetry,PPM+DebugConsole,PPM+ComBridge,PPM+MSP,PPM+MAVLink,PPM+GPS,Outputs,Telemetry,DebugConsole,ComBridge,MSP,MAVLink,GPS"
defaultvalue="PWM" defaultvalue="PWM"
limits="%0905NE:PPM+PWM:PPM+Telemetry:Telemetry:ComBridge:MSP:MAVLink;"/> limits="%0905NE:PPM+PWM:PPM+Telemetry:PPM+DebugConsole:PPM+ComBridge:PPM+MSP:PPM+MAVLink:PPM+GPS:Telemetry:DebugConsole:ComBridge:MSP:MAVLink:GPS;"/>
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/> <field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/> <field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="SPK2_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PPM,S.Bus,DSM,SRXL,EX.Bus,HoTT SUMD,HoTT SUMH" defaultvalue="PPM"/> <field name="SPK2_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PPM,S.Bus,DSM,SRXL,IBus,EX.Bus,HoTT SUMD,HoTT SUMH" defaultvalue="PPM"/>
<field name="SPK2_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/> <field name="SPK2_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="SPK2_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/> <field name="SPK2_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="SPK2_I2CPort" units="function" type="enum" elements="1" options="Disabled,I2C" defaultvalue="Disabled"/> <field name="SPK2_I2CPort" units="function" type="enum" elements="1" options="Disabled,I2C" defaultvalue="Disabled"/>
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/> <field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>

View File

@ -3,7 +3,7 @@
<description>Settings to indicate how to decode receiver input by @ref ManualControlModule.</description> <description>Settings to indicate how to decode receiver input by @ref ManualControlModule.</description>
<field name="ChannelGroups" units="Channel Group" type="enum" <field name="ChannelGroups" units="Channel Group" type="enum"
elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2,Accessory3" elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2,Accessory3"
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),DSM (RcvrPort),S.Bus,EX.Bus,HoTT,SRXL,GCS,OPLink,OpenLRS,None" defaultvalue="None"/> options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),DSM (RcvrPort),S.Bus,EX.Bus,HoTT,SRXL,IBus,GCS,OPLink,OpenLRS,None" defaultvalue="None"/>
<field name="ChannelNumber" units="channel" type="uint8" defaultvalue="0" <field name="ChannelNumber" units="channel" type="uint8" defaultvalue="0"
elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2,Accessory3"/> elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2,Accessory3"/>
<field name="ChannelMin" units="us" type="int16" defaultvalue="1000" <field name="ChannelMin" units="us" type="int16" defaultvalue="1000"

View File

@ -2,7 +2,7 @@
<object name="ReceiverActivity" singleinstance="true" settings="false" category="System"> <object name="ReceiverActivity" singleinstance="true" settings="false" category="System">
<description>Monitors which receiver channels have been active within the last second.</description> <description>Monitors which receiver channels have been active within the last second.</description>
<field name="ActiveGroup" units="Channel Group" type="enum" elements="1" <field name="ActiveGroup" units="Channel Group" type="enum" elements="1"
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),DSM (RcvrPort),S.Bus,EX.Bus,HoTT,SRXL,GCS,OPLink,OpenLRS,None" options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),DSM (RcvrPort),S.Bus,EX.Bus,HoTT,SRXL,IBus,GCS,OPLink,OpenLRS,None"
defaultvalue="None"/> defaultvalue="None"/>
<field name="ActiveChannel" units="channel" type="uint8" elements="1" <field name="ActiveChannel" units="channel" type="uint8" elements="1"
defaultvalue="255"/> defaultvalue="255"/>