mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-18 03:52:11 +01:00
OP-932 Adds a direct PPM channel on each Tx packet when in PPM mode, and adds a PPM only mode that uses a 9600 bps air datarate. Also updates the OPLink configuration tab and moves all OPLink configuration to the OPLink configuration tab on the Revo, and customizes the OPLink configuration tab for the Revo.
This commit is contained in:
parent
b25ba75fd9
commit
2aea2342ab
@ -97,22 +97,6 @@ int32_t OPLinkModInitialize(void)
|
||||
{
|
||||
// Must registers objects here for system thread because ObjectManager started in OpenPilotInit
|
||||
|
||||
// Initialize out status object.
|
||||
OPLinkStatusInitialize();
|
||||
OPLinkStatusData oplinkStatus;
|
||||
OPLinkStatusGet(&oplinkStatus);
|
||||
|
||||
// Get our hardware information.
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
oplinkStatus.BoardType = bdinfo->board_type;
|
||||
PIOS_BL_HELPER_FLASH_Read_Description(oplinkStatus.Description, OPLINKSTATUS_DESCRIPTION_NUMELEM);
|
||||
PIOS_SYS_SerialNumberGetBinary(oplinkStatus.CPUSerial);
|
||||
oplinkStatus.BoardRevision = bdinfo->board_rev;
|
||||
|
||||
// Update the object
|
||||
OPLinkStatusSet(&oplinkStatus);
|
||||
|
||||
// Call the module start function.
|
||||
OPLinkModStart();
|
||||
|
||||
|
@ -37,7 +37,6 @@
|
||||
#include <oplinksettings.h>
|
||||
#include <oplinkreceiver.h>
|
||||
#include <uavtalk_priv.h>
|
||||
#include <pios_ppm_out.h>
|
||||
#include <pios_rfm22b.h>
|
||||
#include <ecc.h>
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
@ -49,14 +48,14 @@
|
||||
// ****************
|
||||
// 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 EV_SEND_ACK 0x20
|
||||
#define EV_SEND_NACK 0x30
|
||||
#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
|
||||
|
||||
// ****************
|
||||
// Private types
|
||||
@ -68,6 +67,7 @@ typedef struct {
|
||||
xTaskHandle radioTxTaskHandle;
|
||||
xTaskHandle radioRxTaskHandle;
|
||||
xTaskHandle PPMInputTaskHandle;
|
||||
xTaskHandle serialRxTaskHandle;
|
||||
|
||||
// The UAVTalk connection on the com side.
|
||||
UAVTalkConnection telemUAVTalkCon;
|
||||
@ -77,14 +77,17 @@ typedef struct {
|
||||
xQueueHandle uavtalkEventQueue;
|
||||
xQueueHandle radioEventQueue;
|
||||
|
||||
// The raw serial Rx buffer
|
||||
uint8_t serialRxBuf[SERIAL_RX_BUF_LEN];
|
||||
|
||||
// Error statistics.
|
||||
uint32_t comTxErrors;
|
||||
uint32_t comTxRetries;
|
||||
uint32_t UAVTalkErrors;
|
||||
uint32_t droppedPackets;
|
||||
uint32_t comTxErrors;
|
||||
uint32_t comTxRetries;
|
||||
uint32_t UAVTalkErrors;
|
||||
uint32_t droppedPackets;
|
||||
|
||||
// Should we parse UAVTalk?
|
||||
bool parseUAVTalk;
|
||||
bool parseUAVTalk;
|
||||
|
||||
// The current configured uart speed
|
||||
OPLinkSettingsComSpeedOptions comSpeed;
|
||||
@ -95,6 +98,7 @@ 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 PPMInputTask(void *parameters);
|
||||
@ -103,7 +107,6 @@ static int32_t RadioSendHandler(uint8_t *buf, int32_t length);
|
||||
static void ProcessTelemetryStream(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle, uint8_t rxbyte);
|
||||
static void ProcessRadioStream(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle, uint8_t rxbyte);
|
||||
static void objectPersistenceUpdatedCb(UAVObjEvent *objEv);
|
||||
static void oplinkReceiverUpdatedCb(UAVObjEvent *objEv);
|
||||
|
||||
// ****************
|
||||
// Private variables
|
||||
@ -170,21 +173,25 @@ static int32_t RadioComBridgeStart(void)
|
||||
|
||||
// Configure the UAVObject callbacks
|
||||
ObjectPersistenceConnectCallback(&objectPersistenceUpdatedCb);
|
||||
if (!is_coordinator) {
|
||||
OPLinkReceiverConnectCallback(&oplinkReceiverUpdatedCb);
|
||||
}
|
||||
|
||||
// Start the primary tasks for receiving/sending UAVTalk packets from the GCS.
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"telemetryTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryTxTaskHandle));
|
||||
xTaskCreate(telemetryRxTask, (signed char *)"telemetryRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryRxTaskHandle));
|
||||
xTaskCreate(radioTxTask, (signed char *)"radioTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioTxTaskHandle));
|
||||
xTaskCreate(radioRxTask, (signed char *)"radioRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioRxTaskHandle));
|
||||
if (PIOS_PPM_RECEIVER != 0) {
|
||||
xTaskCreate(PPMInputTask, (signed char *)"PPMInputTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->PPMInputTaskHandle));
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
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, (signed char *)"serialRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->serialRxTaskHandle));
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_SERIALRX);
|
||||
#endif
|
||||
}
|
||||
xTaskCreate(radioTxTask, (signed char *)"radioTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioTxTaskHandle));
|
||||
xTaskCreate(radioRxTask, (signed char *)"radioRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioRxTaskHandle));
|
||||
|
||||
// Register the watchdog timers.
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
@ -264,28 +271,6 @@ static void telemetryTxTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
}
|
||||
data->comTxRetries += retries;
|
||||
} else if (ev.event == EV_SEND_ACK) {
|
||||
// Send the ACK
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendAck(data->telemUAVTalkCon, ev.obj, ev.instId) == 0;
|
||||
if (!success) {
|
||||
++retries;
|
||||
}
|
||||
}
|
||||
data->comTxRetries += retries;
|
||||
} else if (ev.event == EV_SEND_NACK) {
|
||||
// Send the NACK
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendNack(data->telemUAVTalkCon, UAVObjGetID(ev.obj)) == 0;
|
||||
if (!success) {
|
||||
++retries;
|
||||
}
|
||||
}
|
||||
data->comTxRetries += retries;
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -320,28 +305,6 @@ static void radioTxTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
}
|
||||
data->comTxRetries += retries;
|
||||
} else if (ev.event == EV_SEND_ACK) {
|
||||
// Send the ACK
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendAck(data->radioUAVTalkCon, ev.obj, ev.instId) == 0;
|
||||
if (!success) {
|
||||
++retries;
|
||||
}
|
||||
}
|
||||
data->comTxRetries += retries;
|
||||
} else if (ev.event == EV_SEND_NACK) {
|
||||
// Send the NACK
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendNack(data->radioUAVTalkCon, UAVObjGetID(ev.obj)) == 0;
|
||||
if (!success) {
|
||||
++retries;
|
||||
}
|
||||
}
|
||||
data->comTxRetries += retries;
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -359,13 +322,17 @@ static void radioRxTask(__attribute__((unused)) void *parameters)
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORX);
|
||||
#endif
|
||||
uint8_t serial_data[1];
|
||||
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, serial_data, sizeof(serial_data), MAX_PORT_DELAY);
|
||||
if (bytes_to_process > 0) {
|
||||
// Pass the data through the UAVTalk parser.
|
||||
for (uint8_t i = 0; i < bytes_to_process; i++) {
|
||||
ProcessRadioStream(data->radioUAVTalkCon, data->telemUAVTalkCon, serial_data[i]);
|
||||
if (PIOS_COM_RADIO) {
|
||||
uint8_t serial_data[1];
|
||||
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, serial_data, sizeof(serial_data), MAX_PORT_DELAY);
|
||||
if (bytes_to_process > 0) {
|
||||
// Pass the data through the UAVTalk parser.
|
||||
for (uint8_t i = 0; i < bytes_to_process; i++) {
|
||||
ProcessRadioStream(data->radioUAVTalkCon, data->telemUAVTalkCon, serial_data[i]);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
vTaskDelay(5);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -403,7 +370,6 @@ static void telemetryRxTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Reads the PPM input device and sends out OPLinkReceiver objects.
|
||||
*
|
||||
@ -412,29 +378,54 @@ static void telemetryRxTask(__attribute__((unused)) void *parameters)
|
||||
static void PPMInputTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
xSemaphoreHandle sem = PIOS_RCVR_GetSemaphore(PIOS_PPM_RECEIVER, 1);
|
||||
OPLinkReceiverData opl_rcvr;
|
||||
int16_t channels[RFM22B_PPM_NUM_CHANNELS];
|
||||
|
||||
// Task loop
|
||||
while (1) {
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_PPMINPUT);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Wait for the receiver semaphore.
|
||||
bool valid_input_detected = false;
|
||||
if (xSemaphoreTake(sem, MAX_PORT_DELAY) == pdTRUE) {
|
||||
if (xSemaphoreTake(sem, PPM_INPUT_TIMEOUT) == pdTRUE) {
|
||||
// Read the receiver inputs.
|
||||
for (uint8_t i = 0; i < OPLINKRECEIVER_CHANNEL_NUMELEM; ++i) {
|
||||
opl_rcvr.Channel[i] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i + 1);
|
||||
if ((opl_rcvr.Channel[i] != PIOS_RCVR_INVALID) && (opl_rcvr.Channel[i] != PIOS_RCVR_TIMEOUT)) {
|
||||
valid_input_detected = true;
|
||||
}
|
||||
channels[i] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i + 1);
|
||||
}
|
||||
} else {
|
||||
// Failsafe
|
||||
for (uint8_t i = 0; i < OPLINKRECEIVER_CHANNEL_NUMELEM; ++i) {
|
||||
channels[i] = PIOS_RCVR_INVALID;
|
||||
}
|
||||
}
|
||||
|
||||
// Set the receiver UAVO if we detected valid input.
|
||||
if (valid_input_detected) {
|
||||
OPLinkReceiverSet(&opl_rcvr);
|
||||
// Pass the channel values to the radio device.
|
||||
PIOS_RFM22B_PPMSet(pios_rfm22b_id, 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);
|
||||
|
||||
// Send the data over the radio link.
|
||||
if (bytes_to_process > 0) {
|
||||
PIOS_COM_SendBufferNonBlocking(PIOS_COM_RADIO, data->serialRxBuf, bytes_to_process);
|
||||
}
|
||||
} else {
|
||||
vTaskDelay(5);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -599,19 +590,3 @@ static void objectPersistenceUpdatedCb(__attribute__((unused)) UAVObjEvent *objE
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Callback that is called when the OPLinkReceiver UAVObject is changed.
|
||||
* @param[in] objEv The event that precipitated the callback.
|
||||
*/
|
||||
static void oplinkReceiverUpdatedCb(__attribute__((unused)) UAVObjEvent *objEv)
|
||||
{
|
||||
// Get the OPLinkReceiver object.
|
||||
OPLinkReceiverData opl_rcvr;
|
||||
|
||||
OPLinkReceiverGet(&opl_rcvr);
|
||||
|
||||
for (uint8_t i = 0; i < OPLINKRECEIVER_CHANNEL_NUMELEM; ++i) {
|
||||
PIOS_PPM_OUT_Set(PIOS_PPM_OUTPUT, i, opl_rcvr.Channel[i]);
|
||||
}
|
||||
}
|
||||
|
@ -157,8 +157,8 @@ int32_t TelemetryInitialize(void)
|
||||
#endif
|
||||
|
||||
// Create periodic event that will be used to update the telemetry stats
|
||||
txErrors = 0;
|
||||
txRetries = 0;
|
||||
txErrors = 0;
|
||||
txRetries = 0;
|
||||
UAVObjEvent ev;
|
||||
memset(&ev, 0, sizeof(UAVObjEvent));
|
||||
EventPeriodicQueueCreate(&ev, priorityQueue, STATS_UPDATE_PERIOD_MS);
|
||||
|
@ -34,15 +34,22 @@
|
||||
// This module uses the RFM22B's internal packet handling hardware to
|
||||
// encapsulate our own packet data.
|
||||
//
|
||||
// The RFM22B internal hardware packet handler configuration is as follows ..
|
||||
// The RFM22B internal hardware packet handler configuration is as follows:
|
||||
//
|
||||
// 4-byte (32-bit) preamble .. alternating 0's & 1's
|
||||
// 6-byte (32-bit) preamble .. alternating 0's & 1's
|
||||
// 4-byte (32-bit) sync
|
||||
// 1-byte packet length (number of data bytes to follow)
|
||||
// 0 to 255 user data bytes
|
||||
// 4 byte ECC
|
||||
//
|
||||
// Our own packet data will also contain it's own header and 32-bit CRC
|
||||
// as a single 16-bit CRC is not sufficient for wireless comms.
|
||||
// OR in PPM only mode:
|
||||
//
|
||||
// 6-byte (32-bit) preamble .. alternating 0's & 1's
|
||||
// 4-byte (32-bit) sync
|
||||
// 1-byte packet length (number of data bytes to follow)
|
||||
// 1 byte valid bitmask
|
||||
// 8 PPM values (0-255)
|
||||
// 1 byte CRC
|
||||
//
|
||||
// *****************************************************************
|
||||
|
||||
@ -64,11 +71,10 @@
|
||||
#define RFM22B_DEFAULT_TX_POWER RFM22_tx_pwr_txpow_0
|
||||
#define RFM22B_NOMINAL_CARRIER_FREQUENCY 430000000
|
||||
#define RFM22B_LINK_QUALITY_THRESHOLD 20
|
||||
#define RFM22B_DEFAULT_NUM_CHANNELS 1
|
||||
#define RFM22B_DEFAULT_MIN_CHANNEL 0
|
||||
#define RFM22B_DEFAULT_MAX_CHANNEL 250
|
||||
#define RFM22B_DEFAULT_CHANNEL_SET 24
|
||||
#define RFM22B_DEFAULT_PACKET_PERIOD 15
|
||||
#define RFM22B_PPM_ONLY_DATARATE RFM22_datarate_9600
|
||||
|
||||
// The maximum amount of time without activity before initiating a reset.
|
||||
#define PIOS_RFM22B_SUPERVISOR_TIMEOUT 100 // ms
|
||||
@ -80,6 +86,7 @@
|
||||
#define RX_PREAMBLE_NIBBLES 6 // 5 to 31 (number of nibbles)
|
||||
#define SYNC_BYTES 4
|
||||
#define HEADER_BYTES 4
|
||||
#define LENGTH_BYTES 1
|
||||
|
||||
// the size of the rf modules internal FIFO buffers
|
||||
#define FIFO_SIZE 64
|
||||
@ -217,12 +224,13 @@ static const struct pios_rfm22b_transition rfm22b_transitions[RADIO_STATE_NUM_ST
|
||||
[RADIO_STATE_RX_MODE] = {
|
||||
.entry_fn = radio_setRxMode,
|
||||
.next_state = {
|
||||
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
|
||||
[RADIO_EVENT_INT_RECEIVED] = RADIO_STATE_RX_DATA,
|
||||
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
|
||||
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
|
||||
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
|
||||
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
|
||||
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
|
||||
[RADIO_EVENT_RX_MODE] = RADIO_STATE_RX_MODE,
|
||||
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
|
||||
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
|
||||
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
|
||||
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RADIO_STATE_RX_DATA] = {
|
||||
@ -294,33 +302,37 @@ static const struct pios_rfm22b_transition rfm22b_transitions[RADIO_STATE_NUM_ST
|
||||
};
|
||||
|
||||
// xtal 10 ppm, 434MHz
|
||||
static const uint32_t data_rate[] = { 9600, 19200, 32000, 57600, 64000, 128000, 192000, 256000 };
|
||||
static const uint8_t modulation_index[] = { 1, 1, 1, 1, 1, 1, 1, 1 };
|
||||
static const uint32_t data_rate[] = { 9600, 19200, 32000, 57600, 128000, 192000, 256000 };
|
||||
static const uint8_t modulation_index[] = { 1, 1, 1, 1, 1, 1, 1 };
|
||||
|
||||
static const uint8_t reg_1C[] = { 0x01, 0x05, 0x16, 0x06, 0x07, 0x83, 0x8A, 0x8C }; // rfm22_if_filter_bandwidth
|
||||
static const uint8_t reg_1C[] = { 0x01, 0x05, 0x16, 0x06, 0x83, 0x8A, 0x8C }; // rfm22_if_filter_bandwidth
|
||||
|
||||
static const uint8_t reg_1D[] = { 0x40, 0x40, 0x44, 0x40, 0x44, 0x44, 0x44, 0x44 }; // rfm22_afc_loop_gearshift_override
|
||||
static const uint8_t reg_1E[] = { 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x02 }; // rfm22_afc_timing_control
|
||||
static const uint8_t reg_1D[] = { 0x40, 0x40, 0x44, 0x40, 0x44, 0x44, 0x44 }; // rfm22_afc_loop_gearshift_override
|
||||
static const uint8_t reg_1E[] = { 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x02 }; // rfm22_afc_timing_control
|
||||
|
||||
static const uint8_t reg_1F[] = { 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03 }; // rfm22_clk_recovery_gearshift_override
|
||||
static const uint8_t reg_20[] = { 0xA1, 0xD0, 0x3F, 0x45, 0x3F, 0x5E, 0x3F, 0x2F }; // rfm22_clk_recovery_oversampling_ratio
|
||||
static const uint8_t reg_21[] = { 0x20, 0x00, 0x02, 0x01, 0x02, 0x01, 0x02, 0x02 }; // rfm22_clk_recovery_offset2
|
||||
static const uint8_t reg_1F[] = { 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03 }; // rfm22_clk_recovery_gearshift_override
|
||||
static const uint8_t reg_20[] = { 0xA1, 0xD0, 0x3F, 0x45, 0x5E, 0x3F, 0x2F }; // rfm22_clk_recovery_oversampling_ratio
|
||||
static const uint8_t reg_21[] = { 0x20, 0x00, 0x02, 0x01, 0x01, 0x02, 0x02 }; // rfm22_clk_recovery_offset2
|
||||
static const uint8_t reg_22[] = { 0x4E, 0x9D, 0x0C, 0xD7, 0x0c, 0x5D, 0x0C, 0xBB }; // rfm22_clk_recovery_offset1
|
||||
static const uint8_t reg_23[] = { 0xA5, 0x49, 0x4A, 0xDC, 0x4A, 0x86, 0x4A, 0x0D }; // rfm22_clk_recovery_offset0
|
||||
static const uint8_t reg_23[] = { 0xA5, 0x49, 0x4A, 0xDC, 0x86, 0x4A, 0x0D }; // rfm22_clk_recovery_offset0
|
||||
static const uint8_t reg_24[] = { 0x00, 0x00, 0x07, 0x07, 0x07, 0x05, 0x07, 0x07 }; // rfm22_clk_recovery_timing_loop_gain1
|
||||
static const uint8_t reg_25[] = { 0x34, 0x8, 0xFF, 0x6E, 0xFF, 0x74, 0xFF, 0xFF }; // rfm22_clk_recovery_timing_loop_gain0
|
||||
static const uint8_t reg_25[] = { 0x34, 0x8, 0xFF, 0x6E, 0x74, 0xFF, 0xFF }; // rfm22_clk_recovery_timing_loop_gain0
|
||||
|
||||
static const uint8_t reg_2A[] = { 0x1E, 0x24, 0x17, 0x2D, 0x31, 0x50, 0x50, 0x50 }; // rfm22_afc_limiter .. AFC_pull_in_range = <20>AFCLimiter[7:0] x (hbsel+1) x 625 Hz
|
||||
static const uint8_t reg_2A[] = { 0x1E, 0x24, 0x17, 0x2D, 0x50, 0x50, 0x50 }; // rfm22_afc_limiter .. AFC_pull_in_range = <20>AFCLimiter[7:0] x (hbsel+1) x 625 Hz
|
||||
|
||||
static const uint8_t reg_58[] = { 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80 }; // rfm22_cpcuu
|
||||
static const uint8_t reg_69[] = { 0x60, 0x60, 0x20, 0x60, 0x20, 0x20, 0x20, 0x20 }; // rfm22_agc_override1
|
||||
static const uint8_t reg_6E[] = { 0x4E, 0x9D, 0x08, 0x0E, 0x10, 0x20, 0x31, 0x41 }; // rfm22_tx_data_rate1
|
||||
static const uint8_t reg_6F[] = { 0xA5, 0x49, 0x31, 0xBF, 0x62, 0xC5, 0x27, 0x89 }; // rfm22_tx_data_rate0
|
||||
static const uint8_t reg_58[] = { 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80 }; // rfm22_cpcuu
|
||||
static const uint8_t reg_69[] = { 0x60, 0x60, 0x20, 0x60, 0x20, 0x20, 0x20 }; // rfm22_agc_override1
|
||||
static const uint8_t reg_6E[] = { 0x4E, 0x9D, 0x08, 0x0E, 0x20, 0x31, 0x41 }; // rfm22_tx_data_rate1
|
||||
static const uint8_t reg_6F[] = { 0xA5, 0x49, 0x31, 0xBF, 0xC5, 0x27, 0x89 }; // rfm22_tx_data_rate0
|
||||
|
||||
static const uint8_t reg_70[] = { 0x2C, 0x2C, 0x0D, 0x0C, 0x0C, 0x0D, 0x0D, 0x0D }; // rfm22_modulation_mode_control1
|
||||
static const uint8_t reg_71[] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23 }; // rfm22_modulation_mode_control2
|
||||
static const uint8_t reg_70[] = { 0x2C, 0x2C, 0x0D, 0x0C, 0x0D, 0x0D, 0x0D }; // rfm22_modulation_mode_control1
|
||||
static const uint8_t reg_71[] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23 }; // rfm22_modulation_mode_control2
|
||||
|
||||
static const uint8_t reg_72[] = { 0x30, 0x48, 0x1A, 0x2E, 0x33, 0x66, 0x9A, 0xCD }; // rfm22_frequency_deviation
|
||||
static const uint8_t reg_72[] = { 0x30, 0x48, 0x1A, 0x2E, 0x66, 0x9A, 0xCD }; // rfm22_frequency_deviation
|
||||
|
||||
static const uint8_t packet_time[] = { 80, 40, 25, 15, 8, 6, 5 };
|
||||
static const uint8_t packet_time_ppm[] = { 26, 25, 25, 15, 8, 6, 5 };
|
||||
static const uint8_t num_channels[] = { 3, 3, 4, 6, 9, 12, 15 };
|
||||
|
||||
static struct pios_rfm22b_dev *g_rfm22b_dev = NULL;
|
||||
|
||||
@ -364,6 +376,9 @@ 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;
|
||||
|
||||
// Initialzie the PPM callback.
|
||||
rfm22b_dev->ppm_callback = NULL;
|
||||
|
||||
// Initialize the stats.
|
||||
rfm22b_dev->stats.packets_per_sec = 0;
|
||||
rfm22b_dev->stats.rx_good = 0;
|
||||
@ -381,7 +396,8 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
|
||||
rfm22b_dev->stats.tx_failure = 0;
|
||||
|
||||
// Initialize the channels.
|
||||
PIOS_RFM22B_SetChannelConfig(*rfm22b_id, RFM22B_DEFAULT_NUM_CHANNELS, RFM22B_DEFAULT_MIN_CHANNEL, RFM22B_DEFAULT_MAX_CHANNEL, RFM22B_DEFAULT_CHANNEL_SET, RFM22B_DEFAULT_PACKET_PERIOD, false);
|
||||
PIOS_RFM22B_SetChannelConfig(*rfm22b_id, RFM22B_DEFAULT_RX_DATARATE, RFM22B_DEFAULT_MIN_CHANNEL,
|
||||
RFM22B_DEFAULT_MAX_CHANNEL, RFM22B_DEFAULT_CHANNEL_SET, false, false, false, false);
|
||||
|
||||
// Create the event queue
|
||||
rfm22b_dev->eventQueue = xQueueCreate(EVENT_QUEUE_SIZE, sizeof(enum pios_radio_event));
|
||||
@ -521,33 +537,54 @@ void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr)
|
||||
* The channel spacing is 10MHz / 250 = 40kHz
|
||||
*
|
||||
* @param[in] rfm22b_id The RFM22B device index.
|
||||
* @param[in] num_channels The number of channels to use for frequency hopping.
|
||||
* @param[in] datarate The desired datarate.
|
||||
* @param[in] min_chan The minimum channel.
|
||||
* @param[in] max_chan The maximum channel.
|
||||
* @param[in] chan_set The "seed" for selecting a channel sequence.
|
||||
* @param[in] packet_period The fixed time alloted to sending a single packet
|
||||
* @param[in] coordinator Is this modem an coordinator.
|
||||
* @param[in] ppm_mode Should this modem send/receive ppm packets?
|
||||
* @param[in] oneway Only the coordinator can send packets if true.
|
||||
*/
|
||||
void PIOS_RFM22B_SetChannelConfig(uint32_t rfm22b_id, uint8_t num_chan, uint8_t min_chan, uint8_t max_chan, uint8_t chan_set, uint8_t packet_period, bool oneway)
|
||||
void PIOS_RFM22B_SetChannelConfig(uint32_t rfm22b_id, enum rfm22b_datarate datarate, uint8_t min_chan, uint8_t max_chan, uint8_t chan_set, bool coordinator, bool oneway, bool ppm_mode, bool ppm_only)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
|
||||
return;
|
||||
}
|
||||
rfm22b_dev->packet_period = packet_period;
|
||||
rfm22b_dev->num_channels = num_chan;
|
||||
ppm_mode = ppm_mode || ppm_only;
|
||||
rfm22b_dev->coordinator = coordinator;
|
||||
rfm22b_dev->one_way_link = oneway;
|
||||
rfm22b_dev->ppm_send_mode = ppm_mode && coordinator;
|
||||
rfm22b_dev->ppm_recv_mode = ppm_mode && !coordinator;
|
||||
if (ppm_mode && (datarate <= RFM22B_PPM_ONLY_DATARATE)) {
|
||||
ppm_only = true;
|
||||
}
|
||||
rfm22b_dev->ppm_only_mode = ppm_only;
|
||||
if (ppm_only) {
|
||||
rfm22b_dev->datarate = RFM22B_PPM_ONLY_DATARATE;
|
||||
} else {
|
||||
rfm22b_dev->datarate = datarate;
|
||||
}
|
||||
rfm22b_dev->packet_time = (ppm_mode ? packet_time_ppm[datarate] : packet_time[datarate]);
|
||||
|
||||
// Find the first N channels that meet the min/max criteria out of the random channel list.
|
||||
uint8_t num_found = 0;
|
||||
for (uint16_t i = 0; (i < RFM22B_NUM_CHANNELS) && (num_found < num_chan); ++i) {
|
||||
for (uint16_t i = 0; (i < RFM22B_NUM_CHANNELS) && (num_found < num_channels[datarate]); ++i) {
|
||||
uint8_t idx = (i + chan_set) % RFM22B_NUM_CHANNELS;
|
||||
uint8_t chan = channel_list[idx];
|
||||
if ((chan >= min_chan) && (chan <= max_chan)) {
|
||||
rfm22b_dev->channels[num_found++] = chan;
|
||||
}
|
||||
}
|
||||
|
||||
// Calculate the maximum packet length from the datarate.
|
||||
float bytes_per_period = (float)data_rate[datarate] * (float)(rfm22b_dev->packet_time - 2) / 9000;
|
||||
|
||||
rfm22b_dev->max_packet_len = bytes_per_period - TX_PREAMBLE_NIBBLES / 2 - SYNC_BYTES - HEADER_BYTES - LENGTH_BYTES;
|
||||
if (rfm22b_dev->max_packet_len > RFM22B_MAX_PACKET_LEN) {
|
||||
rfm22b_dev->max_packet_len = RFM22B_MAX_PACKET_LEN;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -656,11 +693,6 @@ bool PIOS_RFM22B_ReceivePacket(uint32_t rfm22b_id, uint8_t *p)
|
||||
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Are we already in Rx mode?
|
||||
if ((rfm22b_dev->rfm22b_state == RFM22B_STATE_RX_MODE) || (rfm22b_dev->rfm22b_state == RFM22B_STATE_RX_WAIT)) {
|
||||
return false;
|
||||
}
|
||||
rfm22b_dev->rx_packet_handle = p;
|
||||
|
||||
// Claim the SPI bus.
|
||||
@ -1005,6 +1037,61 @@ pios_rfm22b_int_result PIOS_RFM22B_ProcessRx(uint32_t rfm22b_id)
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PPM packet received callback.
|
||||
*
|
||||
* @param[in] rfm22b_dev The RFM22B device ID.
|
||||
* @param[in] cb The callback function pointer.
|
||||
*/
|
||||
void PIOS_RFM22B_SetPPMCallback(uint32_t rfm22b_id, PPMReceivedCallback cb)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
|
||||
return;
|
||||
}
|
||||
|
||||
rfm22b_dev->ppm_callback = cb;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PPM values to be transmitted.
|
||||
*
|
||||
* @param[in] rfm22b_dev The RFM22B device ID.
|
||||
* @param[in] channels The PPM channel values.
|
||||
*/
|
||||
extern void PIOS_RFM22B_PPMSet(uint32_t rfm22b_id, int16_t *channels)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
|
||||
return;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
|
||||
rfm22b_dev->ppm[i] = channels[i];
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Fetch the PPM values that have been received.
|
||||
*
|
||||
* @param[in] rfm22b_dev The RFM22B device structure pointer.
|
||||
* @param[out] channels The PPM channel values.
|
||||
*/
|
||||
extern void PIOS_RFM22B_PPMGet(uint32_t rfm22b_id, int16_t *channels)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
|
||||
return;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
|
||||
channels[i] = rfm22b_dev->ppm[i];
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Validate that the device structure is valid.
|
||||
*
|
||||
@ -1057,42 +1144,44 @@ static void pios_rfm22_task(void *parameters)
|
||||
// Has it been too long since the last event?
|
||||
portTickType curTicks = xTaskGetTickCount();
|
||||
if (pios_rfm22_time_difference_ms(lastEventTicks, curTicks) > PIOS_RFM22B_SUPERVISOR_TIMEOUT) {
|
||||
// Transsition through an error event.
|
||||
rfm22_process_event(rfm22b_dev, RADIO_EVENT_ERROR);
|
||||
|
||||
// Clear the event queue.
|
||||
enum pios_radio_event event;
|
||||
while (xQueueReceive(rfm22b_dev->eventQueue, &event, 0) == pdTRUE) {
|
||||
// Do nothing;
|
||||
}
|
||||
lastEventTicks = xTaskGetTickCount();
|
||||
|
||||
// Transsition through an error event.
|
||||
rfm22_process_event(rfm22b_dev, RADIO_EVENT_ERROR);
|
||||
}
|
||||
}
|
||||
|
||||
// Change channels if necessary.
|
||||
rfm22_changeChannel(rfm22b_dev);
|
||||
if (rfm22_changeChannel(rfm22b_dev)) {
|
||||
rfm22_process_event(rfm22b_dev, RADIO_EVENT_RX_MODE);
|
||||
}
|
||||
|
||||
portTickType curTicks = xTaskGetTickCount();
|
||||
// Have we been sending / receiving this packet too long?
|
||||
|
||||
if ((rfm22b_dev->packet_start_ticks > 0) &&
|
||||
(pios_rfm22_time_difference_ms(rfm22b_dev->packet_start_ticks, curTicks) > (rfm22b_dev->packet_period * 3))) {
|
||||
(pios_rfm22_time_difference_ms(rfm22b_dev->packet_start_ticks, curTicks) > (rfm22b_dev->packet_time * 3))) {
|
||||
rfm22_process_event(rfm22b_dev, RADIO_EVENT_TIMEOUT);
|
||||
}
|
||||
|
||||
// Send a packet if it's our time slice
|
||||
// Start transmitting a packet if it's time.
|
||||
bool time_to_send = rfm22_timeToSend(rfm22b_dev);
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
if (time_to_send) {
|
||||
D4_LED_ON;
|
||||
} else {
|
||||
D4_LED_OFF;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Start transmitting a packet if it's time.
|
||||
if (time_to_send && PIOS_RFM22B_InRxWait((uint32_t)rfm22b_dev)) {
|
||||
// If the on_sync_channel flag is set, it means that we were on the sync channel, but no packet was received, so transition to a non-connected state.
|
||||
if (rfm22b_dev->on_sync_channel) {
|
||||
if (!rfm22_isCoordinator(rfm22b_dev) && rfm22b_dev->on_sync_channel) {
|
||||
rfm22b_dev->on_sync_channel = false;
|
||||
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED) {
|
||||
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_CONNECTING;
|
||||
@ -1234,7 +1323,7 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
}
|
||||
|
||||
// Initialize the state
|
||||
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_DISCONNECTED;
|
||||
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_ENABLED;
|
||||
|
||||
// Initialize the packets.
|
||||
rfm22b_dev->rx_packet_len = 0;
|
||||
@ -1442,16 +1531,7 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
static void pios_rfm22_setDatarate(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
enum rfm22b_datarate datarate = rfm22b_dev->datarate;
|
||||
bool data_whitening = true;
|
||||
uint32_t datarate_bps = data_rate[datarate];
|
||||
|
||||
// Calculate the maximum packet length from the datarate.
|
||||
float bytes_per_period = (float)datarate_bps * (float)(rfm22b_dev->packet_period) / 9000;
|
||||
|
||||
rfm22b_dev->max_packet_len = bytes_per_period - TX_PREAMBLE_NIBBLES / 2 - SYNC_BYTES - HEADER_BYTES - 5;
|
||||
if (rfm22b_dev->max_packet_len > RFM22B_MAX_PACKET_LEN) {
|
||||
rfm22b_dev->max_packet_len = RFM22B_MAX_PACKET_LEN;
|
||||
}
|
||||
bool data_whitening = true;
|
||||
|
||||
// Claim the SPI bus.
|
||||
rfm22_claimBus(rfm22b_dev);
|
||||
@ -1649,9 +1729,9 @@ static void rfm22_rxFailure(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
*/
|
||||
static enum pios_radio_event radio_txStart(struct pios_rfm22b_dev *radio_dev)
|
||||
{
|
||||
uint8_t *p = radio_dev->rx_packet;
|
||||
uint8_t *p = radio_dev->tx_packet;
|
||||
uint8_t len = 0;
|
||||
uint8_t max_data_len = radio_dev->max_packet_len - RS_ECC_NPARITY;
|
||||
uint8_t max_data_len = radio_dev->max_packet_len - (radio_dev->ppm_only_mode ? 0 : RS_ECC_NPARITY);
|
||||
|
||||
// Don't send if it's not our turn, or if we're receiving a packet.
|
||||
if (!rfm22_timeToSend(radio_dev) || !PIOS_RFM22B_InRxWait((uint32_t)radio_dev)) {
|
||||
@ -1663,10 +1743,44 @@ static enum pios_radio_event radio_txStart(struct pios_rfm22b_dev *radio_dev)
|
||||
return RADIO_EVENT_RX_MODE;
|
||||
}
|
||||
|
||||
// Try to get some data to send
|
||||
if (radio_dev->tx_out_cb) {
|
||||
// Should we append PPM data to the packet?
|
||||
if (radio_dev->ppm_send_mode) {
|
||||
len = RFM22B_PPM_NUM_CHANNELS + (radio_dev->ppm_only_mode ? 2 : 1);
|
||||
|
||||
// Ensure we can fit the PPM data in the packet.
|
||||
if (max_data_len < len) {
|
||||
return RADIO_EVENT_RX_MODE;
|
||||
}
|
||||
|
||||
// The first byte is a bitmask of valid channels.
|
||||
p[0] = 0;
|
||||
|
||||
// Read the PPM input.
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
|
||||
int32_t val = radio_dev->ppm[i];
|
||||
if ((val == PIOS_RCVR_INVALID) || (val == PIOS_RCVR_TIMEOUT)) {
|
||||
p[i + 1] = 0;
|
||||
} else {
|
||||
p[0] |= 1 << i;
|
||||
p[i + 1] = (val < 1000) ? 0 : ((val >= 1900) ? 255 : (uint8_t)(256 * (val - 1000) / 900));
|
||||
}
|
||||
}
|
||||
|
||||
// The last byte is a CRC.
|
||||
if (radio_dev->ppm_only_mode) {
|
||||
uint8_t crc = 0;
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS + 1; ++i) {
|
||||
crc = PIOS_CRC_updateByte(crc, p[i]);
|
||||
}
|
||||
p[RFM22B_PPM_NUM_CHANNELS + 1] = crc;
|
||||
}
|
||||
}
|
||||
|
||||
// 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
|
||||
bool need_yield = false;
|
||||
len = (radio_dev->tx_out_cb)(radio_dev->tx_out_context, p, max_data_len, NULL, &need_yield);
|
||||
len += (radio_dev->tx_out_cb)(radio_dev->tx_out_context, p + len, max_data_len - len, NULL, &need_yield);
|
||||
}
|
||||
|
||||
// Always send a packet on the sync channel if this modem is a coordinator.
|
||||
@ -1677,14 +1791,13 @@ static enum pios_radio_event radio_txStart(struct pios_rfm22b_dev *radio_dev)
|
||||
// Increment the packet sequence number.
|
||||
radio_dev->stats.tx_seq++;
|
||||
|
||||
// Change the channel.
|
||||
rfm22_changeChannel(radio_dev);
|
||||
|
||||
// Add the error correcting code.
|
||||
if (len != 0) {
|
||||
encode_data((unsigned char *)p, len, (unsigned char *)p);
|
||||
if (!radio_dev->ppm_only_mode) {
|
||||
if (len != 0) {
|
||||
encode_data((unsigned char *)p, len, (unsigned char *)p);
|
||||
}
|
||||
len += RS_ECC_NPARITY;
|
||||
}
|
||||
len += RS_ECC_NPARITY;
|
||||
|
||||
// Transmit the packet.
|
||||
PIOS_RFM22B_TransmitPacket((uint32_t)radio_dev, p, len);
|
||||
@ -1693,7 +1806,7 @@ static enum pios_radio_event radio_txStart(struct pios_rfm22b_dev *radio_dev)
|
||||
}
|
||||
|
||||
/**
|
||||
* Receive packet data.
|
||||
* Transmit packet data.
|
||||
*
|
||||
* @param[in] rfm22b_dev The device structure
|
||||
* @return enum pios_radio_event The next event to inject
|
||||
@ -1749,19 +1862,66 @@ 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)
|
||||
{
|
||||
uint8_t data_len = rx_len - RS_ECC_NPARITY;
|
||||
// Attempt to correct any errors in the packet.
|
||||
bool good_packet = true;
|
||||
bool corrected_packet = false;
|
||||
uint8_t data_len = rx_len;
|
||||
|
||||
if (data_len > 0) {
|
||||
decode_data((unsigned char *)p, rx_len);
|
||||
// We don't rsencode ppm only packets.
|
||||
if (!radio_dev->ppm_only_mode) {
|
||||
data_len -= RS_ECC_NPARITY;
|
||||
|
||||
good_packet = check_syndrome() == 0;
|
||||
// We have an error. Try to correct it.
|
||||
if (!good_packet && (correct_errors_erasures((unsigned char *)p, rx_len, 0, 0) != 0)) {
|
||||
// We corrected it
|
||||
corrected_packet = true;
|
||||
// Attempt to correct any errors in the packet.
|
||||
if (data_len > 0) {
|
||||
decode_data((unsigned char *)p, rx_len);
|
||||
good_packet = check_syndrome() == 0;
|
||||
|
||||
// We have an error. Try to correct it.
|
||||
if (!good_packet && (correct_errors_erasures((unsigned char *)p, rx_len, 0, 0) != 0)) {
|
||||
// We corrected it
|
||||
corrected_packet = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Should we pull PPM data off of the head of the packet?
|
||||
if ((good_packet || corrected_packet) && radio_dev->ppm_recv_mode) {
|
||||
uint8_t ppm_len = RFM22B_PPM_NUM_CHANNELS + (radio_dev->ppm_only_mode ? 2 : 1);
|
||||
|
||||
// Ensure the packet it long enough
|
||||
if (data_len < ppm_len) {
|
||||
good_packet = false;
|
||||
}
|
||||
|
||||
// Verify the CRC if this is a PPM only packet.
|
||||
if ((good_packet || corrected_packet) && radio_dev->ppm_only_mode) {
|
||||
uint8_t crc = 0;
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS + 1; ++i) {
|
||||
crc = PIOS_CRC_updateByte(crc, p[i]);
|
||||
}
|
||||
if (p[RFM22B_PPM_NUM_CHANNELS + 1] != crc) {
|
||||
good_packet = false;
|
||||
corrected_packet = false;
|
||||
}
|
||||
}
|
||||
|
||||
if (good_packet || corrected_packet) {
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
|
||||
// Is this a valid channel?
|
||||
if (p[0] & (1 << i)) {
|
||||
uint32_t val = p[i + 1];
|
||||
radio_dev->ppm[i] = (uint16_t)(1000 + val * 900 / 256);
|
||||
} else {
|
||||
radio_dev->ppm[i] = PIOS_RCVR_INVALID;
|
||||
}
|
||||
}
|
||||
|
||||
p += RFM22B_PPM_NUM_CHANNELS + 1;
|
||||
data_len -= RFM22B_PPM_NUM_CHANNELS + 1;
|
||||
|
||||
// Call the PPM received callback if it's available.
|
||||
if (radio_dev->ppm_callback) {
|
||||
radio_dev->ppm_callback(radio_dev->ppm);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -1780,7 +1940,7 @@ 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) {
|
||||
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);
|
||||
}
|
||||
|
||||
@ -1985,10 +2145,14 @@ static void rfm22_synchronizeClock(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
portTickType start_time = rfm22b_dev->packet_start_ticks;
|
||||
|
||||
// This packet was transmitted on channel 0, calculate the time delta that will force us to transmit on channel 0 at the time this packet started.
|
||||
uint16_t frequency_hop_cycle_time = rfm22b_dev->packet_period * rfm22b_dev->num_channels;
|
||||
uint8_t num_chan = num_channels[rfm22b_dev->datarate];
|
||||
uint16_t frequency_hop_cycle_time = rfm22b_dev->packet_time * num_chan;
|
||||
uint16_t time_delta = start_time % frequency_hop_cycle_time;
|
||||
|
||||
rfm22b_dev->time_delta = frequency_hop_cycle_time - time_delta + 1;
|
||||
// Calculate the adjustment for the preamble
|
||||
uint8_t offset = (uint8_t)ceil(35000.0F / data_rate[rfm22b_dev->datarate]);
|
||||
|
||||
rfm22b_dev->time_delta = frequency_hop_cycle_time - time_delta + offset;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -2012,24 +2176,26 @@ static portTickType rfm22_coordinatorTime(struct pios_rfm22b_dev *rfm22b_dev, po
|
||||
*/
|
||||
static bool rfm22_timeToSend(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
portTickType time = rfm22_coordinatorTime(rfm22b_dev, xTaskGetTickCount());
|
||||
bool is_coordinator = rfm22_isCoordinator(rfm22b_dev);
|
||||
portTickType time = rfm22_coordinatorTime(rfm22b_dev, xTaskGetTickCount());
|
||||
bool is_coordinator = rfm22_isCoordinator(rfm22b_dev);
|
||||
|
||||
// If this is a one-way link, only the coordinator can send.
|
||||
uint8_t packet_period = rfm22b_dev->packet_time;
|
||||
|
||||
if (rfm22b_dev->one_way_link) {
|
||||
if (is_coordinator) {
|
||||
return ((time -1) % (rfm22b_dev->packet_period)) == 0;
|
||||
return ((time - 1) % (packet_period)) == 0;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
if (!is_coordinator) {
|
||||
time += rfm22b_dev->packet_period - 1;
|
||||
time += packet_period - 1;
|
||||
} else {
|
||||
time -= 1;
|
||||
}
|
||||
return (time % (rfm22b_dev->packet_period * 2)) == 0;
|
||||
return (time % (packet_period * 2)) == 0;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -2041,11 +2207,14 @@ static bool rfm22_timeToSend(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
static uint8_t rfm22_calcChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t index)
|
||||
{
|
||||
// Make sure we don't index outside of the range.
|
||||
uint8_t idx = index % rfm22b_dev->num_channels;
|
||||
uint8_t num_chan = num_channels[rfm22b_dev->datarate];
|
||||
uint8_t idx = index % num_chan;
|
||||
|
||||
rfm22b_dev->channel_index = idx;
|
||||
if (idx == 0) {
|
||||
rfm22b_dev->on_sync_channel = true;
|
||||
if (idx != rfm22b_dev->channel_index) {
|
||||
rfm22b_dev->channel_index = idx;
|
||||
if (idx == 0) {
|
||||
rfm22b_dev->on_sync_channel = true;
|
||||
}
|
||||
}
|
||||
return rfm22b_dev->channels[idx];
|
||||
}
|
||||
@ -2060,7 +2229,8 @@ static uint8_t rfm22_calcChannelFromClock(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
portTickType time = rfm22_coordinatorTime(rfm22b_dev, xTaskGetTickCount());
|
||||
// Divide time into 8ms blocks. Coordinator sends in first 2 ms, and remote send in 5th and 6th ms.
|
||||
// Channel changes occur in the last 2 ms.
|
||||
uint8_t n = (time / rfm22b_dev->packet_period) % rfm22b_dev->num_channels;
|
||||
uint8_t num_chan = num_channels[rfm22b_dev->datarate];
|
||||
uint8_t n = (time / rfm22b_dev->packet_time) % num_chan;
|
||||
|
||||
return rfm22_calcChannel(rfm22b_dev, n);
|
||||
}
|
||||
|
@ -55,31 +55,12 @@ const struct pios_com_driver pios_rfm22b_com_driver = {
|
||||
/**
|
||||
* Changes the baud rate of the RFM22B peripheral without re-initialising.
|
||||
*
|
||||
* @param[in] rfm22b_id RFM22B name (GPS, TELEM, AUX)
|
||||
* @param[in] rfm22b_id The defice ID
|
||||
* @param[in] baud Requested baud rate
|
||||
*/
|
||||
static void PIOS_RFM22B_COM_ChangeBaud(uint32_t rfm22b_id, uint32_t baud)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
|
||||
return;
|
||||
}
|
||||
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
|
||||
enum rfm22b_datarate datarate = RFM22_datarate_64000;
|
||||
if (baud <= 9600) {
|
||||
datarate = RFM22_datarate_19200;
|
||||
} else if (baud <= 19200) {
|
||||
datarate = RFM22_datarate_32000;
|
||||
} else if (baud <= 38400) {
|
||||
datarate = RFM22_datarate_57600;
|
||||
} else if (baud <= 57600) {
|
||||
datarate = RFM22_datarate_128000;
|
||||
} else if (baud <= 115200) {
|
||||
datarate = RFM22_datarate_192000;
|
||||
}
|
||||
rfm22b_dev->datarate = datarate;
|
||||
}
|
||||
static void PIOS_RFM22B_COM_ChangeBaud(__attribute__((unused)) uint32_t rfm22b_id,
|
||||
__attribute__((unused)) uint32_t baud)
|
||||
{}
|
||||
|
||||
/**
|
||||
* Start a receive from the COM device
|
||||
@ -97,14 +78,10 @@ static void PIOS_RFM22B_COM_RxStart(__attribute__((unused)) uint32_t rfm22b_id,
|
||||
* @param[in] rfm22b_dev The device ID.
|
||||
* @param[in] tx_bytes_available The number of bytes available to transmit
|
||||
*/
|
||||
static void PIOS_RFM22B_COM_TxStart(uint32_t rfm22b_id, __attribute__((unused)) uint16_t tx_bytes_avail)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
static void PIOS_RFM22B_COM_TxStart(__attribute__((unused)) uint32_t rfm22b_id,
|
||||
__attribute__((unused)) uint16_t tx_bytes_avail)
|
||||
{}
|
||||
|
||||
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Register the callback to pass received data to
|
||||
|
@ -36,6 +36,7 @@
|
||||
|
||||
/* Constant definitions */
|
||||
enum gpio_direction { GPIO0_TX_GPIO1_RX, GPIO0_RX_GPIO1_TX };
|
||||
#define RFM22B_PPM_NUM_CHANNELS 8
|
||||
|
||||
/* Global Types */
|
||||
struct pios_rfm22b_cfg {
|
||||
@ -45,6 +46,7 @@ struct pios_rfm22b_cfg {
|
||||
uint8_t slave_num;
|
||||
enum gpio_direction gpio_direction;
|
||||
};
|
||||
typedef void (*PPMReceivedCallback)(const int16_t *channels);
|
||||
|
||||
enum rfm22b_tx_power {
|
||||
RFM22_tx_pwr_txpow_0 = 0x00, // +1dBm .. 1.25mW
|
||||
@ -101,8 +103,7 @@ struct rfm22b_stats {
|
||||
extern int32_t PIOS_RFM22B_Init(uint32_t *rfb22b_id, uint32_t spi_id, uint32_t slave_num, const struct pios_rfm22b_cfg *cfg);
|
||||
extern void PIOS_RFM22B_Reinit(uint32_t rfb22b_id);
|
||||
extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr);
|
||||
extern void PIOS_RFM22B_SetChannelConfig(uint32_t rfm22b_id, uint8_t num_chan, uint8_t min_chan, uint8_t max_chan, uint8_t chan_set, uint8_t packet_period, bool oneway);
|
||||
extern void PIOS_RFM22B_SetCoordinator(uint32_t rfm22b_id, bool coordinator);
|
||||
extern void PIOS_RFM22B_SetChannelConfig(uint32_t rfm22b_id, enum rfm22b_datarate datarate, uint8_t min_chan, uint8_t max_chan, uint8_t chan_set, bool coordinator, bool oneway, bool ppm_mode, bool ppm_only);
|
||||
extern void PIOS_RFM22B_SetCoordinatorID(uint32_t rfm22b_id, uint32_t coord_id);
|
||||
extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id);
|
||||
extern void PIOS_RFM22B_GetStats(uint32_t rfm22b_id, struct rfm22b_stats *stats);
|
||||
@ -113,6 +114,9 @@ extern bool PIOS_RFM22B_ReceivePacket(uint32_t rfm22b_id, uint8_t *p);
|
||||
extern bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, uint8_t *p, uint8_t len);
|
||||
extern pios_rfm22b_int_result PIOS_RFM22B_ProcessTx(uint32_t rfm22b_id);
|
||||
extern pios_rfm22b_int_result PIOS_RFM22B_ProcessRx(uint32_t rfm22b_id);
|
||||
extern void PIOS_RFM22B_SetPPMCallback(uint32_t rfm22b_id, PPMReceivedCallback cb);
|
||||
extern void PIOS_RFM22B_PPMSet(uint32_t rfm22b_id, int16_t *channels);
|
||||
extern void PIOS_RFM22B_PPMGet(uint32_t rfm22b_id, int16_t *channels);
|
||||
|
||||
/* Global Variables */
|
||||
extern const struct pios_com_driver pios_rfm22b_com_driver;
|
||||
|
@ -718,38 +718,50 @@ struct pios_rfm22b_dev {
|
||||
struct rfm22b_stats stats;
|
||||
|
||||
// Stats
|
||||
uint16_t errors;
|
||||
uint16_t errors;
|
||||
|
||||
// RSSI in dBm
|
||||
int8_t rssi_dBm;
|
||||
int8_t rssi_dBm;
|
||||
|
||||
// The tx data packet
|
||||
uint8_t tx_packet[RFM22B_MAX_PACKET_LEN];
|
||||
uint8_t tx_packet[RFM22B_MAX_PACKET_LEN];
|
||||
// The current tx packet
|
||||
uint8_t *tx_packet_handle;
|
||||
uint8_t *tx_packet_handle;
|
||||
// The tx data read index
|
||||
uint16_t tx_data_rd;
|
||||
uint16_t tx_data_rd;
|
||||
// The tx data write index
|
||||
uint16_t tx_data_wr;
|
||||
uint16_t tx_data_wr;
|
||||
// The tx packet sequence number
|
||||
uint16_t tx_seq;
|
||||
uint16_t tx_seq;
|
||||
|
||||
// The rx data packet
|
||||
uint8_t rx_packet[RFM22B_MAX_PACKET_LEN];
|
||||
uint8_t rx_packet[RFM22B_MAX_PACKET_LEN];
|
||||
// The rx data packet
|
||||
uint8_t *rx_packet_handle;
|
||||
uint8_t *rx_packet_handle;
|
||||
// The receive buffer write index
|
||||
uint16_t rx_buffer_wr;
|
||||
uint16_t rx_buffer_wr;
|
||||
// The receive buffer write index
|
||||
uint16_t rx_packet_len;
|
||||
uint16_t rx_packet_len;
|
||||
|
||||
// The PPM buffer
|
||||
int16_t ppm[RFM22B_PPM_NUM_CHANNELS];
|
||||
// The PPM packet received callback.
|
||||
PPMReceivedCallback ppm_callback;
|
||||
|
||||
// The id that the packet was received from
|
||||
uint32_t rx_destination_id;
|
||||
// The maximum packet length (including header, etc.)
|
||||
uint8_t max_packet_len;
|
||||
// The time alloted for transmission of a packet.
|
||||
uint8_t packet_period;
|
||||
// The packet transmit time in ms.
|
||||
uint8_t packet_time;
|
||||
// Do all packets originate from the coordinator modem?
|
||||
bool one_way_link;
|
||||
// Should this modem send PPM data?
|
||||
bool ppm_send_mode;
|
||||
// Should this modem receive PPM data?
|
||||
bool ppm_recv_mode;
|
||||
// Are we sending / receiving only PPM data?
|
||||
bool ppm_only_mode;
|
||||
|
||||
// The channel list
|
||||
uint8_t channels[RFM22B_NUM_CHANNELS];
|
||||
|
@ -29,6 +29,7 @@
|
||||
|
||||
#include "inc/openpilot.h"
|
||||
#include <pios_board_info.h>
|
||||
#include <pios_ppm_out.h>
|
||||
#include <oplinksettings.h>
|
||||
#include <taskinfo.h>
|
||||
|
||||
@ -80,6 +81,7 @@ static void PIOS_InitUartMainPort();
|
||||
static void PIOS_InitUartFlexiPort();
|
||||
static void PIOS_InitPPMMainPort(bool input);
|
||||
static void PIOS_InitPPMFlexiPort(bool input);
|
||||
static void PIOS_Board_PPM_callback(const int16_t *channels);
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
@ -121,7 +123,10 @@ void PIOS_Board_Init(void)
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif /* PIOS_INCLUDE_RTC */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
OPLinkSettingsInitialize();
|
||||
OPLinkStatusInitialize();
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
@ -218,13 +223,72 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Allocate the uart buffers. */
|
||||
pios_uart_rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_RX_BUF_LEN);
|
||||
pios_uart_tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_TX_BUF_LEN);
|
||||
|
||||
// Configure the main port
|
||||
bool is_coordinator = (oplinkSettings.Coordinator == OPLINKSETTINGS_COORDINATOR_TRUE);
|
||||
bool is_oneway = (oplinkSettings.OneWay == OPLINKSETTINGS_ONEWAY_TRUE);
|
||||
bool ppm_only = (oplinkSettings.PPMOnly == OPLINKSETTINGS_PPMONLY_TRUE);
|
||||
bool ppm_mode = false;
|
||||
switch (oplinkSettings.MainPort) {
|
||||
case OPLINKSETTINGS_MAINPORT_TELEMETRY:
|
||||
case OPLINKSETTINGS_MAINPORT_SERIAL:
|
||||
/* Configure the main port for uart serial */
|
||||
PIOS_InitUartMainPort();
|
||||
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_MAIN;
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINPORT_PPM:
|
||||
PIOS_InitPPMMainPort(is_coordinator);
|
||||
ppm_mode = true;
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINPORT_DISABLED:
|
||||
break;
|
||||
}
|
||||
|
||||
// Configure the flexi port
|
||||
switch (oplinkSettings.FlexiPort) {
|
||||
case OPLINKSETTINGS_FLEXIPORT_TELEMETRY:
|
||||
case OPLINKSETTINGS_FLEXIPORT_SERIAL:
|
||||
/* Configure the flexi port as uart serial */
|
||||
PIOS_InitUartFlexiPort();
|
||||
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_FLEXI;
|
||||
break;
|
||||
case OPLINKSETTINGS_FLEXIPORT_PPM:
|
||||
PIOS_InitPPMFlexiPort(is_coordinator);
|
||||
ppm_mode = 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_DISABLED:
|
||||
break;
|
||||
}
|
||||
|
||||
// Initialize out status object.
|
||||
OPLinkStatusData oplinkStatus;
|
||||
OPLinkStatusGet(&oplinkStatus);
|
||||
|
||||
// Get our hardware information.
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
oplinkStatus.BoardType = bdinfo->board_type;
|
||||
PIOS_BL_HELPER_FLASH_Read_Description(oplinkStatus.Description, OPLINKSTATUS_DESCRIPTION_NUMELEM);
|
||||
PIOS_SYS_SerialNumberGetBinary(oplinkStatus.CPUSerial);
|
||||
oplinkStatus.BoardRevision = bdinfo->board_rev;
|
||||
|
||||
/* Initalize the RFM22B radio COM device. */
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
bool is_coordinator = (oplinkSettings.Coordinator == OPLINKSETTINGS_COORDINATOR_TRUE);
|
||||
{
|
||||
if (oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) {
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
|
||||
|
||||
// Configure the RFM22B device
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev);
|
||||
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
@ -240,31 +304,29 @@ void PIOS_Board_Init(void)
|
||||
tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint32_t comBaud = 9600;
|
||||
|
||||
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
|
||||
enum rfm22b_datarate datarate = RFM22_datarate_64000;
|
||||
switch (oplinkSettings.ComSpeed) {
|
||||
case OPLINKSETTINGS_COMSPEED_2400:
|
||||
comBaud = 2400;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_4800:
|
||||
comBaud = 4800;
|
||||
datarate = RFM22_datarate_9600;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_9600:
|
||||
comBaud = 9600;
|
||||
datarate = RFM22_datarate_19200;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_19200:
|
||||
comBaud = 19200;
|
||||
datarate = RFM22_datarate_32000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_38400:
|
||||
comBaud = 38400;
|
||||
datarate = RFM22_datarate_57600;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_57600:
|
||||
comBaud = 57600;
|
||||
datarate = RFM22_datarate_128000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_115200:
|
||||
comBaud = 115200;
|
||||
datarate = RFM22_datarate_192000;
|
||||
break;
|
||||
}
|
||||
PIOS_COM_ChangeBaud(pios_com_rfm22b_id, comBaud);
|
||||
|
||||
/* Set the modem Tx poer level */
|
||||
switch (oplinkSettings.MaxRFPower) {
|
||||
@ -298,65 +360,26 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
|
||||
// Set the radio configuration parameters.
|
||||
PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, oplinkSettings.NumChannels, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, oplinkSettings.ChannelSet,
|
||||
oplinkSettings.PacketTime, (oplinkSettings.OneWayLink == OPLINKSETTINGS_ONEWAYLINK_TRUE));
|
||||
PIOS_RFM22B_SetCoordinator(pios_rfm22b_id, is_coordinator);
|
||||
PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, datarate, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, oplinkSettings.ChannelSet, is_coordinator, is_oneway, ppm_mode, ppm_only);
|
||||
PIOS_RFM22B_SetCoordinatorID(pios_rfm22b_id, oplinkSettings.CoordID);
|
||||
|
||||
/* Set the PPM callback if we should be receiving PPM. */
|
||||
if (ppm_mode) {
|
||||
PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback);
|
||||
}
|
||||
|
||||
// Reinitilize the modem to affect te changes.
|
||||
PIOS_RFM22B_Reinit(pios_rfm22b_id);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
/* Allocate the uart buffers. */
|
||||
pios_uart_rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_RX_BUF_LEN);
|
||||
pios_uart_tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_TX_BUF_LEN);
|
||||
|
||||
// Configure the main port
|
||||
switch (oplinkSettings.MainPort) {
|
||||
case OPLINKSETTINGS_MAINPORT_TELEMETRY:
|
||||
case OPLINKSETTINGS_MAINPORT_SERIAL:
|
||||
/* Configure the main port for uart serial */
|
||||
PIOS_InitUartMainPort();
|
||||
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_MAIN;
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINPORT_PPM:
|
||||
PIOS_InitPPMMainPort(is_coordinator);
|
||||
break;
|
||||
case OPLINKSETTINGS_MAINPORT_DISABLED:
|
||||
break;
|
||||
} else {
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
|
||||
}
|
||||
|
||||
// Configure the flexi port
|
||||
switch (oplinkSettings.FlexiPort) {
|
||||
case OPLINKSETTINGS_FLEXIPORT_TELEMETRY:
|
||||
case OPLINKSETTINGS_FLEXIPORT_SERIAL:
|
||||
/* Configure the flexi port as uart serial */
|
||||
PIOS_InitUartFlexiPort();
|
||||
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_FLEXI;
|
||||
break;
|
||||
case OPLINKSETTINGS_FLEXIPORT_PPM:
|
||||
PIOS_InitPPMFlexiPort(is_coordinator);
|
||||
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_DISABLED:
|
||||
break;
|
||||
}
|
||||
// Update the object
|
||||
OPLinkStatusSet(&oplinkStatus);
|
||||
|
||||
// Update the com baud rate.
|
||||
uint32_t comBaud = 9600;
|
||||
switch (oplinkSettings.ComSpeed) {
|
||||
case OPLINKSETTINGS_COMSPEED_2400:
|
||||
comBaud = 2400;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_4800:
|
||||
comBaud = 4800;
|
||||
break;
|
||||
@ -458,6 +481,17 @@ static void PIOS_InitPPMFlexiPort(bool input)
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
}
|
||||
|
||||
static void PIOS_Board_PPM_callback(const int16_t *channels)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_PPM) && defined(PIOS_INCLUDE_PPM_OUT)
|
||||
if (pios_ppm_out_id) {
|
||||
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
|
||||
PIOS_PPM_OUT_Set(PIOS_PPM_OUTPUT, i, channels[i]);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PPM && PIOS_INCLUDE_PPM_OUT */
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
@ -77,6 +77,7 @@
|
||||
#define PIOS_WDG_RADIORX 0x0008
|
||||
#define PIOS_WDG_RFM22B 0x000f
|
||||
#define PIOS_WDG_PPMINPUT 0x0010
|
||||
#define PIOS_WDG_SERIALRX 0x0020
|
||||
|
||||
// ------------------------
|
||||
// TELEMETRY
|
||||
|
@ -117,7 +117,7 @@
|
||||
#define PIOS_INCLUDE_RFM22B
|
||||
#define PIOS_INCLUDE_RFM22B_COM
|
||||
/* #define PIOS_INCLUDE_PPM_OUT */
|
||||
#define PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
/* #define PIOS_RFM22B_DEBUG_ON_TELEM */
|
||||
|
||||
/* PIOS misc peripherals */
|
||||
/* #define PIOS_INCLUDE_VIDEO */
|
||||
|
@ -319,6 +319,17 @@ static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *ppm_cfg)
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id;
|
||||
}
|
||||
|
||||
static void PIOS_Board_PPM_callback(const int16_t *channels)
|
||||
{
|
||||
uint8_t max_chan = (RFM22B_PPM_NUM_CHANNELS < OPLINKRECEIVER_CHANNEL_NUMELEM) ? RFM22B_PPM_NUM_CHANNELS : OPLINKRECEIVER_CHANNEL_NUMELEM;
|
||||
OPLinkReceiverData opl_rcvr;
|
||||
|
||||
for (uint8_t i = 0; i < max_chan; ++i) {
|
||||
opl_rcvr.Channel[i] = channels[i];
|
||||
}
|
||||
OPLinkReceiverSet(&opl_rcvr);
|
||||
}
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core subsystems on this specific hardware
|
||||
@ -396,7 +407,10 @@ void PIOS_Board_Init(void)
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
HwSettingsInitialize();
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
OPLinkSettingsInitialize();
|
||||
OPLinkStatusInitialize();
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
@ -709,30 +723,24 @@ void PIOS_Board_Init(void)
|
||||
|
||||
/* Initalize the RFM22B radio COM device. */
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
|
||||
/* Fetch the OPinkSettings object. */
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
OPLinkSettingsGet(&oplinkSettings);
|
||||
|
||||
// Initialize out status object.
|
||||
OPLinkStatusData oplinkStatus;
|
||||
OPLinkStatusGet(&oplinkStatus);
|
||||
oplinkStatus.BoardType = bdinfo->board_type;
|
||||
PIOS_BL_HELPER_FLASH_Read_Description(oplinkStatus.Description, OPLINKSTATUS_DESCRIPTION_NUMELEM);
|
||||
PIOS_SYS_SerialNumberGetBinary(oplinkStatus.CPUSerial);
|
||||
oplinkStatus.BoardRevision = bdinfo->board_rev;
|
||||
|
||||
/* Is the radio turned on? */
|
||||
uint8_t hwsettings_radioport;
|
||||
HwSettingsRadioPortGet(&hwsettings_radioport);
|
||||
switch (hwsettings_radioport) {
|
||||
case HWSETTINGS_RADIOPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RADIOPORT_TELEMETRY:
|
||||
{
|
||||
// Initialize out status object.
|
||||
OPLinkStatusData oplinkStatus;
|
||||
OPLinkStatusGet(&oplinkStatus);
|
||||
oplinkStatus.BoardType = bdinfo->board_type;
|
||||
PIOS_BL_HELPER_FLASH_Read_Description(oplinkStatus.Description, OPLINKSTATUS_DESCRIPTION_NUMELEM);
|
||||
PIOS_SYS_SerialNumberGetBinary(oplinkStatus.CPUSerial);
|
||||
oplinkStatus.BoardRevision = bdinfo->board_rev;
|
||||
OPLinkStatusSet(&oplinkStatus);
|
||||
|
||||
/* Initialize the OPLinkSettings object. */
|
||||
OPLinkSettingsInitialize();
|
||||
|
||||
/* Fetch the OPinkSettings object. */
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
OPLinkSettingsGet(&oplinkSettings);
|
||||
|
||||
bool is_oneway = (oplinkSettings.OneWay == OPLINKSETTINGS_ONEWAY_TRUE);
|
||||
bool ppm_mode = (oplinkSettings.PPM == OPLINKSETTINGS_PPM_TRUE);
|
||||
bool ppm_only = (oplinkSettings.PPMOnly == OPLINKSETTINGS_PPMONLY_TRUE);
|
||||
if (oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) {
|
||||
/* Configure the RFM22B device. */
|
||||
const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev);
|
||||
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) {
|
||||
@ -749,12 +757,40 @@ void PIOS_Board_Init(void)
|
||||
tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
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.
|
||||
enum rfm22b_datarate datarate = RFM22_datarate_64000;
|
||||
switch (oplinkSettings.ComSpeed) {
|
||||
case OPLINKSETTINGS_COMSPEED_4800:
|
||||
datarate = RFM22_datarate_9600;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_9600:
|
||||
datarate = RFM22_datarate_19200;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_19200:
|
||||
datarate = RFM22_datarate_32000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_38400:
|
||||
datarate = RFM22_datarate_57600;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_57600:
|
||||
datarate = RFM22_datarate_128000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_115200:
|
||||
datarate = RFM22_datarate_192000;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Set the radio configuration parameters. */
|
||||
PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, oplinkSettings.NumChannels, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, oplinkSettings.ChannelSet,
|
||||
oplinkSettings.PacketTime, (oplinkSettings.OneWayLink == OPLINKSETTINGS_ONEWAYLINK_TRUE));
|
||||
PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, datarate, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, oplinkSettings.ChannelSet, false, is_oneway, ppm_mode, ppm_only);
|
||||
PIOS_RFM22B_SetCoordinatorID(pios_rfm22b_id, oplinkSettings.CoordID);
|
||||
|
||||
/* Set the PPM callback if we should be receiving PPM. */
|
||||
if (ppm_mode) {
|
||||
PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback);
|
||||
}
|
||||
|
||||
/* Set the modem Tx poer level */
|
||||
switch (oplinkSettings.MaxRFPower) {
|
||||
case OPLINKSETTINGS_MAXRFPOWER_125:
|
||||
@ -788,10 +824,11 @@ void PIOS_Board_Init(void)
|
||||
|
||||
/* Reinitialize the modem. */
|
||||
PIOS_RFM22B_Reinit(pios_rfm22b_id);
|
||||
} else {
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
OPLinkStatusSet(&oplinkStatus);
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PWM)
|
||||
|
@ -151,14 +151,14 @@ void UAVTalkAddStats(UAVTalkConnection connectionHandle, UAVTalkStats *statsOut)
|
||||
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
|
||||
|
||||
// Copy stats
|
||||
statsOut->txBytes += connection->stats.txBytes;
|
||||
statsOut->rxBytes += connection->stats.rxBytes;
|
||||
statsOut->txBytes += connection->stats.txBytes;
|
||||
statsOut->rxBytes += connection->stats.rxBytes;
|
||||
statsOut->txObjectBytes += connection->stats.txObjectBytes;
|
||||
statsOut->rxObjectBytes += connection->stats.rxObjectBytes;
|
||||
statsOut->txObjects += connection->stats.txObjects;
|
||||
statsOut->rxObjects += connection->stats.rxObjects;
|
||||
statsOut->txErrors += connection->stats.txErrors;
|
||||
statsOut->txErrors += connection->stats.txErrors;
|
||||
statsOut->txObjects += connection->stats.txObjects;
|
||||
statsOut->rxObjects += connection->stats.rxObjects;
|
||||
statsOut->txErrors += connection->stats.txErrors;
|
||||
statsOut->txErrors += connection->stats.txErrors;
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
|
@ -33,7 +33,7 @@
|
||||
|
||||
ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_oplink = new Ui_PipXtremeWidget();
|
||||
m_oplink = new Ui_OPLinkWidget();
|
||||
m_oplink->setupUi(this);
|
||||
|
||||
// Connect to the OPLinkStatus object updates
|
||||
@ -65,14 +65,14 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "VCPPort", m_oplink->VCPPort);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "NumChannels", m_oplink->NumChannels);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MinChannel", m_oplink->MinimumChannel);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxChannel", m_oplink->MaximumChannel);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "ChannelSet", m_oplink->ChannelSet);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "PacketTime", m_oplink->PacketLength);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "CoordID", m_oplink->CoordID);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "Coordinator", m_oplink->Coordinator);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "OneWayLink", m_oplink->OneWayLink);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "OneWay", m_oplink->OneWayLink);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "PPMOnly", m_oplink->PPMOnly);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "PPM", m_oplink->PPM);
|
||||
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "DeviceID", m_oplink->DeviceID);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxGood", m_oplink->Good);
|
||||
@ -100,6 +100,12 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
|
||||
connect(m_oplink->Bind3, SIGNAL(clicked()), this, SLOT(bind3()));
|
||||
connect(m_oplink->Bind4, SIGNAL(clicked()), this, SLOT(bind3()));
|
||||
|
||||
// Connect the selection changed signals.
|
||||
connect(m_oplink->PPMOnly, SIGNAL(toggled(bool)), this, SLOT(ppmOnlyToggled(bool)));
|
||||
connect(m_oplink->ComSpeed, SIGNAL(currentIndexChanged(int)), this, SLOT(comSpeedChanged(int)));
|
||||
|
||||
ppmOnlyToggled(m_oplink->PPMOnly->isChecked());
|
||||
|
||||
// Add scroll bar when necessary
|
||||
QScrollArea *scroll = new QScrollArea;
|
||||
scroll->setWidget(m_oplink->frame_3);
|
||||
@ -226,6 +232,56 @@ void ConfigPipXtremeWidget::updateSettings(UAVObject *object)
|
||||
|
||||
if (!settingsUpdated) {
|
||||
settingsUpdated = true;
|
||||
|
||||
// Enable components based on the board type connected.
|
||||
UAVObjectField *board_type_field = oplinkStatusObj->getField("BoardType");
|
||||
if (board_type_field) {
|
||||
switch (board_type_field->getValue().toInt()) {
|
||||
case 0x09: // Revolution
|
||||
m_oplink->MainPort->setVisible(false);
|
||||
m_oplink->MainPortLabel->setVisible(false);
|
||||
m_oplink->FlexiPort->setVisible(false);
|
||||
m_oplink->FlexiPortLabel->setVisible(false);
|
||||
m_oplink->VCPPort->setVisible(false);
|
||||
m_oplink->VCPPortLabel->setVisible(false);
|
||||
m_oplink->FlexiIOPort->setVisible(false);
|
||||
m_oplink->FlexiIOPortLabel->setVisible(false);
|
||||
m_oplink->Coordinator->setVisible(false);
|
||||
m_oplink->PPM->setVisible(true);
|
||||
break;
|
||||
case 0x03: // OPLinkMini
|
||||
m_oplink->MainPort->setVisible(true);
|
||||
m_oplink->MainPortLabel->setVisible(true);
|
||||
m_oplink->FlexiPort->setVisible(true);
|
||||
m_oplink->FlexiPortLabel->setVisible(true);
|
||||
m_oplink->VCPPort->setVisible(true);
|
||||
m_oplink->VCPPortLabel->setVisible(true);
|
||||
m_oplink->FlexiIOPort->setVisible(false);
|
||||
m_oplink->FlexiIOPortLabel->setVisible(false);
|
||||
m_oplink->Coordinator->setVisible(true);
|
||||
m_oplink->PPM->setVisible(false);
|
||||
break;
|
||||
case 0x0A:
|
||||
m_oplink->MainPort->setVisible(true);
|
||||
m_oplink->MainPortLabel->setVisible(true);
|
||||
m_oplink->FlexiPort->setVisible(true);
|
||||
m_oplink->FlexiPortLabel->setVisible(true);
|
||||
m_oplink->VCPPort->setVisible(true);
|
||||
m_oplink->VCPPortLabel->setVisible(true);
|
||||
m_oplink->FlexiIOPort->setVisible(true);
|
||||
m_oplink->FlexiIOPortLabel->setVisible(true);
|
||||
m_oplink->Coordinator->setVisible(true);
|
||||
m_oplink->PPM->setVisible(false);
|
||||
break;
|
||||
default:
|
||||
// This shouldn't happen.
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
qDebug() << "BoardType not found.";
|
||||
}
|
||||
|
||||
// Enable the push buttons.
|
||||
enableControls(true);
|
||||
}
|
||||
}
|
||||
@ -234,6 +290,8 @@ void ConfigPipXtremeWidget::disconnected()
|
||||
{
|
||||
if (settingsUpdated) {
|
||||
settingsUpdated = false;
|
||||
|
||||
// Enable the push buttons.
|
||||
enableControls(false);
|
||||
}
|
||||
}
|
||||
@ -270,6 +328,36 @@ void ConfigPipXtremeWidget::bind4()
|
||||
SetPairID(m_oplink->PairID1);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::ppmOnlyToggled(bool on)
|
||||
{
|
||||
if (on) {
|
||||
m_oplink->PPM->setEnabled(false);
|
||||
m_oplink->OneWayLink->setEnabled(false);
|
||||
m_oplink->ComSpeed->setEnabled(false);
|
||||
} else {
|
||||
m_oplink->PPM->setEnabled(true);
|
||||
m_oplink->OneWayLink->setEnabled(true);
|
||||
m_oplink->ComSpeed->setEnabled(true);
|
||||
// Change the comspeed from 4800 of PPM only is turned off.
|
||||
if (m_oplink->ComSpeed->currentIndex() == OPLinkSettings::COMSPEED_4800) {
|
||||
m_oplink->ComSpeed->setCurrentIndex(OPLinkSettings::COMSPEED_9600);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::comSpeedChanged(int index)
|
||||
{
|
||||
qDebug() << "comSpeedChanged: " << index;
|
||||
switch (index) {
|
||||
case OPLinkSettings::COMSPEED_4800:
|
||||
m_oplink->PPMOnly->setChecked(true);
|
||||
break;
|
||||
default:
|
||||
m_oplink->PPMOnly->setChecked(false);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@}
|
||||
@}
|
||||
|
@ -44,7 +44,7 @@ public slots:
|
||||
void updateSettings(UAVObject *object1);
|
||||
|
||||
private:
|
||||
Ui_PipXtremeWidget *m_oplink;
|
||||
Ui_OPLinkWidget *m_oplink;
|
||||
|
||||
// The OPLink status UAVObject
|
||||
UAVDataObject *oplinkStatusObj;
|
||||
@ -63,6 +63,8 @@ private slots:
|
||||
void bind2();
|
||||
void bind3();
|
||||
void bind4();
|
||||
void ppmOnlyToggled(bool toggled);
|
||||
void comSpeedChanged(int index);
|
||||
};
|
||||
|
||||
#endif // CONFIGTXPIDWIDGET_H
|
||||
|
@ -65,9 +65,6 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
addUAVObjectToWidgetRelation("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
|
||||
|
||||
addUAVObjectToWidgetRelation("HwSettings", "RadioPort", m_ui->cbModem);
|
||||
addUAVObjectToWidgetRelation("HwSettings", "TelemetrySpeed", m_ui->cbRadioSpeed);
|
||||
|
||||
connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
setupCustomCombos();
|
||||
@ -94,7 +91,6 @@ void ConfigRevoHWWidget::setupCustomCombos()
|
||||
|
||||
connect(m_ui->cbFlexi, SIGNAL(currentIndexChanged(int)), this, SLOT(flexiPortChanged(int)));
|
||||
connect(m_ui->cbMain, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged(int)));
|
||||
connect(m_ui->cbModem, SIGNAL(currentIndexChanged(int)), this, SLOT(modemPortChanged(int)));
|
||||
}
|
||||
|
||||
void ConfigRevoHWWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
@ -105,7 +101,6 @@ void ConfigRevoHWWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
usbVCPPortChanged(0);
|
||||
mainPortChanged(0);
|
||||
flexiPortChanged(0);
|
||||
modemPortChanged(0);
|
||||
m_refreshing = false;
|
||||
}
|
||||
|
||||
@ -202,9 +197,6 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
|
||||
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_TELEMETRY) {
|
||||
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
|
||||
}
|
||||
if (m_ui->cbModem->currentIndex() == HwSettings::RADIOPORT_TELEMETRY) {
|
||||
m_ui->cbModem->setCurrentIndex(HwSettings::RADIOPORT_DISABLED);
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_FLEXIPORT_GPS:
|
||||
m_ui->cbFlexiGPSSpeed->setVisible(true);
|
||||
@ -248,9 +240,6 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
|
||||
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
|
||||
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
if (m_ui->cbModem->currentIndex() == HwSettings::RADIOPORT_TELEMETRY) {
|
||||
m_ui->cbModem->setCurrentIndex(HwSettings::RADIOPORT_DISABLED);
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_MAINPORT_GPS:
|
||||
m_ui->cbMainGPSSpeed->setVisible(true);
|
||||
@ -279,26 +268,6 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigRevoHWWidget::modemPortChanged(int index)
|
||||
{
|
||||
Q_UNUSED(index);
|
||||
|
||||
if (m_ui->cbModem->currentIndex() == HwSettings::RADIOPORT_TELEMETRY) {
|
||||
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_TELEMETRY) {
|
||||
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
|
||||
}
|
||||
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
|
||||
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
m_ui->cbRadioSpeed->setVisible(true);
|
||||
if (!m_refreshing) {
|
||||
QMessageBox::warning(this, tr("Warning"), tr("Activating the Radio requires an antenna be attached or modem damage will occur."));
|
||||
}
|
||||
} else {
|
||||
m_ui->cbRadioSpeed->setVisible(false);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigRevoHWWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl("http://wiki.openpilot.org/x/GgDBAQ", QUrl::StrictMode));
|
||||
|
@ -57,7 +57,6 @@ private slots:
|
||||
void usbHIDPortChanged(int index);
|
||||
void flexiPortChanged(int index);
|
||||
void mainPortChanged(int index);
|
||||
void modemPortChanged(int index);
|
||||
void openHelp();
|
||||
};
|
||||
|
||||
|
@ -123,33 +123,16 @@
|
||||
</property>
|
||||
<item row="2" column="2">
|
||||
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
|
||||
<item row="16" column="4">
|
||||
<spacer name="horizontalSpacer_8">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>120</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<widget class="QComboBox" name="cbUSBVCPSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="12" column="3">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="text">
|
||||
<string>Main Port</string>
|
||||
<string>USB HID Function</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
@ -172,8 +155,28 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="12" column="5">
|
||||
<spacer name="horizontalSpacer_6">
|
||||
<item row="15" column="1">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiTelemSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiGPSSpeed"/>
|
||||
</item>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="16" column="1">
|
||||
<spacer name="horizontalSpacer_7">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
@ -188,21 +191,8 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="6" column="5">
|
||||
<widget class="QComboBox" name="cbSonar">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="lblUSBVCPSpeed">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<item row="14" column="3">
|
||||
<widget class="QLabel" name="lblMainSpeed">
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
@ -242,9 +232,116 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="13" column="1">
|
||||
<widget class="QComboBox" name="cbFlexi"/>
|
||||
</item>
|
||||
<item row="16" column="4">
|
||||
<spacer name="horizontalSpacer_8">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="12" column="1">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>Flexi Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="5">
|
||||
<widget class="QComboBox" name="cbSonar">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="13" column="3">
|
||||
<widget class="QComboBox" name="cbMain"/>
|
||||
</item>
|
||||
<item row="10" column="5">
|
||||
<spacer name="verticalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="12" column="3">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="text">
|
||||
<string>Main Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<widget class="QComboBox" name="cbUSBVCPSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="12" column="5">
|
||||
<spacer name="horizontalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>120</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="8" column="0">
|
||||
<widget class="QComboBox" name="cbUSBVCPFunction"/>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QComboBox" name="cbUSBHIDFunction"/>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="lblUSBVCPSpeed">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="5">
|
||||
<widget class="QLabel" name="label_9">
|
||||
<property name="sizePolicy">
|
||||
@ -261,194 +358,6 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<spacer name="verticalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>120</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="13" column="3">
|
||||
<widget class="QComboBox" name="cbMain"/>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="label_8">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>USB VCP Function</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="14" column="3">
|
||||
<widget class="QLabel" name="lblMainSpeed">
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="15" column="1">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiTelemSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiGPSSpeed"/>
|
||||
</item>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="12" column="0">
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>120</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="12" column="1">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>Flexi Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QComboBox" name="cbRcvr"/>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>USB HID Function</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QComboBox" name="cbUSBHIDFunction"/>
|
||||
</item>
|
||||
<item row="15" column="3">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_6">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainTelemSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainGPSSpeed"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="13" column="1">
|
||||
<widget class="QComboBox" name="cbFlexi"/>
|
||||
</item>
|
||||
<item row="12" column="2">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Radio</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="13" column="2">
|
||||
<widget class="QComboBox" name="cbModem"/>
|
||||
</item>
|
||||
<item row="14" column="2">
|
||||
<widget class="QLabel" name="lblRadioSpeed">
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="15" column="2">
|
||||
<widget class="QComboBox" name="cbRadioSpeed"/>
|
||||
</item>
|
||||
<item row="14" column="1">
|
||||
<widget class="QLabel" name="lblFlexiSpeed">
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="16" column="1">
|
||||
<spacer name="horizontalSpacer_7">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>120</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_7">
|
||||
<property name="sizePolicy">
|
||||
@ -481,6 +390,87 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="12" column="0">
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>120</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="label_8">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>USB VCP Function</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<spacer name="verticalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>120</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="14" column="1">
|
||||
<widget class="QLabel" name="lblFlexiSpeed">
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="15" column="3">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_6">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainTelemSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainGPSSpeed"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QComboBox" name="cbRcvr"/>
|
||||
</item>
|
||||
<item row="16" column="3">
|
||||
<spacer name="horizontalSpacer_9">
|
||||
<property name="orientation">
|
||||
@ -545,22 +535,6 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="10" column="5">
|
||||
<spacer name="verticalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="11" column="5">
|
||||
<spacer name="verticalSpacer_9">
|
||||
<property name="orientation">
|
||||
@ -584,7 +558,7 @@
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>120</width>
|
||||
<width>80</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
|
@ -1,7 +1,7 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>PipXtremeWidget</class>
|
||||
<widget class="QWidget" name="PipXtremeWidget">
|
||||
<class>OPLinkWidget</class>
|
||||
<widget class="QWidget" name="OPLinkWidget">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
@ -1259,246 +1259,6 @@
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Configuration</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="4" column="2">
|
||||
<widget class="QLabel" name="MaximumChannelLabel">
|
||||
<property name="text">
|
||||
<string>Max Chan</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="2">
|
||||
<widget class="QLabel" name="PacketLengthLabel">
|
||||
<property name="text">
|
||||
<string>Packet Length</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QLabel" name="NumChannelsLabel">
|
||||
<property name="text">
|
||||
<string>Num Chan</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="MainPortLabel">
|
||||
<property name="text">
|
||||
<string>Main Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<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="2" column="3">
|
||||
<widget class="QSpinBox" name="NumChannels">
|
||||
<property name="maximum">
|
||||
<number>250</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="FlexiPortLabel">
|
||||
<property name="text">
|
||||
<string>Flexi Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QComboBox" name="ComSpeed"/>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="VCPPortLabel">
|
||||
<property name="text">
|
||||
<string>VCP Port</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="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="5" column="0">
|
||||
<widget class="QLabel" name="ComSpeedLabel">
|
||||
<property name="text">
|
||||
<string>Com Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QLabel" name="MinimumChannelLabel">
|
||||
<property name="text">
|
||||
<string>Min Chan</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QSpinBox" name="MinimumChannel">
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="2">
|
||||
<widget class="QLabel" name="ChannelSetLabel">
|
||||
<property name="text">
|
||||
<string>Channel Set</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="3">
|
||||
<widget class="QSpinBox" name="ChannelSet">
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<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="4" column="3">
|
||||
<widget class="QSpinBox" name="MaximumChannel">
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="MaxRFTxPowerLabel">
|
||||
<property name="text">
|
||||
<string>Max Power</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<widget class="QComboBox" name="MaxRFTxPower">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the maximum TX output power the modem will use (mW)</string>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="modelColumn">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="3">
|
||||
<widget class="QSpinBox" name="PacketLength">
|
||||
<property name="toolTip">
|
||||
<string extracomment="The packet length in ms / packet"/>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>15</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="0">
|
||||
<widget class="QCheckBox" name="Coordinator">
|
||||
<property name="text">
|
||||
<string>Coordinator</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="2">
|
||||
<widget class="QCheckBox" name="OneWayLink">
|
||||
<property name="text">
|
||||
<string>One-Way Link</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QGroupBox" name="groupBox_2">
|
||||
<property name="font">
|
||||
@ -1715,12 +1475,236 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<widget class="QCheckBox" name="Coordinator">
|
||||
<property name="text">
|
||||
<string>Coordinator</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Configuration</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="4" column="3">
|
||||
<widget class="QComboBox" name="ComSpeed"/>
|
||||
</item>
|
||||
<item row="4" column="2">
|
||||
<widget class="QLabel" name="ComSpeedLabel">
|
||||
<property name="text">
|
||||
<string>Com Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="2">
|
||||
<widget class="QLabel" name="VCPPortLabel">
|
||||
<property name="text">
|
||||
<string>VCP Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="3">
|
||||
<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="6" column="2">
|
||||
<widget class="QLabel" name="MainPortLabel">
|
||||
<property name="text">
|
||||
<string>Main Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<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="3">
|
||||
<widget class="QComboBox" name="MaxRFTxPower">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the maximum TX output power the modem will use (mW)</string>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="modelColumn">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="MaxRFTxPowerLabel">
|
||||
<property name="text">
|
||||
<string>Max Power</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="3">
|
||||
<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="10" column="2">
|
||||
<widget class="QLabel" name="FlexiIOPortLabel">
|
||||
<property name="text">
|
||||
<string>FlexiIO Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="3">
|
||||
<widget class="QComboBox" name="FlexiIOPort"/>
|
||||
</item>
|
||||
<item row="7" column="2">
|
||||
<widget class="QLabel" name="FlexiPortLabel">
|
||||
<property name="text">
|
||||
<string>Flexi Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QCheckBox" name="OneWayLink">
|
||||
<property name="text">
|
||||
<string>One-Way Link</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QCheckBox" name="PPMOnly">
|
||||
<property name="text">
|
||||
<string>PPM Only</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="MaximumChannelLabel">
|
||||
<property name="text">
|
||||
<string>Max Chan</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QSpinBox" name="MaximumChannel">
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="MinimumChannelLabel">
|
||||
<property name="text">
|
||||
<string>Min Chan</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<widget class="QSpinBox" name="MinimumChannel">
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="ChannelSetLabel">
|
||||
<property name="text">
|
||||
<string>Channel Set</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="1">
|
||||
<widget class="QSpinBox" name="ChannelSet">
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<widget class="QCheckBox" name="PPM">
|
||||
<property name="text">
|
||||
<string>PPM</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
|
@ -16,8 +16,6 @@
|
||||
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM2,DSMX (10bit),DSMX (11bit),DebugConsole,ComBridge,OsdHk" defaultvalue="Telemetry"/>
|
||||
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM2,DSMX (10bit),DSMX (11bit),DebugConsole,ComBridge,OsdHk" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="RadioPort" units="function" type="enum" elements="1" options="Disabled,Telemetry" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="GPSSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="ComUsbBridgeSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
|
@ -2,18 +2,18 @@
|
||||
<object name="OPLinkSettings" singleinstance="true" settings="true">
|
||||
<description>OPLink configurations options.</description>
|
||||
<field name="Coordinator" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="OneWayLink" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="OneWay" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="PPM" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="PPMOnly" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="CoordID" units="hex" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="MainPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM" defaultvalue="Telemetry"/>
|
||||
<field name="FlexiPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM" defaultvalue="Disabled"/>
|
||||
<field name="VCPPort" units="" type="enum" elements="1" options="Disabled,Serial" defaultvalue="Disabled"/>
|
||||
<field name="ComSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="38400"/>
|
||||
<field name="MaxRFPower" units="mW" type="enum" elements="1" options="1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="1.25"/>
|
||||
<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="MinChannel" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="MaxChannel" units="" type="uint8" elements="1" defaultvalue="250"/>
|
||||
<field name="NumChannels" units="" type="uint8" elements="1" defaultvalue="10"/>
|
||||
<field name="ChannelSet" units="" type="uint8" elements="1" defaultvalue="39"/>
|
||||
<field name="PacketTime" units="ms" type="uint8" elements="1" defaultvalue="15"/>
|
||||
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -24,7 +24,7 @@
|
||||
<field name="RXRate" units="Bps" type="uint16" elements="1" defaultvalue="0"/>
|
||||
<field name="TXSeq" units="" type="uint16" elements="1" defaultvalue="0"/>
|
||||
<field name="RXSeq" units="" type="uint16" elements="1" defaultvalue="0"/>
|
||||
<field name="LinkState" units="function" type="enum" elements="1" options="Disconnected,Connecting,Connected" defaultvalue="Disconnected"/>
|
||||
<field name="LinkState" units="function" type="enum" elements="1" options="Disabled,Enabled,Disconnected,Connecting,Connected" defaultvalue="Disabled"/>
|
||||
<field name="PairIDs" units="hex" type="uint32" elements="4" defaultvalue="0"/>
|
||||
<field name="PairSignalStrengths" units="dBm" type="int8" elements="4" defaultvalue="-127"/>
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user