mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
Merged in alessiomorale/librepilot/lp-437_oplinl_secondary_stream (pull request #353)
LP-437 Oplink secondary stream
This commit is contained in:
commit
93bec1a1bc
@ -420,6 +420,8 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
|
||||
rfm22b_dev->rx_in_cb = NULL;
|
||||
rfm22b_dev->tx_out_cb = NULL;
|
||||
|
||||
rfm22b_dev->aux_rx_in_cb = NULL;
|
||||
rfm22b_dev->aux_tx_out_cb = NULL;
|
||||
// Initialize the PPM callback.
|
||||
rfm22b_dev->ppm_callback = NULL;
|
||||
|
||||
@ -1905,10 +1907,28 @@ static enum pios_radio_event radio_txStart(struct pios_rfm22b_dev *radio_dev)
|
||||
}
|
||||
|
||||
// Append data from the com interface if applicable.
|
||||
if (!radio_dev->ppm_only_mode && radio_dev->tx_out_cb) {
|
||||
// Try to get some data to send
|
||||
if (!radio_dev->ppm_only_mode) {
|
||||
uint8_t newlen = 0;
|
||||
bool need_yield = false;
|
||||
len += (radio_dev->tx_out_cb)(radio_dev->tx_out_context, p + len, max_data_len - len, NULL, &need_yield);
|
||||
uint8_t i = 0;
|
||||
// Try to get some data to send
|
||||
while (newlen == 0 && i < 2) {
|
||||
radio_dev->last_stream_sent = (radio_dev->last_stream_sent + 1) % 2;
|
||||
if (!radio_dev->last_stream_sent) {
|
||||
if (radio_dev->tx_out_cb) {
|
||||
newlen = (radio_dev->tx_out_cb)(radio_dev->tx_out_context, p + len + 1, max_data_len - len - 1, NULL, &need_yield);
|
||||
}
|
||||
} else {
|
||||
if (radio_dev->aux_tx_out_cb) {
|
||||
newlen = (radio_dev->aux_tx_out_cb)(radio_dev->aux_tx_out_context, p + len + 1, max_data_len - len - 1, NULL, &need_yield);
|
||||
}
|
||||
}
|
||||
i++;
|
||||
}
|
||||
if (newlen) {
|
||||
*(p + len) = radio_dev->last_stream_sent;
|
||||
len += newlen + 1;
|
||||
}
|
||||
}
|
||||
|
||||
// Always send a packet if this modem is a coordinator.
|
||||
@ -1990,9 +2010,10 @@ static enum pios_radio_event radio_setRxMode(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
*/
|
||||
static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *radio_dev, uint8_t *p, uint16_t rx_len)
|
||||
{
|
||||
bool good_packet = true;
|
||||
bool good_packet = true;
|
||||
bool corrected_packet = false;
|
||||
uint8_t data_len = rx_len;
|
||||
uint8_t stream_num = 0;
|
||||
uint8_t data_len = rx_len;
|
||||
|
||||
// We don't rsencode ppm only packets.
|
||||
if (!radio_dev->ppm_only_mode) {
|
||||
@ -2073,10 +2094,22 @@ static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *radio_d
|
||||
if (good_packet || corrected_packet) {
|
||||
// Send the data to the com port
|
||||
bool rx_need_yield;
|
||||
if (radio_dev->rx_in_cb && (data_len > 0) && !radio_dev->ppm_only_mode) {
|
||||
(radio_dev->rx_in_cb)(radio_dev->rx_in_context, p, data_len, NULL, &rx_need_yield);
|
||||
}
|
||||
|
||||
|
||||
if ((data_len > 0) && !radio_dev->ppm_only_mode) {
|
||||
stream_num = *p;
|
||||
p++;
|
||||
data_len--;
|
||||
if (!stream_num) {
|
||||
if (radio_dev->rx_in_cb) {
|
||||
(radio_dev->rx_in_cb)(radio_dev->rx_in_context, p, data_len, NULL, &rx_need_yield);
|
||||
}
|
||||
} else {
|
||||
if (radio_dev->aux_rx_in_cb) {
|
||||
(radio_dev->aux_rx_in_cb)(radio_dev->aux_rx_in_context, p, data_len, NULL, &rx_need_yield);
|
||||
}
|
||||
}
|
||||
}
|
||||
/*
|
||||
* If the packet is valid and destined for us we synchronize the clock.
|
||||
*/
|
||||
|
@ -40,6 +40,10 @@ static void PIOS_RFM22B_COM_RegisterRxCallback(uint32_t rfm22b_id, pios_com_call
|
||||
static void PIOS_RFM22B_COM_RegisterTxCallback(uint32_t rfm22b_id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
static void PIOS_RFM22B_COM_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail);
|
||||
static void PIOS_RFM22B_COM_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail);
|
||||
|
||||
static void PIOS_RFM22B_COM_RegisterAuxRxCallback(uint32_t rfm22b_id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
static void PIOS_RFM22B_COM_RegisterAuxTxCallback(uint32_t rfm22b_id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
|
||||
static uint32_t PIOS_RFM22B_COM_Available(uint32_t rfm22b_com_id);
|
||||
|
||||
/* Local variables */
|
||||
@ -52,6 +56,15 @@ const struct pios_com_driver pios_rfm22b_com_driver = {
|
||||
.available = PIOS_RFM22B_COM_Available
|
||||
};
|
||||
|
||||
/* Local variables */
|
||||
const struct pios_com_driver pios_rfm22b_aux_com_driver = {
|
||||
.set_baud = PIOS_RFM22B_COM_ChangeBaud,
|
||||
.tx_start = PIOS_RFM22B_COM_TxStart,
|
||||
.rx_start = PIOS_RFM22B_COM_RxStart,
|
||||
.bind_tx_cb = PIOS_RFM22B_COM_RegisterAuxTxCallback,
|
||||
.bind_rx_cb = PIOS_RFM22B_COM_RegisterAuxRxCallback,
|
||||
.available = PIOS_RFM22B_COM_Available
|
||||
};
|
||||
/**
|
||||
* Changes the baud rate of the RFM22B peripheral without re-initialising.
|
||||
*
|
||||
@ -129,6 +142,51 @@ static void PIOS_RFM22B_COM_RegisterTxCallback(uint32_t rfm22b_id, pios_com_call
|
||||
rfm22b_dev->tx_out_cb = tx_out_cb;
|
||||
}
|
||||
|
||||
/**
|
||||
* Register the callback to pass received data to
|
||||
*
|
||||
* @param[in] rfm22b_dev The device ID.
|
||||
* @param[in] rx_in_cb The Rx callback function.
|
||||
* @param[in] context The callback context.
|
||||
*/
|
||||
static void PIOS_RFM22B_COM_RegisterAuxRxCallback(uint32_t rfm22b_id, pios_com_callback rx_in_cb, uint32_t context)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
|
||||
return;
|
||||
}
|
||||
|
||||
/*
|
||||
* Order is important in these assignments since ISR uses _cb
|
||||
* field to determine if it's ok to dereference _cb and _context
|
||||
*/
|
||||
rfm22b_dev->aux_rx_in_context = context;
|
||||
rfm22b_dev->aux_rx_in_cb = rx_in_cb;
|
||||
}
|
||||
|
||||
/**
|
||||
* Register the callback to get data from.
|
||||
*
|
||||
* @param[in] rfm22b_dev The device ID.
|
||||
* @param[in] rx_in_cb The Tx callback function.
|
||||
* @param[in] context The callback context.
|
||||
*/
|
||||
static void PIOS_RFM22B_COM_RegisterAuxTxCallback(uint32_t rfm22b_id, pios_com_callback tx_out_cb, uint32_t context)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
|
||||
return;
|
||||
}
|
||||
|
||||
/*
|
||||
* Order is important in these assignments since ISR uses _cb
|
||||
* field to determine if it's ok to dereference _cb and _context
|
||||
*/
|
||||
rfm22b_dev->aux_tx_out_context = context;
|
||||
rfm22b_dev->aux_tx_out_cb = tx_out_cb;
|
||||
}
|
||||
/**
|
||||
* See if the COM port is alive
|
||||
*
|
||||
|
@ -28,12 +28,13 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_RFM22B_H
|
||||
#define PIOS_RFM22B_H
|
||||
#ifndef PIOS_RFM22B_COM_H
|
||||
#define PIOS_RFM22B_COM_H
|
||||
|
||||
extern const struct pios_com_driver pios_rfm22b_com_driver;
|
||||
extern const struct pios_com_driver pios_rfm22b_aux_com_driver;
|
||||
|
||||
#endif /* PIOS_RFM22B_H */
|
||||
#endif /* PIOS_RFM22B_COM_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -206,12 +206,18 @@ struct pios_rfm22b_dev {
|
||||
// ISR pending semaphore
|
||||
xSemaphoreHandle isrPending;
|
||||
|
||||
// The COM callback functions.
|
||||
// The main COM callback functions.
|
||||
pios_com_callback rx_in_cb;
|
||||
uint32_t rx_in_context;
|
||||
pios_com_callback tx_out_cb;
|
||||
uint32_t tx_out_context;
|
||||
|
||||
uint8_t last_stream_sent;
|
||||
// The Aux COM callback functions.
|
||||
pios_com_callback aux_rx_in_cb;
|
||||
uint32_t aux_rx_in_context;
|
||||
pios_com_callback aux_tx_out_cb;
|
||||
uint32_t aux_tx_out_context;
|
||||
// the transmit power to use for data transmissions
|
||||
uint8_t tx_power;
|
||||
|
||||
|
@ -66,19 +66,21 @@ 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_vcp_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;
|
||||
#endif
|
||||
|
||||
|
||||
uintptr_t pios_uavo_settings_fs_id;
|
||||
uintptr_t pios_user_fs_id = 0;
|
||||
|
||||
@ -496,6 +498,24 @@ void PIOS_Board_Init(void)
|
||||
|
||||
// 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;
|
||||
|
@ -260,6 +260,7 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
#define PIOS_COM_MSP_TX_BUF_LEN 128
|
||||
#define PIOS_COM_MSP_RX_BUF_LEN 64
|
||||
#define PIOS_COM_MAVLINK_TX_BUF_LEN 128
|
||||
#define PIOS_COM_MAVLINK_RX_BUF_LEN 128
|
||||
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
|
||||
@ -279,6 +280,7 @@ uint32_t pios_com_mavlink_id = 0;
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
#include <pios_rfm22b_com.h>
|
||||
#endif
|
||||
|
||||
uintptr_t pios_uavo_settings_fs_id;
|
||||
@ -997,6 +999,32 @@ void PIOS_Board_Init(void)
|
||||
|
||||
/* Reinitialize the modem. */
|
||||
PIOS_RFM22B_Reinit(pios_rfm22b_id);
|
||||
|
||||
uint8_t hwsettings_radioaux;
|
||||
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
|
||||
// TODO: this is in preparation for full mavlink support and is used by LP-368
|
||||
uint16_t mavlink_rx_size = PIOS_COM_MAVLINK_RX_BUF_LEN;
|
||||
|
||||
switch (hwsettings_radioaux) {
|
||||
case HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE:
|
||||
case HWSETTINGS_RADIOAUXSTREAM_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RADIOAUXSTREAM_MAVLINK:
|
||||
{
|
||||
uint8_t *auxrx_buffer = 0;
|
||||
if (mavlink_rx_size) {
|
||||
auxrx_buffer = (uint8_t *)pios_malloc(mavlink_rx_size);
|
||||
}
|
||||
uint8_t *auxtx_buffer = (uint8_t *)pios_malloc(PIOS_COM_MAVLINK_TX_BUF_LEN);
|
||||
PIOS_Assert(auxrx_buffer);
|
||||
PIOS_Assert(auxtx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_mavlink_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
|
||||
auxrx_buffer, mavlink_rx_size,
|
||||
auxtx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
|
||||
|
@ -212,6 +212,7 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
#define PIOS_COM_MSP_RX_BUF_LEN 64
|
||||
|
||||
#define PIOS_COM_MAVLINK_TX_BUF_LEN 128
|
||||
#define PIOS_COM_MAVLINK_RX_BUF_LEN 128
|
||||
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
|
||||
@ -231,6 +232,7 @@ uint32_t pios_com_vcp_id = 0;
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
#include <pios_rfm22b_com.h>
|
||||
#endif
|
||||
|
||||
uintptr_t pios_uavo_settings_fs_id;
|
||||
@ -937,6 +939,32 @@ void PIOS_Board_Init(void)
|
||||
|
||||
/* Reinitialize the modem. */
|
||||
PIOS_RFM22B_Reinit(pios_rfm22b_id);
|
||||
// TODO: this is in preparation for full mavlink support and is used by LP-368
|
||||
uint16_t mavlink_rx_size = PIOS_COM_MAVLINK_RX_BUF_LEN;
|
||||
|
||||
uint8_t hwsettings_radioaux;
|
||||
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
|
||||
|
||||
switch (hwsettings_radioaux) {
|
||||
case HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE:
|
||||
case HWSETTINGS_RADIOAUXSTREAM_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RADIOAUXSTREAM_MAVLINK:
|
||||
{
|
||||
uint8_t *auxrx_buffer = 0;
|
||||
if (mavlink_rx_size) {
|
||||
auxrx_buffer = (uint8_t *)pios_malloc(mavlink_rx_size);
|
||||
}
|
||||
uint8_t *auxtx_buffer = (uint8_t *)pios_malloc(PIOS_COM_MAVLINK_TX_BUF_LEN);
|
||||
PIOS_Assert(auxrx_buffer);
|
||||
PIOS_Assert(auxtx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_mavlink_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
|
||||
auxrx_buffer, mavlink_rx_size,
|
||||
auxtx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
|
||||
|
@ -83,6 +83,7 @@ ConfigOPLinkWidget::ConfigOPLinkWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
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", "RFXtalCap", m_oplink->RFXtalCapValue);
|
||||
addWidgetBinding("OPLinkSettings", "RFXtalCap", m_oplink->RFXtalCapSlider);
|
||||
@ -208,6 +209,8 @@ void ConfigOPLinkWidget::setPortsVisible(bool 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);
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::updateInfo()
|
||||
@ -264,6 +267,8 @@ void ConfigOPLinkWidget::updateSettings()
|
||||
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->RFBand->setEnabled(is_receiver || is_coordinator);
|
||||
m_oplink->MinimumChannel->setEnabled(is_receiver || is_coordinator);
|
||||
m_oplink->MaximumChannel->setEnabled(is_receiver || is_coordinator);
|
||||
|
@ -66,6 +66,8 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbRcvrGPSProtocol);
|
||||
|
||||
addWidgetBinding("HwSettings", "RadioAuxStream", m_ui->cbRadioAux);
|
||||
|
||||
setupCustomCombos();
|
||||
}
|
||||
|
||||
|
@ -530,6 +530,19 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="12" column="2" alignment="Qt::AlignHCenter">
|
||||
<widget class="QLabel" name="label_">
|
||||
<property name="text">
|
||||
<string>Radio Aux Stream</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="13" column="2">
|
||||
<widget class="QComboBox" name="cbRadioAux"/>
|
||||
</item>
|
||||
<item row="0" column="1" rowspan="12" colspan="4" alignment="Qt::AlignHCenter|Qt::AlignVCenter">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="sizePolicy">
|
||||
|
@ -63,6 +63,8 @@ ConfigSparky2HWWidget::ConfigSparky2HWWidget(QWidget *parent) : ConfigTaskWidget
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
|
||||
|
||||
addWidgetBinding("HwSettings", "RadioAuxStream", m_ui->cbRadioAux);
|
||||
|
||||
setupCustomCombos();
|
||||
}
|
||||
|
||||
|
@ -457,6 +457,21 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
|
||||
<item row="0" column="2" alignment="Qt::AlignHCenter">
|
||||
<widget class="QLabel" name="label_">
|
||||
<property name="text">
|
||||
<string>Radio Aux Stream</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QComboBox" name="cbRadioAux"/>
|
||||
</item>
|
||||
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label_9">
|
||||
<property name="text">
|
||||
|
@ -55,8 +55,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>947</width>
|
||||
<height>575</height>
|
||||
<width>926</width>
|
||||
<height>647</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
@ -672,6 +672,35 @@ Leave blank to use autogenerated Device ID.</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>
|
||||
@ -2200,6 +2229,7 @@ a frequency misalignement between the two modems.</string>
|
||||
<tabstop>MainPort</tabstop>
|
||||
<tabstop>FlexiPort</tabstop>
|
||||
<tabstop>VCPPort</tabstop>
|
||||
<tabstop>RadioAuxPort</tabstop>
|
||||
<tabstop>RFXtalCapValue</tabstop>
|
||||
<tabstop>applyButton</tabstop>
|
||||
<tabstop>saveButton</tabstop>
|
||||
|
@ -28,7 +28,8 @@
|
||||
<field name="MSPSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="115200"/>
|
||||
<field name="MAVLinkSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="USB_HIDPort" units="function" type="enum" elements="1" options="USBTelemetry,RCTransmitter,Disabled" defaultvalue="USBTelemetry"/>
|
||||
<field name="USB_VCPPort" units="function" type="enum" elements="1" options="USBTelemetry,ComBridge,DebugConsole,Disabled" defaultvalue="Disabled"/>
|
||||
<field name="USB_VCPPort" units="function" type="enum" elements="1" options="USBTelemetry,ComBridge,DebugConsole,Disabled,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="RadioAuxStream" units="function" type="enum" elements="1" options="DebugConsole,Disabled,MAVLink" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="OptionalModules" units="" type="enum" elementnames="CameraStab,CameraControl,GPS,Fault,Altitude,Airspeed,TxPID,Battery,Overo,MagBaro,OsdHk,AutoTune" options="Disabled,Enabled" defaultvalue="Disabled"/>
|
||||
<field name="ADCRouting" units="" type="enum" elementnames="adc0,adc1,adc2,adc3,adc4,adc5,adc6,adc7" options="Disabled,BatteryVoltage,BatteryCurrent,AnalogAirspeed,Generic" defaultvalue="Disabled"/>
|
||||
|
@ -21,8 +21,8 @@
|
||||
<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"/>
|
||||
|
||||
<!-- rf_magic === CoordID -->
|
||||
<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"/>
|
||||
<field name="RFChannelSpacing" units="Hz" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="HopChannel" units="" type="uint8" elements="24" defaultvalue="0"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user