mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-11-29 07:24:13 +01:00
LP-499 Adds support for bridging either radio primary, radio auxilary, and/or VCP to any of the output ports (main, flexi, VCP, HID). Also adds the ability to configure the com speed of the UARTs independent of the air data rate.
This commit is contained in:
parent
a9ca744293
commit
dc5eef0cb5
@ -122,6 +122,11 @@ static void systemTask(__attribute__((unused)) void *parameters)
|
||||
while (!initTaskDone) {
|
||||
vTaskDelay(10);
|
||||
}
|
||||
|
||||
#ifndef PIOS_INCLUDE_WDG
|
||||
// if no watchdog is enabled, don't reset watchdog in MODULE_TASKCREATE_ALL loop
|
||||
#define PIOS_WDG_Clear()
|
||||
#endif
|
||||
/* create all modules thread */
|
||||
MODULE_TASKCREATE_ALL;
|
||||
|
||||
|
@ -41,23 +41,21 @@
|
||||
#include <uavtalk_priv.h>
|
||||
#include <pios_rfm22b.h>
|
||||
#include <ecc.h>
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
#include <pios_eeprom.h>
|
||||
#endif
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
// ****************
|
||||
// Private constants
|
||||
|
||||
#define STACK_SIZE_BYTES 150
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
|
||||
#define MAX_RETRIES 2
|
||||
#define RETRY_TIMEOUT_MS 20
|
||||
#define EVENT_QUEUE_SIZE 10
|
||||
#define MAX_PORT_DELAY 200
|
||||
#define SERIAL_RX_BUF_LEN 100
|
||||
#define PPM_INPUT_TIMEOUT 100
|
||||
#define TELEM_STACK_SIZE_WORDS 150
|
||||
#define PPM_STACK_SIZE_WORDS 150
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
|
||||
#define MAX_RETRIES 2
|
||||
#define RETRY_TIMEOUT_MS 20
|
||||
#define EVENT_QUEUE_SIZE 10
|
||||
#define MAX_PORT_DELAY 200
|
||||
#define SERIAL_RX_BUF_LEN 100
|
||||
#define PPM_INPUT_TIMEOUT 100
|
||||
|
||||
|
||||
// ****************
|
||||
@ -67,10 +65,9 @@ typedef struct {
|
||||
// The task handles.
|
||||
xTaskHandle telemetryTxTaskHandle;
|
||||
xTaskHandle telemetryRxTaskHandle;
|
||||
xTaskHandle radioTxTaskHandle;
|
||||
xTaskHandle radioRxTaskHandle;
|
||||
xTaskHandle telemRadioTxTaskHandle;
|
||||
xTaskHandle telemRadioRxTaskHandle;
|
||||
xTaskHandle PPMInputTaskHandle;
|
||||
xTaskHandle serialRxTaskHandle;
|
||||
|
||||
// The UAVTalk connection on the com side.
|
||||
UAVTalkConnection telemUAVTalkCon;
|
||||
@ -80,21 +77,12 @@ typedef struct {
|
||||
xQueueHandle uavtalkEventQueue;
|
||||
xQueueHandle radioEventQueue;
|
||||
|
||||
// The raw serial Rx buffer
|
||||
uint8_t serialRxBuf[SERIAL_RX_BUF_LEN];
|
||||
|
||||
// Error statistics.
|
||||
uint32_t telemetryTxRetries;
|
||||
uint32_t radioTxRetries;
|
||||
uint32_t telemetryTxRetries;
|
||||
uint32_t radioTxRetries;
|
||||
|
||||
// Is this modem the coordinator
|
||||
bool isCoordinator;
|
||||
|
||||
// Should we parse UAVTalk?
|
||||
bool parseUAVTalk;
|
||||
|
||||
// The current configured uart speed
|
||||
OPLinkSettingsComSpeedOptions comSpeed;
|
||||
bool isCoordinator;
|
||||
} RadioComBridgeData;
|
||||
|
||||
// ****************
|
||||
@ -102,9 +90,8 @@ typedef struct {
|
||||
|
||||
static void telemetryTxTask(void *parameters);
|
||||
static void telemetryRxTask(void *parameters);
|
||||
static void serialRxTask(void *parameters);
|
||||
static void radioTxTask(void *parameters);
|
||||
static void radioRxTask(void *parameters);
|
||||
static void telemRadioTxTask(void *parameters);
|
||||
static void telemRadioRxTask(void *parameters);
|
||||
static void PPMInputTask(void *parameters);
|
||||
static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length);
|
||||
static int32_t RadioSendHandler(uint8_t *buf, int32_t length);
|
||||
@ -133,11 +120,6 @@ static int32_t RadioComBridgeStart(void)
|
||||
// Check if this is the coordinator modem
|
||||
data->isCoordinator = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPLINKCOORDINATOR);
|
||||
|
||||
// We will not parse/send UAVTalk if any ports are configured as Serial (except for over the USB HID port).
|
||||
data->parseUAVTalk = ((oplinkSettings.MainPort != OPLINKSETTINGS_MAINPORT_SERIAL) &&
|
||||
(oplinkSettings.FlexiPort != OPLINKSETTINGS_FLEXIPORT_SERIAL) &&
|
||||
(oplinkSettings.VCPPort != OPLINKSETTINGS_VCPPORT_SERIAL));
|
||||
|
||||
// Set the maximum radio RF power.
|
||||
switch (oplinkSettings.MaxRFPower) {
|
||||
case OPLINKSETTINGS_MAXRFPOWER_125:
|
||||
@ -186,34 +168,37 @@ static int32_t RadioComBridgeStart(void)
|
||||
ObjectPersistenceConnectCallback(&objectPersistenceUpdatedCb);
|
||||
|
||||
// Start the primary tasks for receiving/sending UAVTalk packets from the GCS.
|
||||
xTaskCreate(telemetryTxTask, "telemetryTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryTxTaskHandle));
|
||||
xTaskCreate(telemetryRxTask, "telemetryRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryRxTaskHandle));
|
||||
if (PIOS_PPM_RECEIVER != 0) {
|
||||
xTaskCreate(PPMInputTask, "PPMInputTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->PPMInputTaskHandle));
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// These tasks are always needed at least for configuration over HID.
|
||||
xTaskCreate(telemetryTxTask, "telemetryTxTask", TELEM_STACK_SIZE_WORDS, NULL, TASK_PRIORITY, &(data->telemetryTxTaskHandle));
|
||||
xTaskCreate(telemetryRxTask, "telemetryRxTask", TELEM_STACK_SIZE_WORDS, NULL, TASK_PRIORITY, &(data->telemetryRxTaskHandle));
|
||||
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_TELEMETRYTX)
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_TELEMETRYTX);
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_TELEMETRYRX)
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_TELEMETRYRX);
|
||||
#endif
|
||||
// Start the tasks for sending/receiving telemetry over a radio link if a telemetry (GCS) link configured.
|
||||
if (PIOS_COM_GCS_OUT) {
|
||||
xTaskCreate(telemRadioTxTask, "telemRadioTxTask", TELEM_STACK_SIZE_WORDS, NULL, TASK_PRIORITY, &(data->telemRadioTxTaskHandle));
|
||||
xTaskCreate(telemRadioRxTask, "telemRadioRxTask", TELEM_STACK_SIZE_WORDS, NULL, TASK_PRIORITY, &(data->telemRadioRxTaskHandle));
|
||||
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_TELEMRADIOTX)
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_TELEMRADIOTX);
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_TELEMRADIORX)
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_TELEMRADIORX);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Start the task for reading and processing PPM data if it's configured.
|
||||
if (PIOS_PPM_RECEIVER) {
|
||||
xTaskCreate(PPMInputTask, "PPMInputTask", PPM_STACK_SIZE_WORDS, NULL, TASK_PRIORITY, &(data->PPMInputTaskHandle));
|
||||
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_PPMINPUT)
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_PPMINPUT);
|
||||
#endif
|
||||
}
|
||||
if (!data->parseUAVTalk) {
|
||||
// If the user wants raw serial communication, we need to spawn another thread to handle it.
|
||||
xTaskCreate(serialRxTask, "serialRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->serialRxTaskHandle));
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_SERIALRX);
|
||||
#endif
|
||||
}
|
||||
xTaskCreate(radioTxTask, "radioTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioTxTaskHandle));
|
||||
xTaskCreate(radioRxTask, "radioRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioRxTaskHandle));
|
||||
|
||||
// Register the watchdog timers.
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_TELEMETRYTX);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_TELEMETRYRX);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_RADIOTX);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORX);
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -248,10 +233,6 @@ static int32_t RadioComBridgeInitialize(void)
|
||||
data->telemetryTxRetries = 0;
|
||||
data->radioTxRetries = 0;
|
||||
|
||||
data->parseUAVTalk = true;
|
||||
data->comSpeed = OPLINKSETTINGS_COMSPEED_9600;
|
||||
PIOS_COM_RADIO = PIOS_COM_RFM22B;
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(RadioComBridgeInitialize, RadioComBridgeStart);
|
||||
@ -323,9 +304,48 @@ static void updateRadioComBridgeStats()
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Telemetry transmit task, regular priority
|
||||
* @brief Reads the PPM input device and sends out OPLinkReceiver objects.
|
||||
*
|
||||
* @param[in] parameters The task parameters
|
||||
* @param[in] parameters The task parameters (unused)
|
||||
*/
|
||||
static void PPMInputTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
xSemaphoreHandle sem = PIOS_RCVR_GetSemaphore(PIOS_PPM_RECEIVER, 1);
|
||||
int16_t channels[RFM22B_PPM_NUM_CHANNELS];
|
||||
|
||||
while (1) {
|
||||
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_PPMINPUT)
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_PPMINPUT);
|
||||
#endif
|
||||
|
||||
// Wait for the receiver semaphore.
|
||||
if (xSemaphoreTake(sem, PPM_INPUT_TIMEOUT) == pdTRUE) {
|
||||
// Read the receiver inputs.
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
|
||||
channels[i] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i + 1);
|
||||
}
|
||||
} else {
|
||||
// Failsafe
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
|
||||
channels[i] = PIOS_RCVR_INVALID;
|
||||
}
|
||||
}
|
||||
|
||||
// Pass the channel values to the radio device.
|
||||
PIOS_RFM22B_PPMSet(pios_rfm22b_id, channels, RFM22B_PPM_NUM_CHANNELS);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Telemetry tasks and functions
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @brief Receives events on the Radio->GCS telemetry stream and sends
|
||||
* the requested object(s) to the GCS.
|
||||
*
|
||||
* @param[in] parameters None.
|
||||
*/
|
||||
static void telemetryTxTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
@ -333,7 +353,7 @@ static void telemetryTxTask(__attribute__((unused)) void *parameters)
|
||||
|
||||
// Loop forever
|
||||
while (1) {
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_TELEMETRYTX)
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_TELEMETRYTX);
|
||||
#endif
|
||||
// Wait for queue message
|
||||
@ -357,16 +377,17 @@ static void telemetryTxTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Radio tx task. Receive data packets from the com port and send to the radio.
|
||||
* @brief Receives events on the GCS->Radio telemetry stream and sends
|
||||
* the requested object(s) over the radio telenetry stream.
|
||||
*
|
||||
* @param[in] parameters The task parameters
|
||||
* @param[in] parameters none.
|
||||
*/
|
||||
static void radioTxTask(__attribute__((unused)) void *parameters)
|
||||
static void telemRadioTxTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
// Task loop
|
||||
while (1) {
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_RADIOTX);
|
||||
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_TELEMRADIOTX)
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_TELEMRADIOTX);
|
||||
#endif
|
||||
|
||||
// Process the radio event queue, sending UAVObjects over the radio link as necessary.
|
||||
@ -391,34 +412,24 @@ static void radioTxTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Radio rx task. Receive data packets from the radio and pass them on.
|
||||
* @brief Reads data from the radio telemetry port and processes it
|
||||
* through the Radio->GCS telemetry stream.
|
||||
*
|
||||
* @param[in] parameters The task parameters
|
||||
*/
|
||||
static void radioRxTask(__attribute__((unused)) void *parameters)
|
||||
static void telemRadioRxTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
// Task loop
|
||||
while (1) {
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORX);
|
||||
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_TELEMRADIORX)
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_TELEMRADIORX);
|
||||
#endif
|
||||
if (PIOS_COM_RADIO) {
|
||||
if (PIOS_COM_GCS_OUT) {
|
||||
uint8_t serial_data[16];
|
||||
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, serial_data, sizeof(serial_data), MAX_PORT_DELAY);
|
||||
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(PIOS_COM_GCS_OUT, serial_data, sizeof(serial_data), MAX_PORT_DELAY);
|
||||
if (bytes_to_process > 0) {
|
||||
if (data->parseUAVTalk) {
|
||||
// Pass the data through the UAVTalk parser.
|
||||
ProcessRadioStream(data->radioUAVTalkCon, data->telemUAVTalkCon, serial_data, bytes_to_process);
|
||||
} else if (PIOS_COM_TELEMETRY) {
|
||||
// Send the data straight to the telemetry port.
|
||||
// Following call can fail with -2 error code (buffer full) or -3 error code (could not acquire send mutex)
|
||||
// It is the caller responsibility to retry in such cases...
|
||||
int32_t ret = -2;
|
||||
uint8_t count = 5;
|
||||
while (count-- > 0 && ret < -1) {
|
||||
ret = PIOS_COM_SendBufferNonBlocking(PIOS_COM_TELEMETRY, serial_data, bytes_to_process);
|
||||
}
|
||||
}
|
||||
// Pass the data through the UAVTalk parser.
|
||||
ProcessRadioStream(data->radioUAVTalkCon, data->telemUAVTalkCon, serial_data, bytes_to_process);
|
||||
}
|
||||
} else {
|
||||
vTaskDelay(5);
|
||||
@ -427,7 +438,8 @@ static void radioRxTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Receive telemetry from the USB/COM port.
|
||||
* @brief Reads data from the GCS telemetry port and processes it
|
||||
* through the GCS->Radio telemetry stream.
|
||||
*
|
||||
* @param[in] parameters The task parameters
|
||||
*/
|
||||
@ -435,14 +447,15 @@ static void telemetryRxTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
// Task loop
|
||||
while (1) {
|
||||
uint32_t inputPort = data->parseUAVTalk ? PIOS_COM_TELEMETRY : 0;
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// uint32_t inputPort = data->parseUAVTalk ? PIOS_COM_TELEMETRY : 0;
|
||||
uint32_t inputPort = PIOS_COM_GCS;
|
||||
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_TELEMETRYRX)
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_TELEMETRYRX);
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
// Determine output port (USB takes priority over telemetry port)
|
||||
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB_HID) {
|
||||
inputPort = PIOS_COM_TELEM_USB_HID;
|
||||
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_HID) {
|
||||
inputPort = PIOS_COM_HID;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
if (inputPort) {
|
||||
@ -458,73 +471,7 @@ static void telemetryRxTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Reads the PPM input device and sends out OPLinkReceiver objects.
|
||||
*
|
||||
* @param[in] parameters The task parameters (unused)
|
||||
*/
|
||||
static void PPMInputTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
xSemaphoreHandle sem = PIOS_RCVR_GetSemaphore(PIOS_PPM_RECEIVER, 1);
|
||||
int16_t channels[RFM22B_PPM_NUM_CHANNELS];
|
||||
|
||||
while (1) {
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_PPMINPUT);
|
||||
#endif
|
||||
|
||||
// Wait for the receiver semaphore.
|
||||
if (xSemaphoreTake(sem, PPM_INPUT_TIMEOUT) == pdTRUE) {
|
||||
// Read the receiver inputs.
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
|
||||
channels[i] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i + 1);
|
||||
}
|
||||
} else {
|
||||
// Failsafe
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
|
||||
channels[i] = PIOS_RCVR_INVALID;
|
||||
}
|
||||
}
|
||||
|
||||
// Pass the channel values to the radio device.
|
||||
PIOS_RFM22B_PPMSet(pios_rfm22b_id, channels, RFM22B_PPM_NUM_CHANNELS);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Receive raw serial data from the USB/COM port.
|
||||
*
|
||||
* @param[in] parameters The task parameters
|
||||
*/
|
||||
static void serialRxTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
// Task loop
|
||||
while (1) {
|
||||
uint32_t inputPort = PIOS_COM_TELEMETRY;
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_SERIALRX);
|
||||
#endif
|
||||
if (inputPort && PIOS_COM_RADIO) {
|
||||
// Receive some data.
|
||||
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(inputPort, data->serialRxBuf, sizeof(data->serialRxBuf), MAX_PORT_DELAY);
|
||||
|
||||
if (bytes_to_process > 0) {
|
||||
// Send the data over the radio link.
|
||||
// Following call can fail with -2 error code (buffer full) or -3 error code (could not acquire send mutex)
|
||||
// It is the caller responsibility to retry in such cases...
|
||||
int32_t ret = -2;
|
||||
uint8_t count = 5;
|
||||
while (count-- > 0 && ret < -1) {
|
||||
ret = PIOS_COM_SendBufferNonBlocking(PIOS_COM_RADIO, data->serialRxBuf, bytes_to_process);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
vTaskDelay(5);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Transmit data buffer to the com port.
|
||||
* @brief Send data from the Radio->GCS telemetry stream to the GCS port.
|
||||
*
|
||||
* @param[in] buf Data buffer to send
|
||||
* @param[in] length Length of buffer
|
||||
@ -534,12 +481,12 @@ static void serialRxTask(__attribute__((unused)) void *parameters)
|
||||
static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length)
|
||||
{
|
||||
int32_t ret;
|
||||
uint32_t outputPort = data->parseUAVTalk ? PIOS_COM_TELEMETRY : 0;
|
||||
uint32_t outputPort = PIOS_COM_GCS;
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
// Determine output port (USB takes priority over telemetry port)
|
||||
if (PIOS_COM_TELEM_USB_HID && PIOS_COM_Available(PIOS_COM_TELEM_USB_HID)) {
|
||||
outputPort = PIOS_COM_TELEM_USB_HID;
|
||||
if (PIOS_COM_HID && PIOS_COM_Available(PIOS_COM_HID)) {
|
||||
outputPort = PIOS_COM_HID;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
if (outputPort) {
|
||||
@ -557,7 +504,7 @@ static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length)
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmit data buffer to the com port.
|
||||
* @brief Send data from the GCS telemetry stream to the Radio->GCS port.
|
||||
*
|
||||
* @param[in] buf Data buffer to send
|
||||
* @param[in] length Length of buffer
|
||||
@ -566,10 +513,7 @@ static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length)
|
||||
*/
|
||||
static int32_t RadioSendHandler(uint8_t *buf, int32_t length)
|
||||
{
|
||||
if (!data->parseUAVTalk) {
|
||||
return length;
|
||||
}
|
||||
uint32_t outputPort = PIOS_COM_RADIO;
|
||||
uint32_t outputPort = PIOS_COM_GCS_OUT;
|
||||
|
||||
// Don't send any data unless the radio port is available.
|
||||
if (outputPort && PIOS_COM_Available(outputPort)) {
|
||||
|
@ -808,6 +808,44 @@ int32_t PIOS_COM_RegisterAvailableCallback(uint32_t com_id, pios_com_callback_av
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* Callback used to pass data from one ocm port to another in PIOS_COM_LinkComPare.
|
||||
* \param[in] context The "to" com port
|
||||
* \param[in] buf The data buffer
|
||||
* \param[in] buf_len The number of bytes received
|
||||
* \param[in] headroom Not used
|
||||
* \param[in] task_woken Not used
|
||||
*/
|
||||
static uint16_t PIOS_COM_LinkComPairRxCallback(uint32_t context, uint8_t *buf, uint16_t buf_len, __attribute__((unused)) uint16_t *headroom, __attribute__((unused)) bool *task_woken)
|
||||
{
|
||||
int32_t sent = PIOS_COM_SendBufferNonBlocking(context, buf, buf_len);
|
||||
|
||||
if (sent > 0) {
|
||||
return sent;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* Link a pair of com ports so that any data arriving on one is sent out the other.
|
||||
* \param[in] com1_id The first com port
|
||||
* \param[in] com2_id The second com port
|
||||
*/
|
||||
void PIOS_COM_LinkComPair(uint32_t com1_id, uint32_t com2_id, bool link_ctrl_line, bool link_baud_rate)
|
||||
{
|
||||
PIOS_COM_ASYNC_RegisterRxCallback(com1_id, PIOS_COM_LinkComPairRxCallback, com2_id);
|
||||
PIOS_COM_ASYNC_RegisterRxCallback(com2_id, PIOS_COM_LinkComPairRxCallback, com1_id);
|
||||
// Optionally link the control like and baudrate changes between the two.
|
||||
if (link_ctrl_line) {
|
||||
PIOS_COM_RegisterCtrlLineCallback(com1_id, (pios_com_callback_ctrl_line)PIOS_COM_SetCtrlLine, com2_id);
|
||||
PIOS_COM_RegisterCtrlLineCallback(com2_id, (pios_com_callback_ctrl_line)PIOS_COM_SetCtrlLine, com1_id);
|
||||
}
|
||||
if (link_baud_rate) {
|
||||
PIOS_COM_RegisterBaudRateCallback(com1_id, (pios_com_callback_baud_rate)PIOS_COM_ChangeBaud, com2_id);
|
||||
PIOS_COM_RegisterBaudRateCallback(com2_id, (pios_com_callback_baud_rate)PIOS_COM_ChangeBaud, com1_id);
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
/**
|
||||
|
@ -808,9 +808,8 @@ bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, uint8_t *p, uint8_t len)
|
||||
return false;
|
||||
}
|
||||
|
||||
rfm22b_dev->tx_packet_handle = p;
|
||||
rfm22b_dev->stats.tx_byte_count += len;
|
||||
rfm22b_dev->packet_start_ticks = xTaskGetTickCount();
|
||||
rfm22b_dev->tx_packet_handle = p;
|
||||
rfm22b_dev->packet_start_ticks = xTaskGetTickCount();
|
||||
if (rfm22b_dev->packet_start_ticks == 0) {
|
||||
rfm22b_dev->packet_start_ticks = 1;
|
||||
}
|
||||
@ -873,8 +872,6 @@ bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, uint8_t *p, uint8_t len)
|
||||
// We're in Tx mode.
|
||||
rfm22b_dev->rfm22b_state = RFM22B_STATE_TX_MODE;
|
||||
|
||||
TX_LED_ON;
|
||||
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
D1_LED_ON;
|
||||
#endif
|
||||
@ -1925,6 +1922,12 @@ static enum pios_radio_event radio_txStart(struct pios_rfm22b_dev *radio_dev)
|
||||
len += RS_ECC_NPARITY;
|
||||
}
|
||||
|
||||
// Only count the packet if it contains valid data.
|
||||
if (radio_dev->ppm_only_mode || (len > RS_ECC_NPARITY)) {
|
||||
TX_LED_ON;
|
||||
radio_dev->stats.tx_byte_count += len;
|
||||
}
|
||||
|
||||
// Transmit the packet.
|
||||
PIOS_RFM22B_TransmitPacket((uint32_t)radio_dev, p, len);
|
||||
|
||||
|
@ -115,6 +115,8 @@ extern int32_t PIOS_COM_ASYNC_RxStart(uint32_t id, uint16_t rx_bytes_avail);
|
||||
extern int32_t PIOS_COM_ASYNC_RegisterRxCallback(uint32_t id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
extern int32_t PIOS_COM_ASYNC_RegisterTxCallback(uint32_t id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
|
||||
extern void PIOS_COM_LinkComPair(uint32_t com1_id, uint32_t com2_id, bool link_ctrl_line, bool link_baud_rate);
|
||||
|
||||
#define COM_AVAILABLE_NONE (0)
|
||||
#define COM_AVAILABLE_RX (1 << 0)
|
||||
#define COM_AVAILABLE_TX (1 << 1)
|
||||
|
@ -691,7 +691,7 @@ const struct pios_ppm_out_cfg pios_flexi_ppm_out_cfg = {
|
||||
/*
|
||||
* SERIAL USART
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_serial_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
@ -727,7 +727,7 @@ static const struct pios_usart_cfg pios_usart_serial_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_telem_flexi_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
|
@ -56,6 +56,8 @@ uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS
|
||||
////////////////////////////////////////
|
||||
uint8_t tempcount = 0;
|
||||
|
||||
extern uint32_t pios_com_telem_usb_id;
|
||||
|
||||
/* Extern variables ----------------------------------------------------------*/
|
||||
DFUStates DeviceState;
|
||||
int16_t status = 0;
|
||||
@ -211,7 +213,7 @@ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count)
|
||||
|
||||
uint8_t processRX()
|
||||
{
|
||||
if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) {
|
||||
if (PIOS_COM_MSG_Receive(pios_com_telem_usb_id, mReceive_Buffer, sizeof(mReceive_Buffer))) {
|
||||
processComand(mReceive_Buffer);
|
||||
}
|
||||
return TRUE;
|
||||
@ -219,5 +221,5 @@ uint8_t processRX()
|
||||
|
||||
int32_t platform_senddata(const uint8_t *msg, uint16_t msg_len)
|
||||
{
|
||||
return PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, msg, msg_len);
|
||||
return PIOS_COM_MSG_Send(pios_com_telem_usb_id, msg, msg_len);
|
||||
}
|
||||
|
@ -31,7 +31,7 @@ override USE_DSP_LIB := NO
|
||||
MODULES += RadioComBridge
|
||||
|
||||
# List of optional modules to include
|
||||
OPTMODULES = ComUsbBridge
|
||||
OPTMODULES =
|
||||
|
||||
# List C source files here (C dependencies are automatically generated).
|
||||
# Use file-extension c for "c-only"-files
|
||||
|
@ -146,26 +146,20 @@
|
||||
/* #define PIOS_QUATERNION_STABILIZATION */
|
||||
|
||||
/* Performance counters */
|
||||
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998
|
||||
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998
|
||||
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 220
|
||||
#define HEAP_LIMIT_CRITICAL 40
|
||||
#define IRQSTACK_LIMIT_WARNING 100
|
||||
#define IRQSTACK_LIMIT_CRITICAL 60
|
||||
#define CPULOAD_LIMIT_WARNING 85
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
#define HEAP_LIMIT_WARNING 220
|
||||
#define HEAP_LIMIT_CRITICAL 40
|
||||
#define IRQSTACK_LIMIT_WARNING 100
|
||||
#define IRQSTACK_LIMIT_CRITICAL 60
|
||||
#define CPULOAD_LIMIT_WARNING 85
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
/* Task stack sizes */
|
||||
#define PIOS_ACTUATOR_STACK_SIZE 1020
|
||||
#define PIOS_MANUAL_STACK_SIZE 724
|
||||
#define PIOS_SYSTEM_STACK_SIZE 460
|
||||
#define PIOS_STABILIZATION_STACK_SIZE 524
|
||||
#define PIOS_TELEM_STACK_SIZE 800
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 130
|
||||
|
||||
/* This can't be too high to stop eventdispatcher thread overflowing */
|
||||
#define PIOS_EVENTDISAPTCHER_QUEUE 10
|
||||
#define PIOS_EVENTDISAPTCHER_QUEUE 10
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
|
@ -48,43 +48,44 @@
|
||||
*/
|
||||
#include "../board_hw_defs.c"
|
||||
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 256
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 256
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 128
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 128
|
||||
|
||||
#define PIOS_COM_TELEM_VCP_RX_BUF_LEN 256
|
||||
#define PIOS_COM_TELEM_VCP_TX_BUF_LEN 256
|
||||
#define PIOS_COM_TELEM_VCP_RX_BUF_LEN 128
|
||||
#define PIOS_COM_TELEM_VCP_TX_BUF_LEN 128
|
||||
|
||||
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 256
|
||||
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 256
|
||||
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 128
|
||||
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 128
|
||||
|
||||
#define PIOS_COM_TELEM_RX_BUF_LEN 256
|
||||
#define PIOS_COM_TELEM_TX_BUF_LEN 256
|
||||
#define PIOS_COM_TELEM_RX_BUF_LEN 128
|
||||
#define PIOS_COM_TELEM_TX_BUF_LEN 128
|
||||
|
||||
uint32_t pios_com_telem_usb_id = 0;
|
||||
uint32_t pios_com_telem_vcp_id = 0;
|
||||
uint32_t pios_com_telem_uart_main_id = 0;
|
||||
uint32_t pios_com_telem_uart_flexi_id = 0;
|
||||
uint32_t pios_com_telemetry_id = 0;
|
||||
uint32_t pios_com_bridge_id = 0;
|
||||
uint32_t pios_com_vcp_id = 0;
|
||||
uint32_t pios_com_hid_id = 0;
|
||||
uint32_t pios_com_vcp_id = 0;
|
||||
uint32_t pios_com_main_id = 0;
|
||||
uint32_t pios_com_flexi_id = 0;
|
||||
uint32_t pios_com_bridge_id = 0;
|
||||
uint32_t pios_com_gcs_id = 0;
|
||||
uint32_t pios_com_gcs_out_id = 0;
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
uint32_t pios_ppm_rcvr_id = 0;
|
||||
uint32_t pios_ppm_rcvr_id = 0;
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_PPM_OUT)
|
||||
uint32_t pios_ppm_out_id = 0;
|
||||
uint32_t pios_ppm_out_id = 0;
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
#include <pios_rfm22b_com.h>
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
uint32_t pios_com_rfm22b_id = 0;
|
||||
uint32_t pios_com_radio_id = 0;
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
uint32_t pios_com_pri_radio_id = 0;
|
||||
uint32_t pios_com_aux_radio_id = 0;
|
||||
uint32_t pios_com_pri_radio_out_id = 0;
|
||||
uint32_t pios_com_aux_radio_out_id = 0;
|
||||
#endif
|
||||
|
||||
|
||||
uintptr_t pios_uavo_settings_fs_id;
|
||||
uintptr_t pios_user_fs_id = 0;
|
||||
uintptr_t pios_user_fs_id = 0;
|
||||
|
||||
uint8_t servo_count = 0;
|
||||
static uint8_t servo_count = 0;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes.
|
||||
@ -188,6 +189,22 @@ void PIOS_Board_Init(void)
|
||||
OPLinkStatusInitialize();
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
/* Retrieve the settings object. */
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
OPLinkSettingsGet(&oplinkSettings);
|
||||
|
||||
/* Determine the modem protocols */
|
||||
bool is_coordinator = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPLINKCOORDINATOR);
|
||||
bool openlrs = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPENLRS);
|
||||
bool ppm_only = (oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL);
|
||||
bool data_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATA) ||
|
||||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
|
||||
bool is_enabled = ((oplinkSettings.Protocol != OPLINKSETTINGS_PROTOCOL_DISABLED) &&
|
||||
((oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) || openlrs));
|
||||
bool ppm_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL) ||
|
||||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
|
||||
bool servo_main = false;
|
||||
bool servo_flexi = false;
|
||||
|
||||
#if defined(PIOS_INCLUDE_TIM)
|
||||
/* Set up pulse timers */
|
||||
@ -229,7 +246,7 @@ void PIOS_Board_Init(void)
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
|
||||
if (PIOS_COM_Init(&pios_com_hid_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
|
||||
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
@ -247,7 +264,7 @@ void PIOS_Board_Init(void)
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_VCP_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_TELEM_VCP_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_VCP_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
@ -256,40 +273,40 @@ void PIOS_Board_Init(void)
|
||||
#endif
|
||||
|
||||
// Configure the main port
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
OPLinkSettingsGet(&oplinkSettings);
|
||||
bool is_coordinator = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPLINKCOORDINATOR);
|
||||
bool openlrs = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPENLRS);
|
||||
bool ppm_only = (oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL);
|
||||
bool data_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATA) ||
|
||||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
|
||||
bool is_enabled = ((oplinkSettings.Protocol != OPLINKSETTINGS_PROTOCOL_DISABLED) &&
|
||||
((oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) || openlrs));
|
||||
bool ppm_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL) ||
|
||||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
|
||||
bool servo_main = false;
|
||||
bool servo_flexi = false;
|
||||
uint32_t mainComSpeed = 0;
|
||||
switch (oplinkSettings.MainComSpeed) {
|
||||
case OPLINKSETTINGS_MAINCOMSPEED_4800:
|
||||
mainComSpeed = 4800;
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINCOMSPEED_9600:
|
||||
mainComSpeed = 9600;
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINCOMSPEED_19200:
|
||||
mainComSpeed = 19200;
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINCOMSPEED_38400:
|
||||
mainComSpeed = 38400;
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINCOMSPEED_57600:
|
||||
mainComSpeed = 57600;
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINCOMSPEED_115200:
|
||||
mainComSpeed = 115200;
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINCOMSPEED_DISABLED:
|
||||
break;
|
||||
}
|
||||
switch (oplinkSettings.MainPort) {
|
||||
case OPLINKSETTINGS_MAINPORT_TELEMETRY:
|
||||
case OPLINKSETTINGS_MAINPORT_SERIAL:
|
||||
{
|
||||
/* Configure the main port for uart serial */
|
||||
#ifndef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
PIOS_Board_configure_com(&pios_usart_serial_cfg,
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg,
|
||||
PIOS_COM_TELEM_RX_BUF_LEN, PIOS_COM_TELEM_TX_BUF_LEN,
|
||||
&pios_usart_com_driver, &pios_com_telem_uart_main_id);
|
||||
|
||||
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_MAIN;
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
case OPLINKSETTINGS_MAINPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_serial_cfg,
|
||||
PIOS_COM_TELEM_RX_BUF_LEN, PIOS_COM_TELEM_TX_BUF_LEN,
|
||||
&pios_usart_com_driver, &pios_com_bridge_id);
|
||||
&pios_usart_com_driver, &pios_com_main_id);
|
||||
PIOS_COM_ChangeBaud(pios_com_main_id, mainComSpeed);
|
||||
#endif /* !PIOS_RFM22B_DEBUG_ON_TELEM */
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINPORT_PPM:
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
/* PPM input is configured on the coordinator modem and output on the remote modem. */
|
||||
if (is_coordinator) {
|
||||
@ -308,35 +325,47 @@ void PIOS_Board_Init(void)
|
||||
#endif /* PIOS_INCLUDE_PPM_OUT */
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
break;
|
||||
}
|
||||
case OPLINKSETTINGS_MAINPORT_PWM:
|
||||
servo_main = true;
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINPORT_DISABLED:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
// Configure the flexi port
|
||||
uint32_t flexiComSpeed = 0;
|
||||
switch (oplinkSettings.FlexiComSpeed) {
|
||||
case OPLINKSETTINGS_FLEXICOMSPEED_4800:
|
||||
flexiComSpeed = 4800;
|
||||
break;
|
||||
case OPLINKSETTINGS_FLEXICOMSPEED_9600:
|
||||
flexiComSpeed = 9600;
|
||||
break;
|
||||
case OPLINKSETTINGS_FLEXICOMSPEED_19200:
|
||||
flexiComSpeed = 19200;
|
||||
break;
|
||||
case OPLINKSETTINGS_FLEXICOMSPEED_38400:
|
||||
flexiComSpeed = 38400;
|
||||
break;
|
||||
case OPLINKSETTINGS_FLEXICOMSPEED_57600:
|
||||
flexiComSpeed = 57600;
|
||||
break;
|
||||
case OPLINKSETTINGS_FLEXICOMSPEED_115200:
|
||||
flexiComSpeed = 115200;
|
||||
break;
|
||||
case OPLINKSETTINGS_FLEXICOMSPEED_DISABLED:
|
||||
break;
|
||||
}
|
||||
switch (oplinkSettings.FlexiPort) {
|
||||
case OPLINKSETTINGS_FLEXIPORT_TELEMETRY:
|
||||
case OPLINKSETTINGS_FLEXIPORT_SERIAL:
|
||||
{
|
||||
/* Configure the flexi port as uart serial */
|
||||
PIOS_Board_configure_com(&pios_usart_telem_flexi_cfg,
|
||||
#ifndef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg,
|
||||
PIOS_COM_TELEM_RX_BUF_LEN, PIOS_COM_TELEM_TX_BUF_LEN,
|
||||
&pios_usart_com_driver,
|
||||
&pios_com_telem_uart_flexi_id);
|
||||
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_FLEXI;
|
||||
break;
|
||||
}
|
||||
case OPLINKSETTINGS_FLEXIPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_telem_flexi_cfg,
|
||||
PIOS_COM_TELEM_RX_BUF_LEN, PIOS_COM_TELEM_TX_BUF_LEN,
|
||||
&pios_usart_com_driver,
|
||||
&pios_com_bridge_id);
|
||||
&pios_usart_com_driver, &pios_com_flexi_id);
|
||||
PIOS_COM_ChangeBaud(pios_com_flexi_id, flexiComSpeed);
|
||||
#endif /* !PIOS_RFM22B_DEBUG_ON_TELEM */
|
||||
break;
|
||||
case OPLINKSETTINGS_FLEXIPORT_PPM:
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
/* PPM input is configured on the coordinator modem and output on the remote modem. */
|
||||
if (is_coordinator) {
|
||||
@ -346,31 +375,22 @@ void PIOS_Board_Init(void)
|
||||
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
} else {
|
||||
}
|
||||
// For some reason, PPM output on the flexi port doesn't work.
|
||||
#if defined(PIOS_INCLUDE_PPM_OUT)
|
||||
else {
|
||||
PIOS_PPM_Out_Init(&pios_ppm_out_id, &pios_flexi_ppm_out_cfg);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PPM_OUT */
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
break;
|
||||
}
|
||||
case OPLINKSETTINGS_FLEXIPORT_PWM:
|
||||
servo_flexi = true;
|
||||
break;
|
||||
case OPLINKSETTINGS_FLEXIPORT_DISABLED:
|
||||
break;
|
||||
}
|
||||
|
||||
// Configure the USB VCP port
|
||||
switch (oplinkSettings.VCPPort) {
|
||||
case OPLINKSETTINGS_VCPPORT_SERIAL:
|
||||
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_USB_VCP;
|
||||
break;
|
||||
case OPLINKSETTINGS_VCPPORT_COMBRIDGE:
|
||||
PIOS_COM_VCP = PIOS_COM_TELEM_USB_VCP;
|
||||
break;
|
||||
case OPLINKSETTINGS_VCPPORT_DISABLED:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
/* Configure the PWM servo outputs. */
|
||||
#if defined(PIOS_INCLUDE_SERVO)
|
||||
if (servo_main) {
|
||||
if (servo_flexi) {
|
||||
@ -429,33 +449,53 @@ void PIOS_Board_Init(void)
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_rfm22b_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
|
||||
if (PIOS_COM_Init(&pios_com_pri_radio_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
|
||||
rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
|
||||
// Initialize the aux radio com interface
|
||||
uint8_t *auxrx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_RX_BUF_LEN);
|
||||
uint8_t *auxtx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_TX_BUF_LEN);
|
||||
PIOS_Assert(auxrx_buffer);
|
||||
PIOS_Assert(auxtx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_aux_radio_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
|
||||
auxrx_buffer, PIOS_COM_TELEM_RX_BUF_LEN,
|
||||
auxtx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
// Set the modem (over the air) datarate.
|
||||
enum rfm22b_datarate datarate = RFM22_datarate_64000;
|
||||
switch (oplinkSettings.ComSpeed) {
|
||||
case OPLINKSETTINGS_COMSPEED_4800:
|
||||
switch (oplinkSettings.AirDataRate) {
|
||||
case OPLINKSETTINGS_AIRDATARATE_9600:
|
||||
datarate = RFM22_datarate_9600;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_9600:
|
||||
case OPLINKSETTINGS_AIRDATARATE_19200:
|
||||
datarate = RFM22_datarate_19200;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_19200:
|
||||
case OPLINKSETTINGS_AIRDATARATE_32000:
|
||||
datarate = RFM22_datarate_32000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_38400:
|
||||
case OPLINKSETTINGS_AIRDATARATE_57600:
|
||||
datarate = RFM22_datarate_57600;
|
||||
break;
|
||||
case OPLINKSETTINGS_AIRDATARATE_64000:
|
||||
datarate = RFM22_datarate_64000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_57600:
|
||||
case OPLINKSETTINGS_AIRDATARATE_100000:
|
||||
datarate = RFM22_datarate_100000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_115200:
|
||||
case OPLINKSETTINGS_AIRDATARATE_128000:
|
||||
datarate = RFM22_datarate_128000;
|
||||
break;
|
||||
case OPLINKSETTINGS_AIRDATARATE_192000:
|
||||
datarate = RFM22_datarate_192000;
|
||||
break;
|
||||
case OPLINKSETTINGS_AIRDATARATE_256000:
|
||||
datarate = RFM22_datarate_256000;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Set the modem Tx power level */
|
||||
@ -499,61 +539,92 @@ void PIOS_Board_Init(void)
|
||||
if (ppm_mode || (ppm_only && !is_coordinator)) {
|
||||
PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback, 0);
|
||||
}
|
||||
|
||||
// Reinitialize the modem to affect the changes.
|
||||
PIOS_RFM22B_Reinit(pios_rfm22b_id);
|
||||
uint8_t oplinksettings_radioaux;
|
||||
OPLinkSettingsRadioAuxStreamGet(&oplinksettings_radioaux);
|
||||
switch (oplinksettings_radioaux) {
|
||||
case OPLINKSETTINGS_RADIOAUXSTREAM_DISABLED:
|
||||
break;
|
||||
case OPLINKSETTINGS_RADIOAUXSTREAM_COMBRIDGE:
|
||||
{
|
||||
uint8_t *auxrx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_RX_BUF_LEN);
|
||||
uint8_t *auxtx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_TX_BUF_LEN);
|
||||
PIOS_Assert(auxrx_buffer);
|
||||
PIOS_Assert(auxtx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_bridge_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
|
||||
auxrx_buffer, PIOS_COM_TELEM_RX_BUF_LEN,
|
||||
auxtx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
} // openlrs
|
||||
} else {
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
|
||||
}
|
||||
|
||||
// Configure the primary radio stream destination.
|
||||
switch (oplinkSettings.RadioPriStream) {
|
||||
case OPLINKSETTINGS_RADIOPRISTREAM_DISABLED:
|
||||
break;
|
||||
case OPLINKSETTINGS_RADIOPRISTREAM_HID:
|
||||
// HID is always connected to GCS
|
||||
pios_com_gcs_id = pios_com_hid_id;
|
||||
pios_com_gcs_out_id = pios_com_pri_radio_id;
|
||||
break;
|
||||
case OPLINKSETTINGS_RADIOPRISTREAM_MAIN:
|
||||
// Is the main port configured for telemetry (GCS)?
|
||||
if (oplinkSettings.MainPort == OPLINKSETTINGS_MAINPORT_TELEMETRY) {
|
||||
pios_com_gcs_id = pios_com_main_id;
|
||||
pios_com_gcs_out_id = pios_com_pri_radio_id;
|
||||
} else {
|
||||
PIOS_COM_LinkComPair(pios_com_pri_radio_id, pios_com_main_id, false, false);
|
||||
}
|
||||
break;
|
||||
case OPLINKSETTINGS_RADIOPRISTREAM_FLEXI:
|
||||
// Is the flexi port configured for telemetry (GCS)?
|
||||
if (oplinkSettings.FlexiPort == OPLINKSETTINGS_FLEXIPORT_TELEMETRY) {
|
||||
pios_com_gcs_id = pios_com_flexi_id;
|
||||
pios_com_gcs_out_id = pios_com_pri_radio_id;
|
||||
} else {
|
||||
PIOS_COM_LinkComPair(pios_com_pri_radio_id, pios_com_flexi_id, false, false);
|
||||
}
|
||||
break;
|
||||
case OPLINKSETTINGS_RADIOPRISTREAM_VCP:
|
||||
// VCP is never connected to GCS
|
||||
PIOS_COM_LinkComPair(pios_com_pri_radio_id, pios_com_vcp_id, false, false);
|
||||
break;
|
||||
}
|
||||
|
||||
// Configure the Auxiliary radio stream destination.
|
||||
switch (oplinkSettings.RadioAuxStream) {
|
||||
case OPLINKSETTINGS_RADIOAUXSTREAM_DISABLED:
|
||||
break;
|
||||
case OPLINKSETTINGS_RADIOAUXSTREAM_HID:
|
||||
// HID is always connected to GCS
|
||||
pios_com_gcs_id = pios_com_hid_id;
|
||||
pios_com_gcs_out_id = pios_com_aux_radio_id;
|
||||
break;
|
||||
case OPLINKSETTINGS_RADIOAUXSTREAM_MAIN:
|
||||
// Is the main port configured for telemetry (GCS)?
|
||||
if (oplinkSettings.MainPort == OPLINKSETTINGS_MAINPORT_TELEMETRY) {
|
||||
pios_com_gcs_id = pios_com_main_id;
|
||||
pios_com_gcs_out_id = pios_com_aux_radio_id;
|
||||
} else {
|
||||
PIOS_COM_LinkComPair(pios_com_aux_radio_id, pios_com_main_id, false, false);
|
||||
}
|
||||
break;
|
||||
case OPLINKSETTINGS_RADIOAUXSTREAM_FLEXI:
|
||||
// Is the flexi port configured for telemetry (GCS)?
|
||||
if (oplinkSettings.FlexiPort == OPLINKSETTINGS_FLEXIPORT_TELEMETRY) {
|
||||
pios_com_gcs_id = pios_com_flexi_id;
|
||||
pios_com_gcs_out_id = pios_com_aux_radio_id;
|
||||
} else {
|
||||
PIOS_COM_LinkComPair(pios_com_aux_radio_id, pios_com_flexi_id, false, false);
|
||||
}
|
||||
break;
|
||||
case OPLINKSETTINGS_RADIOAUXSTREAM_VCP:
|
||||
// VCP is never connected to GCS
|
||||
PIOS_COM_LinkComPair(pios_com_aux_radio_id, pios_com_vcp_id, false, false);
|
||||
break;
|
||||
}
|
||||
|
||||
// Configure the VCP COM bridge
|
||||
switch (oplinkSettings.VCPBridge) {
|
||||
case OPLINKSETTINGS_VCPBRIDGE_MAIN:
|
||||
PIOS_COM_LinkComPair(pios_com_vcp_id, pios_com_main_id, true, true);
|
||||
break;
|
||||
case OPLINKSETTINGS_VCPBRIDGE_FLEXI:
|
||||
PIOS_COM_LinkComPair(pios_com_vcp_id, pios_com_flexi_id, true, true);
|
||||
break;
|
||||
case OPLINKSETTINGS_VCPBRIDGE_DISABLED:
|
||||
break;
|
||||
}
|
||||
|
||||
// Update the object
|
||||
OPLinkStatusSet(&oplinkStatus);
|
||||
|
||||
// Update the com baud rate.
|
||||
uint32_t comBaud = 9600;
|
||||
switch (oplinkSettings.ComSpeed) {
|
||||
case OPLINKSETTINGS_COMSPEED_4800:
|
||||
comBaud = 4800;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_9600:
|
||||
comBaud = 9600;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_19200:
|
||||
comBaud = 19200;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_38400:
|
||||
comBaud = 38400;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_57600:
|
||||
comBaud = 57600;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_115200:
|
||||
comBaud = 115200;
|
||||
break;
|
||||
}
|
||||
if (PIOS_COM_TELEMETRY) {
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, comBaud);
|
||||
}
|
||||
|
||||
/* Remap AFIO pin */
|
||||
GPIO_PinRemapConfig(GPIO_Remap_SWJ_NoJTRST, ENABLE);
|
||||
|
||||
|
@ -73,11 +73,10 @@
|
||||
#define PIOS_WDG_REGISTER BKP_DR4
|
||||
#define PIOS_WDG_TELEMETRYTX 0x0001
|
||||
#define PIOS_WDG_TELEMETRYRX 0x0002
|
||||
#define PIOS_WDG_RADIOTX 0x0004
|
||||
#define PIOS_WDG_RADIORX 0x0008
|
||||
#define PIOS_WDG_TELEMRADIOTX 0x0004
|
||||
#define PIOS_WDG_TELEMRADIORX 0x0008
|
||||
#define PIOS_WDG_RFM22B 0x000f
|
||||
#define PIOS_WDG_PPMINPUT 0x0010
|
||||
#define PIOS_WDG_SERIALRX 0x0020
|
||||
|
||||
// ------------------------
|
||||
// TELEMETRY
|
||||
@ -174,30 +173,40 @@ extern uint32_t pios_i2c_flexi_adapter_id;
|
||||
// -------------------------
|
||||
#define PIOS_COM_MAX_DEVS 5
|
||||
|
||||
extern uint32_t pios_com_telem_usb_id;
|
||||
extern uint32_t pios_com_telem_vcp_id;
|
||||
extern uint32_t pios_com_telem_uart_main_id;
|
||||
extern uint32_t pios_com_telem_uart_flexi_id;
|
||||
extern uint32_t pios_com_telemetry_id;
|
||||
extern uint32_t pios_com_rfm22b_id;
|
||||
extern uint32_t pios_com_radio_id;
|
||||
extern uint32_t pios_com_bridge_id;
|
||||
// The direct com ports
|
||||
extern uint32_t pios_com_hid_id;
|
||||
extern uint32_t pios_com_vcp_id;
|
||||
extern uint32_t pios_com_main_id;
|
||||
extern uint32_t pios_com_flexi_id;
|
||||
extern uint32_t pios_com_pri_radio_id;
|
||||
extern uint32_t pios_com_aux_radio_id;
|
||||
// The port that the GCS is connected to
|
||||
extern uint32_t pios_com_gcs_id;
|
||||
// The destination port from the GCS port
|
||||
extern uint32_t pios_com_gcs_out_id;
|
||||
// The destination port from the VCP com bridge
|
||||
extern uint32_t pios_com_bridge_id;
|
||||
// The destination port for the primary radio port
|
||||
extern uint32_t pios_com_pri_radio_out_id;
|
||||
// The destination port for the auxiliary radio port.
|
||||
extern uint32_t pios_com_aux_radio_out_id;
|
||||
// The PPM IDs
|
||||
extern uint32_t pios_ppm_rcvr_id;
|
||||
extern uint32_t pios_ppm_out_id;
|
||||
#define PIOS_COM_TELEM_USB_HID (pios_com_telem_usb_id)
|
||||
#define PIOS_COM_TELEM_USB PIOS_COM_TELEM_USB_HID
|
||||
#define PIOS_COM_TELEM_USB_VCP (pios_com_telem_vcp_id)
|
||||
#define PIOS_COM_VCP (pios_com_vcp_id)
|
||||
#define PIOS_COM_TELEM_UART_MAIN (pios_com_telem_uart_main_id)
|
||||
#define PIOS_COM_TELEM_UART_FLEXI (pios_com_telem_uart_flexi_id)
|
||||
#define PIOS_COM_TELEMETRY (pios_com_telemetry_id)
|
||||
#define PIOS_COM_RFM22B (pios_com_rfm22b_id)
|
||||
#define PIOS_COM_RADIO (pios_com_radio_id)
|
||||
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
|
||||
#define PIOS_PPM_RECEIVER (pios_ppm_rcvr_id)
|
||||
#define PIOS_PPM_OUTPUT (pios_ppm_out_id)
|
||||
#define RFM22_DEBUG 1
|
||||
#define PIOS_COM_HID (pios_com_hid_id)
|
||||
#define PIOS_COM_VCP (pios_com_vcp_id)
|
||||
#define PIOS_COM_MAIN (pios_com_main_id)
|
||||
#define PIOS_COM_FLEXI (pios_com_flexi_id)
|
||||
#define PIOS_COM_PRI_RADIO (pios_com_pri_radio_id)
|
||||
#define PIOS_COM_AUX_RADIO (pios_com_aux_radio_id)
|
||||
#define PIOS_COM_PRI_RADIO_OUT (pios_com_pri_radio_out_id)
|
||||
#define PIOS_COM_AUX_RADIO_OUT (pios_com_aux_radio_out_id)
|
||||
#define PIOS_COM_GCS (pios_com_gcs_id)
|
||||
#define PIOS_COM_GCS_OUT (pios_com_gcs_out_id)
|
||||
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
|
||||
#define PIOS_PPM_RECEIVER (pios_ppm_rcvr_id)
|
||||
#define PIOS_PPM_OUTPUT (pios_ppm_out_id)
|
||||
#define RFM22_DEBUG 1
|
||||
|
||||
// -------------------------
|
||||
// ADC
|
||||
|
@ -931,27 +931,36 @@ void PIOS_Board_Init(void)
|
||||
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
|
||||
|
||||
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
|
||||
// Set the modem (over the air) datarate.
|
||||
enum rfm22b_datarate datarate = RFM22_datarate_64000;
|
||||
switch (oplinkSettings.ComSpeed) {
|
||||
case OPLINKSETTINGS_COMSPEED_4800:
|
||||
switch (oplinkSettings.AirDataRate) {
|
||||
case OPLINKSETTINGS_AIRDATARATE_9600:
|
||||
datarate = RFM22_datarate_9600;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_9600:
|
||||
case OPLINKSETTINGS_AIRDATARATE_19200:
|
||||
datarate = RFM22_datarate_19200;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_19200:
|
||||
case OPLINKSETTINGS_AIRDATARATE_32000:
|
||||
datarate = RFM22_datarate_32000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_38400:
|
||||
case OPLINKSETTINGS_AIRDATARATE_57600:
|
||||
datarate = RFM22_datarate_57600;
|
||||
break;
|
||||
case OPLINKSETTINGS_AIRDATARATE_64000:
|
||||
datarate = RFM22_datarate_64000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_57600:
|
||||
case OPLINKSETTINGS_AIRDATARATE_100000:
|
||||
datarate = RFM22_datarate_100000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_115200:
|
||||
case OPLINKSETTINGS_AIRDATARATE_128000:
|
||||
datarate = RFM22_datarate_128000;
|
||||
break;
|
||||
case OPLINKSETTINGS_AIRDATARATE_192000:
|
||||
datarate = RFM22_datarate_192000;
|
||||
break;
|
||||
case OPLINKSETTINGS_AIRDATARATE_256000:
|
||||
datarate = RFM22_datarate_256000;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Set the radio configuration parameters. */
|
||||
|
@ -861,27 +861,36 @@ void PIOS_Board_Init(void)
|
||||
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
|
||||
|
||||
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
|
||||
// Set the modem (over the air) datarate.
|
||||
enum rfm22b_datarate datarate = RFM22_datarate_64000;
|
||||
switch (oplinkSettings.ComSpeed) {
|
||||
case OPLINKSETTINGS_COMSPEED_4800:
|
||||
switch (oplinkSettings.AirDataRate) {
|
||||
case OPLINKSETTINGS_AIRDATARATE_9600:
|
||||
datarate = RFM22_datarate_9600;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_9600:
|
||||
case OPLINKSETTINGS_AIRDATARATE_19200:
|
||||
datarate = RFM22_datarate_19200;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_19200:
|
||||
case OPLINKSETTINGS_AIRDATARATE_32000:
|
||||
datarate = RFM22_datarate_32000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_38400:
|
||||
case OPLINKSETTINGS_AIRDATARATE_57600:
|
||||
datarate = RFM22_datarate_57600;
|
||||
break;
|
||||
case OPLINKSETTINGS_AIRDATARATE_64000:
|
||||
datarate = RFM22_datarate_64000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_57600:
|
||||
case OPLINKSETTINGS_AIRDATARATE_100000:
|
||||
datarate = RFM22_datarate_100000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_115200:
|
||||
case OPLINKSETTINGS_AIRDATARATE_128000:
|
||||
datarate = RFM22_datarate_128000;
|
||||
break;
|
||||
case OPLINKSETTINGS_AIRDATARATE_192000:
|
||||
datarate = RFM22_datarate_192000;
|
||||
break;
|
||||
case OPLINKSETTINGS_AIRDATARATE_256000:
|
||||
datarate = RFM22_datarate_256000;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Set the radio configuration parameters. */
|
||||
|
@ -79,11 +79,14 @@ ConfigOPLinkWidget::ConfigOPLinkWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
addWidgetBinding("OPLinkSettings", "MinChannel", m_oplink->MinimumChannel);
|
||||
addWidgetBinding("OPLinkSettings", "MaxChannel", m_oplink->MaximumChannel);
|
||||
addWidgetBinding("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
|
||||
addWidgetBinding("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
|
||||
addWidgetBinding("OPLinkSettings", "MainPort", m_oplink->MainPort);
|
||||
addWidgetBinding("OPLinkSettings", "FlexiPort", m_oplink->FlexiPort);
|
||||
addWidgetBinding("OPLinkSettings", "VCPPort", m_oplink->VCPPort);
|
||||
addWidgetBinding("OPLinkSettings", "RadioAuxStream", m_oplink->RadioAuxPort);
|
||||
addWidgetBinding("OPLinkSettings", "RadioPriStream", m_oplink->RadioPriStream);
|
||||
addWidgetBinding("OPLinkSettings", "RadioAuxStream", m_oplink->RadioAuxStream);
|
||||
addWidgetBinding("OPLinkSettings", "VCPBridge", m_oplink->VCPBridge);
|
||||
addWidgetBinding("OPLinkSettings", "MainComSpeed", m_oplink->MainComSpeed);
|
||||
addWidgetBinding("OPLinkSettings", "FlexiComSpeed", m_oplink->FlexiComSpeed);
|
||||
addWidgetBinding("OPLinkSettings", "AirDataRate", m_oplink->AirDataRate);
|
||||
|
||||
addWidgetBinding("OPLinkSettings", "RFXtalCap", m_oplink->RFXtalCapValue);
|
||||
addWidgetBinding("OPLinkSettings", "RFXtalCap", m_oplink->RFXtalCapSlider);
|
||||
@ -121,7 +124,9 @@ ConfigOPLinkWidget::ConfigOPLinkWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
connect(m_oplink->MaximumChannel, SIGNAL(valueChanged(int)), this, SLOT(maxChannelChanged()));
|
||||
connect(m_oplink->MainPort, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged()));
|
||||
connect(m_oplink->FlexiPort, SIGNAL(currentIndexChanged(int)), this, SLOT(flexiPortChanged()));
|
||||
connect(m_oplink->VCPPort, SIGNAL(currentIndexChanged(int)), this, SLOT(vcpPortChanged()));
|
||||
connect(m_oplink->RadioPriStream, SIGNAL(currentIndexChanged(int)), this, SLOT(radioPriStreamChanged()));
|
||||
connect(m_oplink->RadioAuxStream, SIGNAL(currentIndexChanged(int)), this, SLOT(radioAuxStreamChanged()));
|
||||
connect(m_oplink->VCPBridge, SIGNAL(currentIndexChanged(int)), this, SLOT(vcpBridgeChanged()));
|
||||
|
||||
// Connect the Unbind button
|
||||
connect(m_oplink->UnbindButton, SIGNAL(released()), this, SLOT(unbind()));
|
||||
@ -203,14 +208,22 @@ void ConfigOPLinkWidget::updateStatus()
|
||||
|
||||
void ConfigOPLinkWidget::setPortsVisible(bool visible)
|
||||
{
|
||||
m_oplink->UartsLabel->setVisible(visible);
|
||||
m_oplink->MainPort->setVisible(visible);
|
||||
m_oplink->MainPortLabel->setVisible(visible);
|
||||
m_oplink->FlexiPort->setVisible(visible);
|
||||
m_oplink->FlexiPortLabel->setVisible(visible);
|
||||
m_oplink->VCPPort->setVisible(visible);
|
||||
m_oplink->VCPPortLabel->setVisible(visible);
|
||||
m_oplink->RadioAuxPort->setVisible(visible);
|
||||
m_oplink->RadioAuxPortLabel->setVisible(visible);
|
||||
m_oplink->ConnectionsLabel->setVisible(visible);
|
||||
m_oplink->RadioPriStream->setVisible(visible);
|
||||
m_oplink->RadioPriStreamLabel->setVisible(visible);
|
||||
m_oplink->RadioAuxStream->setVisible(visible);
|
||||
m_oplink->RadioAuxStreamLabel->setVisible(visible);
|
||||
m_oplink->MainComSpeed->setVisible(visible);
|
||||
m_oplink->MainComSpeedLabel->setVisible(visible);
|
||||
m_oplink->FlexiComSpeed->setVisible(visible);
|
||||
m_oplink->FlexiComSpeedLabel->setVisible(visible);
|
||||
m_oplink->VCPBridge->setVisible(visible);
|
||||
m_oplink->VCPBridgeLabel->setVisible(visible);
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::updateInfo()
|
||||
@ -255,30 +268,35 @@ void ConfigOPLinkWidget::updateSettings()
|
||||
{
|
||||
// qDebug() << "ConfigOPLinkWidget::updateSettings";
|
||||
|
||||
bool is_enabled = !isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_DISABLED);
|
||||
bool is_coordinator = isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_OPLINKCOORDINATOR);
|
||||
bool is_receiver = isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_OPLINKRECEIVER);
|
||||
bool is_openlrs = isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_OPENLRS);
|
||||
bool is_ppm_only = isComboboxOptionSelected(m_oplink->LinkType, OPLinkSettings::LINKTYPE_CONTROL);
|
||||
bool is_enabled = !isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_DISABLED);
|
||||
bool is_coordinator = isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_OPLINKCOORDINATOR);
|
||||
bool is_receiver = isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_OPLINKRECEIVER);
|
||||
bool is_openlrs = isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_OPENLRS);
|
||||
bool is_ppm_only = isComboboxOptionSelected(m_oplink->LinkType, OPLinkSettings::LINKTYPE_CONTROL);
|
||||
bool is_main_serial = isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_SERIAL);
|
||||
bool is_main_telem = isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_TELEMETRY);
|
||||
bool is_flexi_serial = isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_SERIAL);
|
||||
bool is_flexi_telem = isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_TELEMETRY);
|
||||
bool is_vcp_main = isComboboxOptionSelected(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_MAIN);
|
||||
bool is_vcp_flexi = isComboboxOptionSelected(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_FLEXI);
|
||||
bool is_bound = (m_oplink->CoordID->text() != "");
|
||||
|
||||
m_oplink->ComSpeed->setEnabled(is_enabled && !is_ppm_only && !is_openlrs);
|
||||
m_oplink->MainPort->setEnabled(is_enabled || is_vcp_main);
|
||||
m_oplink->FlexiPort->setEnabled(is_enabled || is_vcp_flexi);
|
||||
m_oplink->MainComSpeed->setEnabled((is_enabled || is_vcp_main) && !is_ppm_only && !is_openlrs && (is_main_serial || is_main_telem));
|
||||
m_oplink->FlexiComSpeed->setEnabled((is_enabled || is_vcp_flexi) && !is_ppm_only && !is_openlrs && (is_flexi_serial || is_flexi_telem));
|
||||
m_oplink->CoordID->setEnabled(is_enabled && is_receiver);
|
||||
m_oplink->UnbindButton->setEnabled(is_enabled && is_bound && !is_coordinator);
|
||||
m_oplink->CustomDeviceID->setEnabled(is_coordinator);
|
||||
|
||||
m_oplink->RadioAuxPort->setEnabled(is_receiver || is_coordinator);
|
||||
m_oplink->RadioPriStream->setEnabled((is_receiver || is_coordinator) && !is_ppm_only);
|
||||
m_oplink->RadioAuxStream->setEnabled((is_receiver || is_coordinator) && !is_ppm_only);
|
||||
|
||||
m_oplink->AirDataRate->setEnabled((is_receiver || is_coordinator) && !is_ppm_only);
|
||||
m_oplink->RFBand->setEnabled(is_receiver || is_coordinator);
|
||||
m_oplink->MinimumChannel->setEnabled(is_receiver || is_coordinator);
|
||||
m_oplink->MaximumChannel->setEnabled(is_receiver || is_coordinator);
|
||||
|
||||
enableComboBoxOptionItem(m_oplink->VCPPort, OPLinkSettings::VCPPORT_SERIAL, (is_receiver || is_coordinator));
|
||||
|
||||
if (isComboboxOptionSelected(m_oplink->VCPPort, OPLinkSettings::VCPPORT_SERIAL) && !(is_receiver || is_coordinator)) {
|
||||
setComboboxSelectedOption(m_oplink->VCPPort, OPLinkSettings::VCPPORT_DISABLED);
|
||||
}
|
||||
|
||||
m_oplink->LinkType->setEnabled(is_enabled && !is_openlrs);
|
||||
m_oplink->MaxRFTxPower->setEnabled(is_enabled && !is_openlrs);
|
||||
}
|
||||
@ -366,22 +384,28 @@ void ConfigOPLinkWidget::updateFrequencyDisplay()
|
||||
void ConfigOPLinkWidget::mainPortChanged()
|
||||
{
|
||||
switch (getComboboxSelectedOption(m_oplink->MainPort)) {
|
||||
case OPLinkSettings::MAINPORT_TELEMETRY:
|
||||
case OPLinkSettings::MAINPORT_SERIAL:
|
||||
if (isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_TELEMETRY)
|
||||
|| isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_SERIAL)) {
|
||||
setComboboxSelectedOption(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_DISABLED);
|
||||
}
|
||||
break;
|
||||
case OPLinkSettings::MAINPORT_COMBRIDGE:
|
||||
if (isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_DISABLED);
|
||||
}
|
||||
break;
|
||||
case OPLinkSettings::MAINPORT_PPM:
|
||||
if (isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_PPM)) {
|
||||
setComboboxSelectedOption(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_DISABLED);
|
||||
case OPLinkSettings::MAINPORT_PWM:
|
||||
case OPLinkSettings::MAINPORT_DISABLED:
|
||||
if (isComboboxOptionSelected(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_MAIN)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_MAIN)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_MAIN)) {
|
||||
setComboboxSelectedOption(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_DISABLED);
|
||||
}
|
||||
m_oplink->MainComSpeed->setEnabled(false);
|
||||
break;
|
||||
case OPLinkSettings::MAINPORT_TELEMETRY:
|
||||
if (isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_SERIAL);
|
||||
}
|
||||
case OPLinkSettings::MAINPORT_SERIAL:
|
||||
m_oplink->MainComSpeed->setEnabled(true);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -389,41 +413,161 @@ void ConfigOPLinkWidget::mainPortChanged()
|
||||
void ConfigOPLinkWidget::flexiPortChanged()
|
||||
{
|
||||
switch (getComboboxSelectedOption(m_oplink->FlexiPort)) {
|
||||
case OPLinkSettings::FLEXIPORT_TELEMETRY:
|
||||
case OPLinkSettings::FLEXIPORT_SERIAL:
|
||||
if (isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_TELEMETRY)
|
||||
|| isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_SERIAL)) {
|
||||
setComboboxSelectedOption(m_oplink->MainPort, OPLinkSettings::MAINPORT_DISABLED);
|
||||
}
|
||||
break;
|
||||
case OPLinkSettings::FLEXIPORT_COMBRIDGE:
|
||||
if (isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_oplink->MainPort, OPLinkSettings::MAINPORT_DISABLED);
|
||||
}
|
||||
break;
|
||||
case OPLinkSettings::FLEXIPORT_PPM:
|
||||
if (isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_PPM)) {
|
||||
setComboboxSelectedOption(m_oplink->MainPort, OPLinkSettings::MAINPORT_DISABLED);
|
||||
case OPLinkSettings::FLEXIPORT_PWM:
|
||||
case OPLinkSettings::FLEXIPORT_DISABLED:
|
||||
if (isComboboxOptionSelected(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_FLEXI)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_FLEXI)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_FLEXI)) {
|
||||
setComboboxSelectedOption(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_DISABLED);
|
||||
}
|
||||
m_oplink->FlexiComSpeed->setEnabled(false);
|
||||
break;
|
||||
case OPLinkSettings::FLEXIPORT_TELEMETRY:
|
||||
if (isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_oplink->MainPort, OPLinkSettings::MAINPORT_SERIAL);
|
||||
}
|
||||
m_oplink->FlexiComSpeed->setEnabled(true);
|
||||
break;
|
||||
case OPLinkSettings::FLEXIPORT_SERIAL:
|
||||
m_oplink->FlexiComSpeed->setEnabled(true);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::vcpPortChanged()
|
||||
void ConfigOPLinkWidget::radioPriStreamChanged()
|
||||
{
|
||||
bool vcpComBridgeEnabled = isComboboxOptionSelected(m_oplink->VCPPort, OPLinkSettings::VCPPORT_COMBRIDGE);
|
||||
|
||||
enableComboBoxOptionItem(m_oplink->MainPort, OPLinkSettings::MAINPORT_COMBRIDGE, vcpComBridgeEnabled);
|
||||
enableComboBoxOptionItem(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_COMBRIDGE, vcpComBridgeEnabled);
|
||||
|
||||
if (!vcpComBridgeEnabled) {
|
||||
if (isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_oplink->MainPort, OPLinkSettings::MAINPORT_DISABLED);
|
||||
switch (getComboboxSelectedOption(m_oplink->RadioPriStream)) {
|
||||
case OPLinkSettings::RADIOPRISTREAM_DISABLED:
|
||||
break;
|
||||
case OPLinkSettings::RADIOPRISTREAM_HID:
|
||||
if (isComboboxOptionSelected(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_HID)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_DISABLED);
|
||||
break;
|
||||
case OPLinkSettings::RADIOPRISTREAM_MAIN:
|
||||
if (!isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_TELEMETRY) &&
|
||||
!isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_SERIAL)) {
|
||||
setComboboxSelectedOption(m_oplink->MainPort, OPLinkSettings::MAINPORT_SERIAL);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_MAIN)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_MAIN)) {
|
||||
setComboboxSelectedOption(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_DISABLED);
|
||||
}
|
||||
break;
|
||||
case OPLinkSettings::RADIOPRISTREAM_FLEXI:
|
||||
if (!isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_TELEMETRY) &&
|
||||
!isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_SERIAL)) {
|
||||
setComboboxSelectedOption(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_SERIAL);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_FLEXI)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_FLEXI)) {
|
||||
setComboboxSelectedOption(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_DISABLED);
|
||||
}
|
||||
break;
|
||||
case OPLinkSettings::RADIOPRISTREAM_VCP:
|
||||
if (!isComboboxOptionSelected(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_DISABLED)) {
|
||||
setComboboxSelectedOption(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_VCP)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_DISABLED);
|
||||
}
|
||||
break;
|
||||
}
|
||||
updateSettings();
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::radioAuxStreamChanged()
|
||||
{
|
||||
switch (getComboboxSelectedOption(m_oplink->RadioAuxStream)) {
|
||||
case OPLinkSettings::RADIOAUXSTREAM_DISABLED:
|
||||
break;
|
||||
case OPLinkSettings::RADIOAUXSTREAM_HID:
|
||||
if (isComboboxOptionSelected(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_HID)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_DISABLED);
|
||||
}
|
||||
break;
|
||||
case OPLinkSettings::RADIOAUXSTREAM_MAIN:
|
||||
if (!isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_TELEMETRY) &&
|
||||
!isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_SERIAL)) {
|
||||
setComboboxSelectedOption(m_oplink->MainPort, OPLinkSettings::MAINPORT_SERIAL);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_MAIN)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_MAIN)) {
|
||||
setComboboxSelectedOption(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_DISABLED);
|
||||
}
|
||||
break;
|
||||
case OPLinkSettings::RADIOAUXSTREAM_FLEXI:
|
||||
if (!isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_TELEMETRY) &&
|
||||
!isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_SERIAL)) {
|
||||
setComboboxSelectedOption(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_SERIAL);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_FLEXI)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_MAIN)) {
|
||||
setComboboxSelectedOption(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_DISABLED);
|
||||
}
|
||||
break;
|
||||
case OPLinkSettings::RADIOAUXSTREAM_VCP:
|
||||
if (!isComboboxOptionSelected(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_DISABLED)) {
|
||||
setComboboxSelectedOption(m_oplink->VCPBridge, OPLinkSettings::VCPBRIDGE_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_VCP)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_DISABLED);
|
||||
}
|
||||
break;
|
||||
}
|
||||
updateSettings();
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::vcpBridgeChanged()
|
||||
{
|
||||
switch (getComboboxSelectedOption(m_oplink->VCPBridge)) {
|
||||
case OPLinkSettings::VCPBRIDGE_DISABLED:
|
||||
break;
|
||||
case OPLinkSettings::VCPBRIDGE_MAIN:
|
||||
if (!isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_TELEMETRY) &&
|
||||
!isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_SERIAL)) {
|
||||
setComboboxSelectedOption(m_oplink->MainPort, OPLinkSettings::MAINPORT_SERIAL);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_VCP) ||
|
||||
isComboboxOptionSelected(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_MAIN)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_VCP) ||
|
||||
isComboboxOptionSelected(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_MAIN)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_DISABLED);
|
||||
}
|
||||
break;
|
||||
case OPLinkSettings::VCPBRIDGE_FLEXI:
|
||||
if (!isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_TELEMETRY) &&
|
||||
!isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_SERIAL)) {
|
||||
setComboboxSelectedOption(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_SERIAL);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_VCP) ||
|
||||
isComboboxOptionSelected(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_FLEXI)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioPriStream, OPLinkSettings::RADIOPRISTREAM_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_VCP) ||
|
||||
isComboboxOptionSelected(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_FLEXI)) {
|
||||
setComboboxSelectedOption(m_oplink->RadioAuxStream, OPLinkSettings::RADIOAUXSTREAM_DISABLED);
|
||||
}
|
||||
break;
|
||||
}
|
||||
updateSettings();
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::unbind()
|
||||
|
@ -78,7 +78,9 @@ private slots:
|
||||
|
||||
void mainPortChanged();
|
||||
void flexiPortChanged();
|
||||
void vcpPortChanged();
|
||||
void radioPriStreamChanged();
|
||||
void radioAuxStreamChanged();
|
||||
void vcpBridgeChanged();
|
||||
|
||||
void unbind();
|
||||
};
|
||||
|
@ -101,7 +101,7 @@
|
||||
<string>Configuration</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="3" column="1">
|
||||
<item row="5" column="1">
|
||||
<widget class="QLineEdit" name="CoordID">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
|
||||
@ -138,7 +138,7 @@ The device must be rebooted for the binding to take place.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<item row="4" column="1">
|
||||
<widget class="QLineEdit" name="CustomDeviceID">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
|
||||
@ -196,7 +196,29 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<item row="0" column="5">
|
||||
<widget class="QLabel" name="UartsLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Serial Ports</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
<widget class="QLabel" name="MainPortLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -212,7 +234,227 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<item row="1" column="6">
|
||||
<widget class="QComboBox" name="MainPort">
|
||||
<property name="toolTip">
|
||||
<string>Choose a function for the main port.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="7">
|
||||
<widget class="QLabel" name="MainComSpeedLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="8">
|
||||
<widget class="QComboBox" name="MainComSpeed">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the baud rate for the main com port.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<widget class="QLabel" name="FlexiPortLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Flexi Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<widget class="QComboBox" name="FlexiPort">
|
||||
<property name="toolTip">
|
||||
<string>Choose a function for the flexi port.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="7">
|
||||
<widget class="QLabel" name="FlexiComSpeedLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="8">
|
||||
<widget class="QComboBox" name="FlexiComSpeed">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the baud rate for the main com port.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="5">
|
||||
<widget class="QLabel" name="ConnectionsLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Connections</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="5">
|
||||
<widget class="QLabel" name="RadioPriStreamLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Radio Primary</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="6">
|
||||
<widget class="QComboBox" name="RadioPriStream">
|
||||
<property name="toolTip">
|
||||
<string>Choose a destination for the primary radio stream.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="AirDataRateLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Air Data Rate</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QComboBox" name="AirDataRate">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>90</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the over-the-air baud rate for the radio.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="5">
|
||||
<widget class="QLabel" name="RadioAuxStreamLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Radio Auxiliary</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="6">
|
||||
<widget class="QComboBox" name="RadioAuxStream">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose a destination for the auxiliary radio stream.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="5">
|
||||
<widget class="QLabel" name="VCPBridgeLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>VCP Bridge</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="6">
|
||||
<widget class="QComboBox" name="VCPBridge">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose a destination for the Virtual Com Port bridge connection.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="MaximumChannelLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@ -259,41 +501,6 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="7">
|
||||
<widget class="QComboBox" name="MainPort">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the function for the main port.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="6">
|
||||
<widget class="QLabel" name="MaxRFTxPowerLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Max Power</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
@ -307,7 +514,7 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<item row="7" column="1">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<widget class="QSpinBox" name="MaximumChannel">
|
||||
@ -358,20 +565,7 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="3" column="7">
|
||||
<widget class="QComboBox" name="FlexiPort">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the function for the flexi port.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<item row="4" column="2">
|
||||
<widget class="QPushButton" name="UnbindButton">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::NoFocus</enum>
|
||||
@ -384,7 +578,7 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<item row="8" column="0">
|
||||
<widget class="QLabel" name="MinimumChannelLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@ -428,29 +622,6 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<widget class="QLabel" name="ComSpeedLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Com Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="7">
|
||||
<widget class="QComboBox" name="ComSpeed">
|
||||
<property name="toolTip">
|
||||
<string>Com speed in bps.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="LinkTypeLabel">
|
||||
<property name="font">
|
||||
@ -467,7 +638,7 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<item row="8" column="1">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_3">
|
||||
<item>
|
||||
<widget class="QSpinBox" name="MinimumChannel">
|
||||
@ -518,7 +689,7 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="CustomDeviceIDLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -534,23 +705,7 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<widget class="QLabel" name="FlexiPortLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Flexi Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="CoordIDLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -588,11 +743,33 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="7">
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="MaxRFTxPowerLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Max Power</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="MaxRFTxPower">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<width>90</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
@ -608,7 +785,7 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="BandLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -624,7 +801,7 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<item row="6" column="1">
|
||||
<widget class="QComboBox" name="RFBand">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
@ -643,64 +820,6 @@ Leave blank to use autogenerated Device ID.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="6">
|
||||
<widget class="QLabel" name="VCPPortLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>VCP Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="7">
|
||||
<widget class="QComboBox" name="VCPPort">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the function for the USB virtual com port.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="6">
|
||||
<widget class="QLabel" name="RadioAuxPortLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Radio Aux Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="7">
|
||||
<widget class="QComboBox" name="RadioAuxPort">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the function for the Radio Auxiliary virtual com port.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
|
@ -3,27 +3,33 @@
|
||||
<description>OPLink configurations options.</description>
|
||||
<field name="Protocol" units="" type="enum" elements="1" options="Disabled,OPLinkReceiver,OPLinkCoordinator,OpenLRS" defaultvalue="Disabled"/>
|
||||
<field name="LinkType" units="" type="enum" elements="1" options="Data,Control,DataAndControl" defaultvalue="Data"/>
|
||||
<field name="CoordID" units="hex" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="MainPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,ComBridge,PPM,PWM" defaultvalue="Disabled"/>
|
||||
<field name="FlexiPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,ComBridge,PPM,PWM" defaultvalue="Disabled"/>
|
||||
<field name="VCPPort" units="" type="enum" elements="1" options="Disabled,Serial,ComBridge" defaultvalue="Disabled"/>
|
||||
<field name="ComSpeed" units="bps" type="enum" elements="1" options="4800,9600,19200,38400,57600,115200" defaultvalue="38400"/>
|
||||
<field name="MaxRFPower" units="mW" type="enum" elements="1" options="0,1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="0"/>
|
||||
<field name="RFBand" units="" type="enum" elements="1" options="433MHz,868MHz,915MHz" defaultvalue="433MHz"/>
|
||||
<field name="MinChannel" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="MaxChannel" units="" type="uint8" elements="1" defaultvalue="250"/>
|
||||
<field name="CoordID" units="hex" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="CustomDeviceID" units="hex" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="RFXtalCap" units="" type="uint8" elements="1" defaultvalue="127" limits="%BE:0:171" description="0 to 171 range, default 127"/>
|
||||
|
||||
<!-- OpenLRS options -->
|
||||
<!-- port options -->
|
||||
<field name="MainPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM,PWM" defaultvalue="Disabled"/>
|
||||
<field name="FlexiPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM,PWM" defaultvalue="Disabled"/>
|
||||
<field name="RadioPriStream" units="connection" type="enum" elements="1" options="Disabled,HID,Main,Flexi,VCP" defaultvalue="HID"/>
|
||||
<field name="RadioAuxStream" units="connection" type="enum" elements="1" options="Disabled,HID,Main,Flexi,VCP" defaultvalue="Disabled"/>
|
||||
<field name="VCPBridge" units="connection" type="enum" elements="1" options="Disabled,Main,Flexi" defaultvalue="Disabled"/>
|
||||
<field name="MainComSpeed" units="bps" type="enum" elements="1" options="Disabled,4800,9600,19200,38400,57600,115200" defaultvalue="38400"/>
|
||||
<field name="FlexiComSpeed" units="bps" type="enum" elements="1" options="Disabled,4800,9600,19200,38400,57600,115200" defaultvalue="38400"/>
|
||||
<field name="AirDataRate" units="bps" type="enum" elements="1" options="9600,19200,32000,57600,64000,100000,128000,192000,256000" defaultvalue="64000"/>
|
||||
|
||||
<!-- OpenLRS options -->
|
||||
<field name="Version" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="SerialBaudrate" units="bps" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="RFFrequency" units="Hz" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="FailsafeDelay" units="ms" type="uint32" elements="1" defaultvalue="1000"/>
|
||||
<field name="RSSIType" units="function" type="enum" elements="1" options="Combined,RSSI,LinkQuality" defaultvalue="Combined"/>
|
||||
<field name="RadioAuxStream" units="function" type="enum" elements="1" options="ComBridge,Disabled" defaultvalue="Disabled"/>
|
||||
<!-- rf_magic === CoordID -->
|
||||
<field name="RFPower" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
|
||||
<!-- RF options -->
|
||||
<field name="RFXtalCap" units="" type="uint8" elements="1" defaultvalue="127" limits="%BE:0:171" description="0 to 171 range, default 127"/>
|
||||
<field name="MinChannel" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="MaxChannel" units="" type="uint8" elements="1" defaultvalue="250"/>
|
||||
<field name="RFBand" units="" type="enum" elements="1" options="433MHz,868MHz,915MHz" defaultvalue="433MHz"/>
|
||||
<field name="MaxRFPower" units="mW" type="enum" elements="1" options="0,1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="0"/>
|
||||
<field name="RFChannelSpacing" units="Hz" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="HopChannel" units="" type="uint8" elements="24" defaultvalue="0"/>
|
||||
<field name="ModemParams" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
|
Loading…
Reference in New Issue
Block a user