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

Merge remote-tracking branch 'remotes/origin/next' into sambas/diffnext

Conflicts:
	.gitignore
This commit is contained in:
sambas 2013-04-14 10:13:51 +03:00
commit 6989468d17
39 changed files with 3162 additions and 2057 deletions

10
.gitignore vendored
View File

@ -50,6 +50,16 @@ openpilotgcs-build-desktop
# Ignore build output from Eclipse android builds # Ignore build output from Eclipse android builds
/androidgcs/bin/ /androidgcs/bin/
/androidgcs/gen/ /androidgcs/gen/
# Ignore Eclipse Projects and Metadata
/.cproject /.cproject
/.project /.project
/.metadata /.metadata
# Ignore Eclipse temp folder, git plugin based?
RemoteSystemsTempFiles
# Ignore patch-related files
*.rej
*.orig
*.diff~

2
.gitmodules vendored
View File

@ -1,3 +1,3 @@
[submodule "overo"] [submodule "overo"]
path = overo path = overo
url = git@github.com:peabody124/op_overo.git url = gitolite@git.openpilot.org:op_overo.git

View File

@ -1,7 +1,7 @@
Here is a list of some known unresolved issues. If an issue has JIRA ID [OP-XXX], you may track it using the Here is a list of some known unresolved issues. If an issue has JIRA ID [OP-XXX], you may track it using the
following URL: http://bugs.openpilot.org/browse/OP-XXX following URL: http://bugs.openpilot.org/browse/OP-XXX
+ Missing Translations, use English. + Only French translation is updated, use English for other locales or help with translations.
+ Radio Wizard confused by a reversed throttle, fix it on your transmitter before starting wizard. + Radio Wizard confused by a reversed throttle, fix it on your transmitter before starting wizard.
+ Radio Wizard Throttle display does not show full range properly. + Radio Wizard Throttle display does not show full range properly.
+ [Windows 8] USB Driver is broken. + [Windows 8] USB Driver is broken.
@ -17,6 +17,4 @@ following URL: http://bugs.openpilot.org/browse/OP-XXX
+ [OP-725] GCS camera stab config error message disappears too fast (but config error is cleared as it should) + [OP-725] GCS camera stab config error message disappears too fast (but config error is cleared as it should)
+ [OP-767] GCS does not send AttitudeActual packets over serial port when GPS is connected and system is armed + [OP-767] GCS does not send AttitudeActual packets over serial port when GPS is connected and system is armed
+ [OP-768] GCS does not show UAV position on the map (master or next CC branches, but works in Revo branches) + [OP-768] GCS does not show UAV position on the map (master or next CC branches, but works in Revo branches)
+ [OP-682] GCS crashes on firmware page. Noted on Windows and OSX platforms, difficult to reproduce.
Workaround: use Vehicle setup wizard to update the firmware.
+ [OP-769] Can't enter "12,45" on German system. Workaround: change GCS language (in fact, locale) to German. + [OP-769] Can't enter "12,45" on German system. Workaround: change GCS language (in fact, locale) to German.

View File

@ -70,7 +70,7 @@ SANITIZE_GCC_VARS += CFLAGS CPATH C_INCLUDE_PATH CPLUS_INCLUDE_PATH OBJC_INCLUDE
$(foreach var, $(SANITIZE_GCC_VARS), $(eval $(call SANITIZE_VAR,$(var),disallowed))) $(foreach var, $(SANITIZE_GCC_VARS), $(eval $(call SANITIZE_VAR,$(var),disallowed)))
# These specific variables used to be valid but now they make no sense # These specific variables used to be valid but now they make no sense
SANITIZE_DEPRECATED_VARS := USE_BOOTLOADER SANITIZE_DEPRECATED_VARS := USE_BOOTLOADER CLEAN_BUILD
$(foreach var, $(SANITIZE_DEPRECATED_VARS), $(eval $(call SANITIZE_VAR,$(var),deprecated))) $(foreach var, $(SANITIZE_DEPRECATED_VARS), $(eval $(call SANITIZE_VAR,$(var),deprecated)))
# Make sure this isn't being run as root (no whoami on Windows, but that is ok here) # Make sure this isn't being run as root (no whoami on Windows, but that is ok here)
@ -755,9 +755,9 @@ $(OPFW_RESOURCE): $(FW_TARGETS)
$(V1) $(MKDIR) -p $(dir $@) $(V1) $(MKDIR) -p $(dir $@)
$(V1) $(ECHO) $(QUOTE)$(OPFW_CONTENTS)$(QUOTE) > $@ $(V1) $(ECHO) $(QUOTE)$(OPFW_CONTENTS)$(QUOTE) > $@
# If opfw_resource or all are requested, GCS should depend on the resource # If opfw_resource or all firmware are requested, GCS should depend on the resource
ifneq ($(strip $(filter opfw_resource all,$(MAKECMDGOALS))),) ifneq ($(strip $(filter opfw_resource all all_fw all_flight,$(MAKECMDGOALS))),)
$(eval openpilotgcs: | opfw_resource) $(eval openpilotgcs: $(OPFW_RESOURCE))
endif endif
# Packaging targets: package, clean_package # Packaging targets: package, clean_package
@ -780,7 +780,7 @@ ifneq ($(strip $(filter package clean_package,$(MAKECMDGOALS))),)
# Packaged GCS should depend on opfw_resource # Packaged GCS should depend on opfw_resource
ifneq ($(strip $(filter package clean_package,$(MAKECMDGOALS))),) ifneq ($(strip $(filter package clean_package,$(MAKECMDGOALS))),)
$(eval openpilotgcs: | opfw_resource) $(eval openpilotgcs: $(OPFW_RESOURCE))
endif endif
# Clean the build directory if clean_package is requested # Clean the build directory if clean_package is requested

View File

@ -42,22 +42,21 @@
// Public types // Public types
typedef enum { typedef enum {
PACKET_TYPE_NONE = 0, PACKET_TYPE_NONE = 0,
PACKET_TYPE_STATUS, // broadcasts status of this modem PACKET_TYPE_STATUS, // broadcasts status of this modem
PACKET_TYPE_CON_REQUEST, // request a connection to another modem PACKET_TYPE_CON_REQUEST, // request a connection to another modem
PACKET_TYPE_DATA, // data packet (packet contains user data) PACKET_TYPE_DATA, // data packet (packet contains user data)
PACKET_TYPE_DUPLICATE_DATA, // a duplicate data packet PACKET_TYPE_DUPLICATE_DATA, // a duplicate data packet
PACKET_TYPE_PPM, // PPM relay values PACKET_TYPE_PPM, // PPM relay values
PACKET_TYPE_ACK, // Acknowlege the receipt of a packet PACKET_TYPE_ACK, // Acknowlege the receipt of a packet
PACKET_TYPE_ACK_RTS, // Acknowlege the receipt of a packet and indicate that the receiving side has data to send (ready to send) PACKET_TYPE_ACK_RTS, // Acknowlege the receipt of a packet and indicate that the receiving side has data to send (ready to send)
PACKET_TYPE_NACK, // Acknowlege the receipt of an uncorrectable packet PACKET_TYPE_NACK, // Acknowlege the receipt of an uncorrectable packet
} PHPacketType; } PHPacketType;
typedef struct { typedef struct {
uint32_t destination_id; uint32_t destination_id;
uint32_t source_id; uint16_t seq_num;
uint8_t type; uint8_t type;
uint8_t data_size; uint8_t data_size;
uint16_t seq_num;
} PHPacketHeader; } PHPacketHeader;
#define PH_MAX_DATA (PIOS_PH_MAX_PACKET - sizeof(PHPacketHeader) - RS_ECC_NPARITY) #define PH_MAX_DATA (PIOS_PH_MAX_PACKET - sizeof(PHPacketHeader) - RS_ECC_NPARITY)
@ -70,6 +69,7 @@ typedef struct {
#define PH_ACK_NACK_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) #define PH_ACK_NACK_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data))
typedef struct { typedef struct {
PHPacketHeader header; PHPacketHeader header;
portTickType packet_recv_time;
uint8_t ecc[RS_ECC_NPARITY]; uint8_t ecc[RS_ECC_NPARITY];
} PHAckNackPacket, *PHAckNackPacketHandle; } PHAckNackPacket, *PHAckNackPacketHandle;
@ -83,6 +83,7 @@ typedef struct {
#define PH_STATUS_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) #define PH_STATUS_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data))
typedef struct { typedef struct {
PHPacketHeader header; PHPacketHeader header;
uint32_t source_id;
uint8_t link_quality; uint8_t link_quality;
int8_t received_rssi; int8_t received_rssi;
uint8_t ecc[RS_ECC_NPARITY]; uint8_t ecc[RS_ECC_NPARITY];
@ -91,12 +92,13 @@ typedef struct {
#define PH_CONNECTION_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) #define PH_CONNECTION_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data))
typedef struct { typedef struct {
PHPacketHeader header; PHPacketHeader header;
uint8_t datarate; uint32_t source_id;
uint32_t frequency_hz;
uint32_t min_frequency; uint32_t min_frequency;
uint32_t max_frequency; uint32_t max_frequency;
uint8_t max_tx_power; uint32_t channel_spacing;
OPLinkSettingsOutputConnectionOptions port; OPLinkSettingsMainPortOptions main_port;
OPLinkSettingsFlexiPortOptions flexi_port;
OPLinkSettingsVCPPortOptions vcp_port;
OPLinkSettingsComSpeedOptions com_speed; OPLinkSettingsComSpeedOptions com_speed;
uint8_t ecc[RS_ECC_NPARITY]; uint8_t ecc[RS_ECC_NPARITY];
} PHConnectionPacket, *PHConnectionPacketHandle; } PHConnectionPacket, *PHConnectionPacketHandle;

View File

@ -705,11 +705,8 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon
static void updatePathDesired(ManualControlCommandData * cmd, bool changed,bool home) static void updatePathDesired(ManualControlCommandData * cmd, bool changed,bool home)
{ {
static portTickType lastSysTime; static portTickType lastSysTime;
portTickType thisSysTime; portTickType thisSysTime = xTaskGetTickCount();
float dT; /* float dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f; */
thisSysTime = xTaskGetTickCount();
dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f;
lastSysTime = thisSysTime; lastSysTime = thisSysTime;
if (home && changed) { if (home && changed) {
@ -746,16 +743,15 @@ static void updatePathDesired(ManualControlCommandData * cmd, bool changed,bool
pathDesired.EndingVelocity=0; pathDesired.EndingVelocity=0;
pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT; pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT;
PathDesiredSet(&pathDesired); PathDesiredSet(&pathDesired);
/* Disable this section, until such time as proper discussion can be had about how to implement it for all types of crafts.
} else { } else {
/*Disable this section, until such time as proper discussion can be had about how to implement it for all types of crafts.
PathDesiredData pathDesired; PathDesiredData pathDesired;
PathDesiredGet(&pathDesired); PathDesiredGet(&pathDesired);
pathDesired.End[PATHDESIRED_END_NORTH] += dT * -cmd->Pitch; pathDesired.End[PATHDESIRED_END_NORTH] += dT * -cmd->Pitch;
pathDesired.End[PATHDESIRED_END_EAST] += dT * cmd->Roll; pathDesired.End[PATHDESIRED_END_EAST] += dT * cmd->Roll;
pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT; pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT;
PathDesiredSet(&pathDesired); PathDesiredSet(&pathDesired);
*/ */
} }
} }

View File

@ -47,7 +47,6 @@
// Private constants // Private constants
#define SYSTEM_UPDATE_PERIOD_MS 1000 #define SYSTEM_UPDATE_PERIOD_MS 1000
#define LED_BLINK_RATE_HZ 5
#if defined(PIOS_SYSTEM_STACK_SIZE) #if defined(PIOS_SYSTEM_STACK_SIZE)
#define STACK_SIZE_BYTES PIOS_SYSTEM_STACK_SIZE #define STACK_SIZE_BYTES PIOS_SYSTEM_STACK_SIZE
@ -155,9 +154,7 @@ static void systemTask(void *parameters)
// Update the PipXstatus UAVO // Update the PipXstatus UAVO
OPLinkStatusData oplinkStatus; OPLinkStatusData oplinkStatus;
uint32_t pairID;
OPLinkStatusGet(&oplinkStatus); OPLinkStatusGet(&oplinkStatus);
OPLinkSettingsPairIDGet(&pairID);
// Get the other device stats. // Get the other device stats.
PIOS_RFM2B_GetPairStats(pios_rfm22b_id, oplinkStatus.PairIDs, oplinkStatus.PairSignalStrengths, OPLINKSTATUS_PAIRIDS_NUMELEM); PIOS_RFM2B_GetPairStats(pios_rfm22b_id, oplinkStatus.PairIDs, oplinkStatus.PairSignalStrengths, OPLINKSTATUS_PAIRIDS_NUMELEM);
@ -167,6 +164,7 @@ static void systemTask(void *parameters)
PIOS_RFM22B_GetStats(pios_rfm22b_id, &radio_stats); PIOS_RFM22B_GetStats(pios_rfm22b_id, &radio_stats);
// Update the status // Update the status
oplinkStatus.HeapRemaining = xPortGetFreeHeapSize();
oplinkStatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); oplinkStatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id);
oplinkStatus.RxGood = radio_stats.rx_good; oplinkStatus.RxGood = radio_stats.rx_good;
oplinkStatus.RxCorrected = radio_stats.rx_corrected; oplinkStatus.RxCorrected = radio_stats.rx_corrected;
@ -179,7 +177,6 @@ static void systemTask(void *parameters)
oplinkStatus.Resets = radio_stats.resets; oplinkStatus.Resets = radio_stats.resets;
oplinkStatus.Timeouts = radio_stats.timeouts; oplinkStatus.Timeouts = radio_stats.timeouts;
oplinkStatus.RSSI = radio_stats.rssi; oplinkStatus.RSSI = radio_stats.rssi;
oplinkStatus.AFCCorrection = radio_stats.afc_correction;
oplinkStatus.LinkQuality = radio_stats.link_quality; oplinkStatus.LinkQuality = radio_stats.link_quality;
if (first_time) if (first_time)
first_time = false; first_time = false;

View File

@ -46,6 +46,12 @@
#include <stdbool.h> #include <stdbool.h>
// External functions
void PIOS_InitUartMainPort();
void PIOS_InitUartFlexiPort();
void PIOS_InitPPMMainPort(bool input);
void PIOS_InitPPMFlexiPort(bool input);
// **************** // ****************
// Private constants // Private constants
@ -82,6 +88,12 @@ typedef struct {
uint32_t UAVTalkErrors; uint32_t UAVTalkErrors;
uint32_t droppedPackets; uint32_t droppedPackets;
// Should we parse UAVTalk?
bool parseUAVTalk;
// The current configured uart speed
OPLinkSettingsComSpeedOptions comSpeed;
} RadioComBridgeData; } RadioComBridgeData;
// **************** // ****************
@ -94,7 +106,9 @@ static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length);
static int32_t RadioSendHandler(uint8_t *buf, int32_t length); static int32_t RadioSendHandler(uint8_t *buf, int32_t length);
static void ProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte); static void ProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte);
static void queueEvent(xQueueHandle queue, void *obj, uint16_t instId, UAVObjEventType type); static void queueEvent(xQueueHandle queue, void *obj, uint16_t instId, UAVObjEventType type);
static void configureComCallback(OPLinkSettingsOutputConnectionOptions com_port, OPLinkSettingsComSpeedOptions com_speed); static void configureComCallback(OPLinkSettingsRemoteMainPortOptions main_port, OPLinkSettingsRemoteFlexiPortOptions flexi_port,
OPLinkSettingsRemoteVCPPortOptions vcp_port, OPLinkSettingsComSpeedOptions com_speed,
uint32_t min_frequency, uint32_t max_frequency, uint32_t channel_spacing);
static void updateSettings(); static void updateSettings();
// **************** // ****************
@ -109,30 +123,77 @@ static RadioComBridgeData *data;
*/ */
static int32_t RadioComBridgeStart(void) static int32_t RadioComBridgeStart(void)
{ {
if(data) { if(data) {
// Configure the com port configuration callback // Configure the com port configuration callback
PIOS_RFM22B_SetComConfigCallback(pios_rfm22b_id, &configureComCallback); PIOS_RFM22B_SetComConfigCallback(pios_rfm22b_id, &configureComCallback);
// Set the baudrates, etc. // Get the settings.
updateSettings(); OPLinkSettingsData oplinkSettings;
OPLinkSettingsGet(&oplinkSettings);
// Start the primary tasks for receiving/sending UAVTalk packets from the GCS. // Set the baudrates, etc.
xTaskCreate(telemetryTxTask, (signed char *)"telemTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryTxTaskHandle)); bool is_coordinator = PIOS_RFM22B_IsCoordinator(pios_rfm22b_id);
xTaskCreate(radioRxTask, (signed char *)"radioRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioRxTaskHandle)); if (is_coordinator) {
xTaskCreate(radioTxTask, (signed char *)"radioTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioTxTaskHandle));
// Register the watchdog timers. // Set the maximum radio RF power.
switch (oplinkSettings.MaxRFPower)
{
case OPLINKSETTINGS_MAXRFPOWER_125:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0);
break;
case OPLINKSETTINGS_MAXRFPOWER_16:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1);
break;
case OPLINKSETTINGS_MAXRFPOWER_316:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2);
break;
case OPLINKSETTINGS_MAXRFPOWER_63:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3);
break;
case OPLINKSETTINGS_MAXRFPOWER_126:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4);
break;
case OPLINKSETTINGS_MAXRFPOWER_25:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5);
break;
case OPLINKSETTINGS_MAXRFPOWER_50:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6);
break;
case OPLINKSETTINGS_MAXRFPOWER_100:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7);
break;
default:
// do nothing
break;
}
// Set the frequency range.
PIOS_RFM22B_SetFrequencyRange(pios_rfm22b_id, oplinkSettings.MinFrequency, oplinkSettings.MaxFrequency, oplinkSettings.ChannelSpacing);
// Reinitilize the modem.
PIOS_RFM22B_Reinit(pios_rfm22b_id);
}
// Set the initial frequency.
PIOS_RFM22B_SetInitialFrequency(pios_rfm22b_id, oplinkSettings.InitFrequency);
// Start the primary tasks for receiving/sending UAVTalk packets from the GCS.
xTaskCreate(telemetryTxTask, (signed char *)"telemTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryTxTaskHandle));
xTaskCreate(radioRxTask, (signed char *)"radioRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioRxTaskHandle));
xTaskCreate(radioTxTask, (signed char *)"radioTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioTxTaskHandle));
// Register the watchdog timers.
#ifdef PIOS_INCLUDE_WDG #ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_TELEMETRY); PIOS_WDG_RegisterFlag(PIOS_WDG_TELEMETRY);
PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORX); PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORX);
PIOS_WDG_RegisterFlag(PIOS_WDG_RADIOTX); PIOS_WDG_RegisterFlag(PIOS_WDG_RADIOTX);
#endif #endif
return 0; return 0;
} }
return -1; return -1;
} }
/** /**
@ -149,7 +210,6 @@ static int32_t RadioComBridgeInitialize(void)
return -1; return -1;
// Initialize the UAVObjects that we use // Initialize the UAVObjects that we use
GCSReceiverInitialize();
OPLinkStatusInitialize(); OPLinkStatusInitialize();
ObjectPersistenceInitialize(); ObjectPersistenceInitialize();
@ -163,11 +223,17 @@ static int32_t RadioComBridgeInitialize(void)
// Configure our UAVObjects for updates. // Configure our UAVObjects for updates.
UAVObjConnectQueue(UAVObjGetByID(OPLINKSTATUS_OBJID), data->uavtalkEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ); UAVObjConnectQueue(UAVObjGetByID(OPLINKSTATUS_OBJID), data->uavtalkEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
UAVObjConnectQueue(UAVObjGetByID(OBJECTPERSISTENCE_OBJID), data->uavtalkEventQueue, EV_UPDATED | EV_UPDATED_MANUAL); UAVObjConnectQueue(UAVObjGetByID(OBJECTPERSISTENCE_OBJID), data->uavtalkEventQueue, EV_UPDATED | EV_UPDATED_MANUAL);
#if defined(PIOS_INCLUDE_RFM22B_GCSRECEIVER)
UAVObjConnectQueue(UAVObjGetByID(GCSRECEIVER_OBJID), data->uavtalkEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
#endif
// Initialize the statistics. // Initialize the statistics.
data->comTxErrors = 0; data->comTxErrors = 0;
data->comTxRetries = 0; data->comTxRetries = 0;
data->UAVTalkErrors = 0; data->UAVTalkErrors = 0;
data->parseUAVTalk = false;
data->comSpeed = OPLINKSETTINGS_COMSPEED_9600;
PIOS_COM_RADIO = PIOS_COM_RFM22B;
return 0; return 0;
} }
@ -235,7 +301,7 @@ static void radioRxTask(void *parameters)
// Task loop // Task loop
while (1) { while (1) {
#ifdef PIOS_INCLUDE_WDG #ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORX); PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORX);
#endif #endif
uint8_t serial_data[1]; uint8_t serial_data[1];
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, serial_data, sizeof(serial_data), MAX_PORT_DELAY); uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, serial_data, sizeof(serial_data), MAX_PORT_DELAY);
@ -259,17 +325,18 @@ static void radioTxTask(void *parameters)
#endif #endif
#if defined(PIOS_INCLUDE_USB) #if defined(PIOS_INCLUDE_USB)
// Determine output port (USB takes priority over telemetry port) // Determine output port (USB takes priority over telemetry port)
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB) if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB_HID)
inputPort = PIOS_COM_TELEM_USB; inputPort = PIOS_COM_TELEM_USB_HID;
#endif /* PIOS_INCLUDE_USB */ #endif /* PIOS_INCLUDE_USB */
if(inputPort) if(inputPort) {
{
uint8_t serial_data[1]; uint8_t serial_data[1];
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(inputPort, serial_data, sizeof(serial_data), MAX_PORT_DELAY); uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(inputPort, serial_data, sizeof(serial_data), MAX_PORT_DELAY);
if (bytes_to_process > 0) if (bytes_to_process > 0) {
for (uint8_t i = 0; i < bytes_to_process; i++) for (uint8_t i = 0; i < bytes_to_process; i++)
ProcessInputStream(data->inUAVTalkCon, serial_data[i]); ProcessInputStream(data->inUAVTalkCon, serial_data[i]);
} }
} else
vTaskDelay(5);
} }
} }
@ -285,8 +352,8 @@ static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length)
uint32_t outputPort = PIOS_COM_TELEMETRY; uint32_t outputPort = PIOS_COM_TELEMETRY;
#if defined(PIOS_INCLUDE_USB) #if defined(PIOS_INCLUDE_USB)
// Determine output port (USB takes priority over telemetry port) // Determine output port (USB takes priority over telemetry port)
if (PIOS_COM_TELEM_USB && PIOS_COM_Available(PIOS_COM_TELEM_USB)) if (PIOS_COM_TELEM_USB_HID && PIOS_COM_Available(PIOS_COM_TELEM_USB_HID))
outputPort = PIOS_COM_TELEM_USB; outputPort = PIOS_COM_TELEM_USB_HID;
#endif /* PIOS_INCLUDE_USB */ #endif /* PIOS_INCLUDE_USB */
if(outputPort) if(outputPort)
return PIOS_COM_SendBufferNonBlocking(outputPort, buf, length); return PIOS_COM_SendBufferNonBlocking(outputPort, buf, length);
@ -303,13 +370,14 @@ static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length)
*/ */
static int32_t RadioSendHandler(uint8_t *buf, int32_t length) static int32_t RadioSendHandler(uint8_t *buf, int32_t length)
{ {
uint32_t outputPort = PIOS_COM_RADIO; uint32_t outputPort = PIOS_COM_RADIO;
// Don't send any data unless the radio port is available. // Don't send any data unless the radio port is available.
if(outputPort && PIOS_COM_Available(outputPort)) if(outputPort && PIOS_COM_Available(outputPort)) {
return PIOS_COM_SendBuffer(outputPort, buf, length); return PIOS_COM_SendBufferNonBlocking(outputPort, buf, length);
else } else {
// For some reason, if this function returns failure, it prevents saving settings. // For some reason, if this function returns failure, it prevents saving settings.
return length; return length;
}
} }
static void ProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte) static void ProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte)
@ -443,161 +511,149 @@ static void queueEvent(xQueueHandle queue, void *obj, uint16_t instId, UAVObjEve
* \param[in] com_port The com port to configure * \param[in] com_port The com port to configure
* \param[in] com_speed The com port speed * \param[in] com_speed The com port speed
*/ */
static void configureComCallback(OPLinkSettingsOutputConnectionOptions com_port, OPLinkSettingsComSpeedOptions com_speed) static void configureComCallback(OPLinkSettingsRemoteMainPortOptions main_port, OPLinkSettingsRemoteFlexiPortOptions flexi_port,
OPLinkSettingsRemoteVCPPortOptions vcp_port, OPLinkSettingsComSpeedOptions com_speed,
uint32_t min_frequency, uint32_t max_frequency, uint32_t channel_spacing)
{ {
// Get the settings. // Update the com baud rate
OPLinkSettingsData oplinkSettings; data->comSpeed = com_speed;
OPLinkSettingsGet(&oplinkSettings);
// Set the output telemetry port and speed. // Set the output main/flexi/vcp port and speed.
switch (com_port) bool is_coordinator = PIOS_RFM22B_IsCoordinator(pios_rfm22b_id);
{ if (!is_coordinator) {
case OPLINKSETTINGS_OUTPUTCONNECTION_REMOTEHID:
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_HID; // Get the settings.
break; OPLinkSettingsData oplinkSettings;
case OPLINKSETTINGS_OUTPUTCONNECTION_REMOTEVCP: OPLinkSettingsGet(&oplinkSettings);
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_VCP;
break; switch (main_port) {
case OPLINKSETTINGS_OUTPUTCONNECTION_REMOTETELEMETRY: case OPLINKSETTINGS_REMOTEMAINPORT_DISABLED:
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_TELEMETRY; oplinkSettings.MainPort = OPLINKSETTINGS_MAINPORT_DISABLED;
break; break;
case OPLINKSETTINGS_OUTPUTCONNECTION_REMOTEFLEXI: case OPLINKSETTINGS_REMOTEMAINPORT_SERIAL:
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_FLEXI; oplinkSettings.MainPort = OPLINKSETTINGS_MAINPORT_SERIAL;
break; break;
case OPLINKSETTINGS_OUTPUTCONNECTION_TELEMETRY: case OPLINKSETTINGS_REMOTEMAINPORT_PPM:
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_HID; oplinkSettings.MainPort = OPLINKSETTINGS_MAINPORT_PPM;
break; break;
case OPLINKSETTINGS_OUTPUTCONNECTION_FLEXI:
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_HID;
break;
} }
oplinkSettings.ComSpeed = com_speed;
// A non-coordinator modem should not set a remote telemetry connection. switch (flexi_port) {
oplinkSettings.OutputConnection = OPLINKSETTINGS_OUTPUTCONNECTION_REMOTEHID; case OPLINKSETTINGS_REMOTEFLEXIPORT_DISABLED:
oplinkSettings.FlexiPort = OPLINKSETTINGS_FLEXIPORT_DISABLED;
break;
case OPLINKSETTINGS_REMOTEFLEXIPORT_SERIAL:
oplinkSettings.FlexiPort = OPLINKSETTINGS_FLEXIPORT_SERIAL;
break;
case OPLINKSETTINGS_REMOTEFLEXIPORT_PPM:
oplinkSettings.FlexiPort = OPLINKSETTINGS_FLEXIPORT_PPM;
break;
}
// Update the OPLinkSettings object. switch (vcp_port) {
OPLinkSettingsSet(&oplinkSettings); case OPLINKSETTINGS_REMOTEVCPPORT_DISABLED:
oplinkSettings.VCPPort = OPLINKSETTINGS_VCPPORT_DISABLED;
break;
case OPLINKSETTINGS_REMOTEVCPPORT_SERIAL:
oplinkSettings.VCPPort = OPLINKSETTINGS_VCPPORT_SERIAL;
break;
}
// Perform the update. // Set the frequency range.
updateSettings(); PIOS_RFM22B_SetFrequencyRange(pios_rfm22b_id, min_frequency, max_frequency, channel_spacing);
// Update the OPLinkSettings object.
OPLinkSettingsSet(&oplinkSettings);
}
// Perform the update.
updateSettings();
} }
/** /**
* Update the oplink settings, called on startup. * Update the oplink settings.
*/ */
static void updateSettings() static void updateSettings()
{ {
// Get the settings.
OPLinkSettingsData oplinkSettings;
OPLinkSettingsGet(&oplinkSettings);
// Get the settings. // Configure the main port
OPLinkSettingsData oplinkSettings; bool is_coordinator = PIOS_RFM22B_IsCoordinator(pios_rfm22b_id);
OPLinkSettingsGet(&oplinkSettings); switch (oplinkSettings.MainPort)
{
case OPLINKSETTINGS_MAINPORT_TELEMETRY:
data->parseUAVTalk = true;
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;
}
bool is_coordinator = (oplinkSettings.Coordinator == OPLINKSETTINGS_COORDINATOR_TRUE); // Configure the flexi port
if (is_coordinator) switch (oplinkSettings.FlexiPort)
{ {
// Set the remote com configuration parameters case OPLINKSETTINGS_FLEXIPORT_TELEMETRY:
PIOS_RFM22B_SetRemoteComConfig(pios_rfm22b_id, oplinkSettings.OutputConnection, oplinkSettings.ComSpeed); data->parseUAVTalk = true;
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 RFM22B device as coordinator or not // Configure the USB VCP port
PIOS_RFM22B_SetCoordinator(pios_rfm22b_id, true); switch (oplinkSettings.VCPPort)
{
case OPLINKSETTINGS_VCPPORT_SERIAL:
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_USB_VCP;
break;
case OPLINKSETTINGS_VCPPORT_DISABLED:
break;
}
// Set the frequencies. // Update the com baud rate.
PIOS_RFM22B_SetFrequencyRange(pios_rfm22b_id, oplinkSettings.MinFrequency, oplinkSettings.MaxFrequency); uint32_t comBaud = 9600;
switch (data->comSpeed) {
// Set the maximum radio RF power. case OPLINKSETTINGS_COMSPEED_2400:
switch (oplinkSettings.MaxRFPower) comBaud = 2400;
{ break;
case OPLINKSETTINGS_MAXRFPOWER_125: case OPLINKSETTINGS_COMSPEED_4800:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); comBaud = 4800;
break; break;
case OPLINKSETTINGS_MAXRFPOWER_16: case OPLINKSETTINGS_COMSPEED_9600:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1); comBaud = 9600;
break; break;
case OPLINKSETTINGS_MAXRFPOWER_316: case OPLINKSETTINGS_COMSPEED_19200:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2); comBaud = 19200;
break; break;
case OPLINKSETTINGS_MAXRFPOWER_63: case OPLINKSETTINGS_COMSPEED_38400:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3); comBaud = 38400;
break; break;
case OPLINKSETTINGS_MAXRFPOWER_126: case OPLINKSETTINGS_COMSPEED_57600:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4); comBaud = 57600;
break; break;
case OPLINKSETTINGS_MAXRFPOWER_25: case OPLINKSETTINGS_COMSPEED_115200:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5); comBaud = 115200;
break; break;
case OPLINKSETTINGS_MAXRFPOWER_50: }
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6); if (PIOS_COM_RADIO) {
break; PIOS_COM_ChangeBaud(PIOS_COM_RADIO, comBaud);
case OPLINKSETTINGS_MAXRFPOWER_100: }
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7); if (PIOS_COM_TELEMETRY) {
break; PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, comBaud);
} }
// Set the radio destination ID.
PIOS_RFM22B_SetDestinationId(pios_rfm22b_id, oplinkSettings.PairID);
}
// Determine what com ports we're using.
switch (oplinkSettings.InputConnection)
{
case OPLINKSETTINGS_INPUTCONNECTION_VCP:
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_VCP;
break;
case OPLINKSETTINGS_INPUTCONNECTION_TELEMETRY:
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_TELEM;
break;
case OPLINKSETTINGS_INPUTCONNECTION_FLEXI:
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_FLEXI;
break;
default:
PIOS_COM_TELEMETRY = 0;
break;
}
switch (oplinkSettings.OutputConnection)
{
case OPLINKSETTINGS_OUTPUTCONNECTION_FLEXI:
PIOS_COM_RADIO = PIOS_COM_TELEM_UART_FLEXI;
break;
case OPLINKSETTINGS_OUTPUTCONNECTION_TELEMETRY:
PIOS_COM_RADIO = PIOS_COM_TELEM_UART_TELEM;
break;
default:
PIOS_COM_RADIO = PIOS_COM_RFM22B;
break;
}
// Configure the com port speeds.
switch (oplinkSettings.ComSpeed) {
case OPLINKSETTINGS_COMSPEED_2400:
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 2400);
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 2400);
break;
case OPLINKSETTINGS_COMSPEED_4800:
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 4800);
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 4800);
break;
case OPLINKSETTINGS_COMSPEED_9600:
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 9600);
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 9600);
break;
case OPLINKSETTINGS_COMSPEED_19200:
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 19200);
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 19200);
break;
case OPLINKSETTINGS_COMSPEED_38400:
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 38400);
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 38400);
break;
case OPLINKSETTINGS_COMSPEED_57600:
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 57600);
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 57600);
break;
case OPLINKSETTINGS_COMSPEED_115200:
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 115200);
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 115200);
break;
}
} }

View File

@ -174,17 +174,18 @@ extern uint32_t pios_i2c_flexi_adapter_id;
extern uint32_t pios_com_telem_usb_id; extern uint32_t pios_com_telem_usb_id;
extern uint32_t pios_com_telem_vcp_id; extern uint32_t pios_com_telem_vcp_id;
extern uint32_t pios_com_telem_uart_telem_id; extern uint32_t pios_com_telem_uart_main_id;
extern uint32_t pios_com_telem_uart_flexi_id; extern uint32_t pios_com_telem_uart_flexi_id;
extern uint32_t pios_com_telemetry_id; extern uint32_t pios_com_telemetry_id;
extern uint32_t pios_com_rfm22b_id; extern uint32_t pios_com_rfm22b_id;
extern uint32_t pios_com_radio_id; extern uint32_t pios_com_radio_id;
extern uint32_t pios_ppm_rcvr_id; extern uint32_t pios_ppm_rcvr_id;
extern uint32_t pios_ppm_out_id; extern uint32_t pios_ppm_out_id;
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) #define PIOS_COM_TELEM_USB_HID (pios_com_telem_usb_id)
#define PIOS_COM_TELEM_VCP (pios_com_telem_vcp_id) #define PIOS_COM_TELEM_USB PIOS_COM_TELEM_USB_HID
#define PIOS_COM_TELEM_USB_VCP (pios_com_telem_vcp_id)
#define PIOS_COM_TELEM_UART_MAIN (pios_com_telem_uart_main_id)
#define PIOS_COM_TELEM_UART_FLEXI (pios_com_telem_uart_flexi_id) #define PIOS_COM_TELEM_UART_FLEXI (pios_com_telem_uart_flexi_id)
#define PIOS_COM_TELEM_UART_TELEM (pios_com_telem_uart_telem_id)
#define PIOS_COM_TELEMETRY (pios_com_telemetry_id) #define PIOS_COM_TELEMETRY (pios_com_telemetry_id)
#define PIOS_COM_RFM22B (pios_com_rfm22b_id) #define PIOS_COM_RFM22B (pios_com_rfm22b_id)
#define PIOS_COM_RADIO (pios_com_radio_id) #define PIOS_COM_RADIO (pios_com_radio_id)

View File

@ -77,6 +77,28 @@ TIM8 | | | |
//------------------------ //------------------------
#define PIOS_LED_HEARTBEAT 0 #define PIOS_LED_HEARTBEAT 0
#define PIOS_LED_ALARM 1 #define PIOS_LED_ALARM 1
#ifdef PIOS_RFM22B_DEBUG_ON_SERVO
#define PIOS_LED_D1 2
#define PIOS_LED_D2 3
#define PIOS_LED_D3 4
#define PIOS_LED_D4 5
#define D1_LED_ON PIOS_LED_On(PIOS_LED_D1)
#define D1_LED_OFF PIOS_LED_Off(PIOS_LED_D1)
#define D1_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D1)
#define D2_LED_ON PIOS_LED_On(PIOS_LED_D2)
#define D2_LED_OFF PIOS_LED_Off(PIOS_LED_D2)
#define D2_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D2)
#define D3_LED_ON PIOS_LED_On(PIOS_LED_D3)
#define D3_LED_OFF PIOS_LED_Off(PIOS_LED_D3)
#define D3_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D3)
#define D4_LED_ON PIOS_LED_On(PIOS_LED_D4)
#define D4_LED_OFF PIOS_LED_Off(PIOS_LED_D4)
#define D4_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D4)
#endif
//------------------------ //------------------------
// PIOS_SPI // PIOS_SPI
@ -193,7 +215,6 @@ extern uint32_t pios_packet_handler;
// //
#define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK #define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK
//------------------------- //-------------------------
// Interrupt Priorities // Interrupt Priorities
//------------------------- //-------------------------
@ -209,7 +230,7 @@ extern uint32_t pios_packet_handler;
#define PIOS_RCVR_MAX_DEVS 3 #define PIOS_RCVR_MAX_DEVS 3
#define PIOS_RCVR_MAX_CHANNELS 12 #define PIOS_RCVR_MAX_CHANNELS 12
#define PIOS_GCSRCVR_TIMEOUT_MS 100 #define PIOS_GCSRCVR_TIMEOUT_MS 100
#define PIOS_RFM22B_RCVR_TIMEOUT_MS 100 #define PIOS_RFM22B_RCVR_TIMEOUT_MS 200
//------------------------- //-------------------------
// Receiver PPM input // Receiver PPM input

View File

@ -52,6 +52,9 @@
#include <pios_spi_priv.h> #include <pios_spi_priv.h>
#include <packet_handler.h> #include <packet_handler.h>
#if defined(PIOS_INCLUDE_GCSRCVR)
#include <gcsreceiver.h>
#endif
#include <pios_rfm22b_priv.h> #include <pios_rfm22b_priv.h>
#include <pios_ppm_out_priv.h> #include <pios_ppm_out_priv.h>
#include <ecc.h> #include <ecc.h>
@ -62,11 +65,13 @@
#define ISR_TIMEOUT 2 // ms #define ISR_TIMEOUT 2 // ms
#define EVENT_QUEUE_SIZE 5 #define EVENT_QUEUE_SIZE 5
#define RFM22B_DEFAULT_RX_DATARATE RFM22_datarate_9600 #define RFM22B_DEFAULT_RX_DATARATE RFM22_datarate_9600
#define RFM22B_DEFAULT_FREQUENCY 434000000 #define RFM22B_DEFAULT_TX_POWER RFM22_tx_pwr_txpow_0
#define RFM22B_DEFAULT_MIN_FREQUENCY (RFM22B_DEFAULT_FREQUENCY - 2000000)
#define RFM22B_DEFAULT_MAX_FREQUENCY (RFM22B_DEFAULT_FREQUENCY + 2000000)
#define RFM22B_DEFAULT_TX_POWER RFM22_tx_pwr_txpow_7
#define RFM22B_LINK_QUALITY_THRESHOLD 20 #define RFM22B_LINK_QUALITY_THRESHOLD 20
#define RFM22B_NOMINAL_CARRIER_FREQUENCY 430000000
#define RFM22B_MAXIMUM_FREQUENCY 440000000
#define RFM22B_DEFAULT_FREQUENCY 433000000
#define RFM22B_FREQUENCY_HOP_STEP_SIZE 75000
//#define RFM22B_TEST_DROPPED_PACKETS 1
// The maximum amount of time since the last message received to consider the connection broken. // The maximum amount of time since the last message received to consider the connection broken.
#define DISCONNECT_TIMEOUT_MS 1000 // ms #define DISCONNECT_TIMEOUT_MS 1000 // ms
@ -84,7 +89,7 @@
#define MAX_RADIOSTATS_MISS_COUNT 3 #define MAX_RADIOSTATS_MISS_COUNT 3
// The time between PPM updates // The time between PPM updates
#define PPM_UPDATE_PERIOD_MS 40 #define PPM_UPDATE_PERIOD_MS 20
// this is too adjust the RF module so that it is on frequency // this is too adjust the RF module so that it is on frequency
#define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default #define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default
@ -142,8 +147,8 @@ struct pios_rfm22b_transition {
}; };
// Must ensure these prefilled arrays match the define sizes // Must ensure these prefilled arrays match the define sizes
static const uint8_t FULL_PREAMBLE[FIFO_SIZE] = static const uint8_t FULL_PREAMBLE[FIFO_SIZE] = {
{PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,
PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,
PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,
PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,
@ -157,7 +162,8 @@ static const uint8_t FULL_PREAMBLE[FIFO_SIZE] =
PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,
PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE}; // 64 bytes PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE}; // 64 bytes
static const uint8_t HEADER[(TX_PREAMBLE_NIBBLES + 1)/2 + 2] = {PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE,PREAMBLE_BYTE, PREAMBLE_BYTE, SYNC_BYTE_1, SYNC_BYTE_2}; static const uint8_t HEADER[(TX_PREAMBLE_NIBBLES + 1)/2 + 2] = {PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE,PREAMBLE_BYTE, PREAMBLE_BYTE, SYNC_BYTE_1, SYNC_BYTE_2};
static const uint8_t OUT_FF[64] = {0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, static const uint8_t OUT_FF[64] = {
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
@ -182,7 +188,6 @@ static enum pios_rfm22b_event rfm22_receiveNack(struct pios_rfm22b_dev *rfm22b_d
static enum pios_rfm22b_event rfm22_sendAck(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_sendAck(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_rfm22b_event rfm22_sendNack(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_sendNack(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_rfm22b_event rfm22_requestConnection(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_requestConnection(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_rfm22b_event rfm22_initConnection(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_rfm22b_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev);
@ -196,10 +201,16 @@ static void rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev);
static void rfm22_sendPPM(struct pios_rfm22b_dev *rfm22b_dev); static void rfm22_sendPPM(struct pios_rfm22b_dev *rfm22b_dev);
static void rfm22b_add_rx_status(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_rx_packet_status status); static void rfm22b_add_rx_status(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_rx_packet_status status);
static bool rfm22_receivePacket(struct pios_rfm22b_dev *rfm22b_dev, PHPacketHandle p, uint16_t rx_len); static bool rfm22_receivePacket(struct pios_rfm22b_dev *rfm22b_dev, PHPacketHandle p, uint16_t rx_len);
static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint32_t frequency_hz); static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint32_t min_frequency, uint32_t max_frequency, uint32_t step_size);
static bool rfm22_setFreqHopChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t channel);
static void rfm22_calculateLinkQuality(struct pios_rfm22b_dev *rfm22b_dev); static void rfm22_calculateLinkQuality(struct pios_rfm22b_dev *rfm22b_dev);
static bool rfm22_ready_to_send(struct pios_rfm22b_dev *rfm22b_dev); static bool rfm22_ready_to_send(struct pios_rfm22b_dev *rfm22b_dev);
static bool rfm22_isConnected(struct pios_rfm22b_dev *rfm22b_dev);
static void rfm22_setConnectionParameters(struct pios_rfm22b_dev *rfm22b_dev); static void rfm22_setConnectionParameters(struct pios_rfm22b_dev *rfm22b_dev);
static portTickType rfm22_coordinatorTime(struct pios_rfm22b_dev *rfm22b_dev, portTickType ticks);
static bool rfm22_inChannelBuffer(struct pios_rfm22b_dev *rfm22b_dev);
static uint8_t rfm22_calcChannel(struct pios_rfm22b_dev *rfm22b_dev);
static bool rfm22_changeChannel(struct pios_rfm22b_dev *rfm22b_dev);
static void rfm22_clearLEDs(); static void rfm22_clearLEDs();
// SPI read/write functions // SPI read/write functions
@ -225,18 +236,7 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
[RFM22B_STATE_INITIALIZING] = { [RFM22B_STATE_INITIALIZING] = {
.entry_fn = rfm22_init, .entry_fn = rfm22_init,
.next_state = { .next_state = {
[RFM22B_EVENT_INITIALIZED] = RFM22B_STATE_INITIATING_CONNECTION, [RFM22B_EVENT_INITIALIZED] = RFM22B_STATE_RX_MODE,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
},
},
[RFM22B_STATE_INITIATING_CONNECTION] = {
.entry_fn = rfm22_initConnection,
.next_state = {
[RFM22B_EVENT_REQUEST_CONNECTION] = RFM22B_STATE_REQUESTING_CONNECTION,
[RFM22B_EVENT_WAIT_FOR_CONNECTION] = RFM22B_STATE_RX_MODE,
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
@ -249,13 +249,13 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT, [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR
}, },
}, },
[RFM22B_STATE_ACCEPTING_CONNECTION] = { [RFM22B_STATE_ACCEPTING_CONNECTION] = {
.entry_fn = rfm22_acceptConnection, .entry_fn = rfm22_acceptConnection,
.next_state = { .next_state = {
[RFM22B_EVENT_CONNECTION_ACCEPTED] = RFM22B_STATE_SENDING_ACK, [RFM22B_EVENT_DEFAULT] = RFM22B_STATE_SENDING_ACK,
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT, [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
@ -307,6 +307,7 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
.next_state = { .next_state = {
[RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_RX_DATA, [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_RX_DATA,
[RFM22B_EVENT_RX_COMPLETE] = RFM22B_STATE_SENDING_ACK, [RFM22B_EVENT_RX_COMPLETE] = RFM22B_STATE_SENDING_ACK,
[RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE,
[RFM22B_EVENT_RX_ERROR] = RFM22B_STATE_SENDING_NACK, [RFM22B_EVENT_RX_ERROR] = RFM22B_STATE_SENDING_NACK,
[RFM22B_EVENT_STATUS_RECEIVED] = RFM22B_STATE_RECEIVING_STATUS, [RFM22B_EVENT_STATUS_RECEIVED] = RFM22B_STATE_RECEIVING_STATUS,
[RFM22B_EVENT_CONNECTION_REQUESTED] = RFM22B_STATE_ACCEPTING_CONNECTION, [RFM22B_EVENT_CONNECTION_REQUESTED] = RFM22B_STATE_ACCEPTING_CONNECTION,
@ -375,6 +376,7 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
.entry_fn = rfm22_txData, .entry_fn = rfm22_txData,
.next_state = { .next_state = {
[RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_TX_DATA, [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_TX_DATA,
[RFM22B_EVENT_REQUEST_CONNECTION] = RFM22B_STATE_REQUESTING_CONNECTION,
[RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE, [RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE,
[RFM22B_EVENT_FAILURE] = RFM22B_STATE_TX_FAILURE, [RFM22B_EVENT_FAILURE] = RFM22B_STATE_TX_FAILURE,
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT, [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
@ -397,7 +399,6 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
.entry_fn = rfm22_sendAck, .entry_fn = rfm22_sendAck,
.next_state = { .next_state = {
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
@ -407,7 +408,6 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
.entry_fn = rfm22_sendNack, .entry_fn = rfm22_sendNack,
.next_state = { .next_state = {
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
@ -417,7 +417,6 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
.entry_fn = rfm22_timeout, .entry_fn = rfm22_timeout,
.next_state = { .next_state = {
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
@ -426,7 +425,6 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
[RFM22B_STATE_ERROR] = { [RFM22B_STATE_ERROR] = {
.entry_fn = rfm22_error, .entry_fn = rfm22_error,
.next_state = { .next_state = {
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
@ -440,63 +438,34 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
}; };
// xtal 10 ppm, 434MHz // xtal 10 ppm, 434MHz
#define LOOKUP_SIZE 14 #define LOOKUP_SIZE 15
static const uint32_t data_rate[] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 64000, 128000, 192000, 256000}; static const uint32_t data_rate[] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 57600, 64000, 128000, 192000, 256000};
static const uint8_t modulation_index[] = { 16, 8, 4, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}; static const uint8_t modulation_index[] = { 16, 8, 4, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1};
static const uint32_t freq_deviation[] = { 4000, 4000, 4000, 4000, 4000, 4800, 8000, 9600, 12000, 16000, 32000, 64000, 96000, 128000};
static const uint32_t rx_bandwidth[] = { 17500, 17500, 17500, 17500, 17500, 19400, 32200, 38600, 51200, 64100, 137900, 269300, 420200, 518800};
static const int8_t est_rx_sens_dBm[] = { -118, -118, -117, -116, -115, -115, -112, -112, -110, -109, -106, -103, -101, -100}; // estimated receiver sensitivity for BER = 1E-3
static const uint8_t reg_1C[] = { 0x37, 0x37, 0x37, 0x37, 0x3A, 0x3B, 0x26, 0x28, 0x2E, 0x16, 0x07, 0x83, 0x8A, 0x8C}; // rfm22_if_filter_bandwidth static const uint8_t reg_1C[] = { 0x37, 0x37, 0x37, 0x37, 0x3A, 0x3B, 0x26, 0x28, 0x2E, 0x16, 0x06, 0x07, 0x83, 0x8A, 0x8C}; // rfm22_if_filter_bandwidth
static const uint8_t reg_1D[] = { 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44}; // rfm22_afc_loop_gearshift_override static const uint8_t reg_1D[] = { 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x40, 0x44, 0x44, 0x44, 0x44}; // rfm22_afc_loop_gearshift_override
static const uint8_t reg_1E[] = { 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x02}; // rfm22_afc_timing_control static const uint8_t reg_1E[] = { 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 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, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03}; // rfm22_clk_recovery_gearshift_override static const uint8_t reg_1F[] = { 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03}; // rfm22_clk_recovery_gearshift_override
static const uint8_t reg_20[] = { 0xE8, 0xF4, 0xFA, 0x70, 0x3F, 0x34, 0x3F, 0x34, 0x2A, 0x3F, 0x3F, 0x5E, 0x3F, 0x2F}; // rfm22_clk_recovery_oversampling_ratio static const uint8_t reg_20[] = { 0xE8, 0xF4, 0xFA, 0x70, 0x3F, 0x34, 0x3F, 0x34, 0x2A, 0x3F, 0x45, 0x3F, 0x5E, 0x3F, 0x2F}; // rfm22_clk_recovery_oversampling_ratio
static const uint8_t reg_21[] = { 0x60, 0x20, 0x00, 0x01, 0x02, 0x02, 0x02, 0x02, 0x03, 0x02, 0x02, 0x01, 0x02, 0x02}; // rfm22_clk_recovery_offset2 static const uint8_t reg_21[] = { 0x60, 0x20, 0x00, 0x01, 0x02, 0x02, 0x02, 0x02, 0x03, 0x02, 0x01, 0x02, 0x01, 0x02, 0x02}; // rfm22_clk_recovery_offset2
static const uint8_t reg_22[] = { 0x20, 0x41, 0x83, 0x06, 0x0C, 0x75, 0x0C, 0x75, 0x12, 0x0C, 0x0C, 0x5D, 0x0C, 0xBB}; // rfm22_clk_recovery_offset1 static const uint8_t reg_22[] = { 0x20, 0x41, 0x83, 0x06, 0x0C, 0x75, 0x0C, 0x75, 0x12, 0x0C, 0xD7, 0x0c, 0x5D, 0x0C, 0xBB}; // rfm22_clk_recovery_offset1
static const uint8_t reg_23[] = { 0xC5, 0x89, 0x12, 0x25, 0x4A, 0x25, 0x4A, 0x25, 0x6F, 0x4A, 0x4A, 0x86, 0x4A, 0x0D}; // rfm22_clk_recovery_offset0 static const uint8_t reg_23[] = { 0xC5, 0x89, 0x12, 0x25, 0x4A, 0x25, 0x4A, 0x25, 0x6F, 0x4A, 0xDC, 0x4A, 0x86, 0x4A, 0x0D}; // rfm22_clk_recovery_offset0
static const uint8_t reg_24[] = { 0x00, 0x00, 0x00, 0x02, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x05, 0x07, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 static const uint8_t reg_24[] = { 0x00, 0x00, 0x00, 0x02, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x05, 0x07, 0x07}; // rfm22_clk_recovery_timing_loop_gain1
static const uint8_t reg_25[] = { 0x0A, 0x23, 0x85, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x74, 0xFF, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 static const uint8_t reg_25[] = { 0x0A, 0x23, 0x85, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x6E, 0xFF, 0x74, 0xFF, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0
static const uint8_t reg_2A[] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 0x17, 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[] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 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_6E[] = { 0x04, 0x08, 0x10, 0x20, 0x41, 0x4E, 0x83, 0x9D, 0xC4, 0x08, 0x10, 0x20, 0x31, 0x41}; // rfm22_tx_data_rate1 static const uint8_t reg_58[] = { 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80}; // rfm22_cpcuu
static const uint8_t reg_6F[] = { 0x19, 0x31, 0x62, 0xC5, 0x89, 0xA5, 0x12, 0x49, 0x9C, 0x31, 0x62, 0xC5, 0x27, 0x89}; // rfm22_tx_data_rate0 static const uint8_t reg_69[] = { 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x60, 0x20, 0x20, 0x20, 0x20}; // rfm22_agc_override1
static const uint8_t reg_6E[] = { 0x04, 0x08, 0x10, 0x20, 0x41, 0x4E, 0x83, 0x9D, 0xC4, 0x08, 0x0E, 0x10, 0x20, 0x31, 0x41}; // rfm22_tx_data_rate1
static const uint8_t reg_6F[] = { 0x19, 0x31, 0x62, 0xC5, 0x89, 0xA5, 0x12, 0x49, 0x9C, 0x31, 0xBF, 0x62, 0xC5, 0x27, 0x89}; // rfm22_tx_data_rate0
static const uint8_t reg_70[] = { 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x0D, 0x0D, 0x0D, 0x0D, 0x0D}; // rfm22_modulation_mode_control1 static const uint8_t reg_70[] = { 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x0D, 0x0C, 0x0C, 0x0D, 0x0D, 0x0D}; // rfm22_modulation_mode_control1
static const uint8_t reg_71[] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23}; // rfm22_modulation_mode_control2 static const uint8_t reg_71[] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23}; // rfm22_modulation_mode_control2
static const uint8_t reg_72[] = { 0x06, 0x06, 0x06, 0x06, 0x06, 0x08, 0x0D, 0x0F, 0x13, 0x1A, 0x33, 0x66, 0x9A, 0xCD}; // rfm22_frequency_deviation static const uint8_t reg_72[] = { 0x06, 0x06, 0x06, 0x06, 0x06, 0x08, 0x0D, 0x0F, 0x13, 0x1A, 0x2E, 0x33, 0x66, 0x9A, 0xCD}; // rfm22_frequency_deviation
// ************************************
// Scan Spectrum settings
// GFSK modulation
// no manchester encoding
// data whitening
// FIFO mode
// 5-nibble rx preamble length detection
// 10-nibble tx preamble length
#define SS_LOOKUP_SIZE 2
// xtal 1 ppm, 434MHz
static const uint32_t ss_rx_bandwidth[] = { 2600, 10600};
static const uint8_t ss_reg_1C[] = { 0x51, 0x32}; // rfm22_if_filter_bandwidth
static const uint8_t ss_reg_1D[] = { 0x00, 0x00}; // rfm22_afc_loop_gearshift_override
static const uint8_t ss_reg_20[] = { 0xE8, 0x38}; // rfm22_clk_recovery_oversampling_ratio
static const uint8_t ss_reg_21[] = { 0x60, 0x02}; // rfm22_clk_recovery_offset2
static const uint8_t ss_reg_22[] = { 0x20, 0x4D}; // rfm22_clk_recovery_offset1
static const uint8_t ss_reg_23[] = { 0xC5, 0xD3}; // rfm22_clk_recovery_offset0
static const uint8_t ss_reg_24[] = { 0x00, 0x07}; // rfm22_clk_recovery_timing_loop_gain1
static const uint8_t ss_reg_25[] = { 0x0F, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0
static const uint8_t ss_reg_2A[] = { 0xFF, 0xFF}; // rfm22_afc_limiter .. AFC_pull_in_range = <20>AFCLimiter[7:0] x (hbsel+1) x 625 Hz
static const uint8_t ss_reg_70[] = { 0x24, 0x2D}; // rfm22_modulation_mode_control1
static const uint8_t ss_reg_71[] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2
static inline uint32_t timeDifferenceMs(portTickType start_time, portTickType end_time) static inline uint32_t timeDifferenceMs(portTickType start_time, portTickType end_time)
@ -563,9 +532,9 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
rfm22b_dev->spi_id = spi_id; rfm22b_dev->spi_id = spi_id;
// Initialize our configuration parameters // Initialize our configuration parameters
rfm22b_dev->coordinator = false;
rfm22b_dev->send_ppm = false; rfm22b_dev->send_ppm = false;
rfm22b_dev->datarate = RFM22B_DEFAULT_RX_DATARATE; rfm22b_dev->datarate = RFM22B_DEFAULT_RX_DATARATE;
rfm22b_dev->tx_power = RFM22B_DEFAULT_TX_POWER;
// Initialize the com callbacks. // Initialize the com callbacks.
rfm22b_dev->com_config_cb = NULL; rfm22b_dev->com_config_cb = NULL;
@ -584,6 +553,18 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
rfm22b_dev->stats.timeouts = 0; rfm22b_dev->stats.timeouts = 0;
rfm22b_dev->stats.link_quality = 0; rfm22b_dev->stats.link_quality = 0;
rfm22b_dev->stats.rssi = 0; rfm22b_dev->stats.rssi = 0;
rfm22b_dev->stats.tx_seq = 0;
rfm22b_dev->stats.rx_seq = 0;
// Initialize the frequencies.
PIOS_RFM22B_SetInitialFrequency(*rfm22b_id, RFM22B_DEFAULT_FREQUENCY);
PIOS_RFM22B_SetFrequencyRange(*rfm22b_id, RFM22B_DEFAULT_FREQUENCY, RFM22B_DEFAULT_FREQUENCY, RFM22B_FREQUENCY_HOP_STEP_SIZE);
// Initialize the bindings.
for (uint32_t i = 0; i < OPLINKSETTINGS_BINDINGS_NUMELEM; ++i) {
rfm22b_dev->bindings[i].pairID = 0;
}
rfm22b_dev->coordinator = false;
// Create the event queue // Create the event queue
rfm22b_dev->eventQueue = xQueueCreate(EVENT_QUEUE_SIZE, sizeof(enum pios_rfm22b_event)); rfm22b_dev->eventQueue = xQueueCreate(EVENT_QUEUE_SIZE, sizeof(enum pios_rfm22b_event));
@ -606,6 +587,11 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
rfm22b_dev->deviceID = crcs[0] | crcs[1] << 8 | crcs[2] << 16 | crcs[3] << 24; rfm22b_dev->deviceID = crcs[0] | crcs[1] << 8 | crcs[2] << 16 | crcs[3] << 24;
DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID); DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID);
#if defined(PIOS_INCLUDE_GCSRCVR)
// Initialize the GCSReceive object
GCSReceiverInitialize();
#endif
// Initialize the external interrupt. // Initialize the external interrupt.
PIOS_EXTI_Init(cfg->exti_cfg); PIOS_EXTI_Init(cfg->exti_cfg);
@ -629,13 +615,23 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
return(0); return(0);
} }
/**
* Re-initialize the modem after a configuration change.
*/
void PIOS_RFM22B_Reinit(uint32_t rfm22b_id)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (PIOS_RFM22B_validate(rfm22b_dev))
PIOS_RFM22B_InjectEvent(rfm22b_dev, RFM22B_EVENT_INITIALIZE, false);
}
/** /**
* The RFM22B external interrupt routine. * The RFM22B external interrupt routine.
*/ */
bool PIOS_RFM22_EXT_Int(void) bool PIOS_RFM22_EXT_Int(void)
{ {
if (!PIOS_RFM22B_validate(g_rfm22b_dev)) if (!PIOS_RFM22B_validate(g_rfm22b_dev))
return false; return false;
// Inject an interrupt event into the state machine. // Inject an interrupt event into the state machine.
PIOS_RFM22B_InjectEvent(g_rfm22b_dev, RFM22B_EVENT_INT_RECEIVED, true); PIOS_RFM22B_InjectEvent(g_rfm22b_dev, RFM22B_EVENT_INT_RECEIVED, true);
@ -681,10 +677,26 @@ void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22
uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id) uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id)
{ {
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (PIOS_RFM22B_validate(rfm22b_dev)) if (PIOS_RFM22B_validate(rfm22b_dev)) {
return rfm22b_dev->deviceID; return rfm22b_dev->deviceID;
else } else {
return 0; return 0;
}
}
/**
* Returns true if the modem is configured as a coordinator.
* \param[in] rfm22b_id The RFM22B device index.
* \return True if the modem is configured as a coordinator.
*/
bool PIOS_RFM22B_IsCoordinator(uint32_t rfm22b_id)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (PIOS_RFM22B_validate(rfm22b_dev)) {
return rfm22b_dev->coordinator;
} else {
return false;
}
} }
/** /**
@ -695,74 +707,42 @@ uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id)
void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr) void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr)
{ {
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_validate(rfm22b_dev)) if (!PIOS_RFM22B_validate(rfm22b_dev)) {
return; return;
}
rfm22b_dev->tx_power = tx_pwr; rfm22b_dev->tx_power = tx_pwr;
} }
/** /**
* Sets the radio frequency range and value. * Sets the radio frequency range and initial frequency
* \param[in] rfm22b_id The RFM22B device index. * \param[in] rfm22b_id The RFM22B device index.
* \param[in] min_frequency The minimum frequency. * \param[in] min_freq The minimum frequency
* \param[in] max_frequency The maximum frequency. * \param[in] max_freq The maximum frequency
* \param[in] step_size The channel step size
*/ */
void PIOS_RFM22B_SetFrequencyRange(uint32_t rfm22b_id, uint32_t min_frequency, uint32_t max_frequency) void PIOS_RFM22B_SetFrequencyRange(uint32_t rfm22b_id, uint32_t min_freq, uint32_t max_freq, uint32_t step_size)
{ {
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_validate(rfm22b_dev)) if (!PIOS_RFM22B_validate(rfm22b_dev)) {
return; return;
rfm22b_dev->min_frequency = min_frequency; }
rfm22b_dev->max_frequency = max_frequency; rfm22b_dev->con_packet.min_frequency = min_freq;
rfm22_setNominalCarrierFrequency(rfm22b_dev, (max_frequency - min_frequency) / 2); rfm22b_dev->con_packet.max_frequency = max_freq;
rfm22b_dev->con_packet.channel_spacing = step_size;
} }
/** /**
* Sets the radio destination ID. * Sets the initial radio frequency range
* \param[in] rfm22b_id The RFM22B device index. * \param[in] rfm22b_id The RFM22B device index.
* \param[in] dest_id The destination ID. * \param[in] init_freq The initial frequency
*/ */
void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id) void PIOS_RFM22B_SetInitialFrequency(uint32_t rfm22b_id, uint32_t init_freq)
{ {
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_validate(rfm22b_dev)) if (!PIOS_RFM22B_validate(rfm22b_dev)) {
return; return;
rfm22b_dev->destination_id = (dest_id == 0) ? 0xffffffff : dest_id; }
// The first slot is reserved for our current pairID rfm22b_dev->init_frequency = init_freq;
rfm22b_dev->pair_stats[0].pairID = dest_id;
rfm22b_dev->pair_stats[0].rssi = -127;
rfm22b_dev->pair_stats[0].afc_correction = 0;
rfm22b_dev->pair_stats[0].lastContact = 0;
}
/**
* Configures the radio as a coordinator or not.
* \param[in] rfm22b_id The RFM22B device index.
* \param[in] coordinator Sets as coordinator if true.
*/
void PIOS_RFM22B_SetCoordinator(uint32_t rfm22b_id, bool coordinator)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_validate(rfm22b_dev))
return;
rfm22b_dev->coordinator = coordinator;
// Re-initialize the radio device.
PIOS_RFM22B_InjectEvent(rfm22b_dev, RFM22B_EVENT_INITIALIZE, false);
}
/**
* Set the remote com port configuration parameters.
* \param[in] rfm22b_id The rfm22b device.
* \param[in] com_port The remote com port
* \param[in] com_speed The remote com port speed
*/
void PIOS_RFM22B_SetRemoteComConfig(uint32_t rfm22b_id, OPLinkSettingsOutputConnectionOptions com_port, OPLinkSettingsComSpeedOptions com_speed)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if(!PIOS_RFM22B_validate(rfm22b_dev))
return;
rfm22b_dev->con_packet.port = com_port;
rfm22b_dev->con_packet.com_speed = com_speed;
} }
/** /**
@ -771,11 +751,35 @@ void PIOS_RFM22B_SetRemoteComConfig(uint32_t rfm22b_id, OPLinkSettingsOutputConn
* \param[in] cb A pointer to the callback function * \param[in] cb A pointer to the callback function
*/ */
void PIOS_RFM22B_SetComConfigCallback(uint32_t rfm22b_id, PIOS_RFM22B_ComConfigCallback cb) void PIOS_RFM22B_SetComConfigCallback(uint32_t rfm22b_id, PIOS_RFM22B_ComConfigCallback cb)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if(!PIOS_RFM22B_validate(rfm22b_dev)) {
return;
}
rfm22b_dev->com_config_cb = cb;
}
/**
* Set the list of modems that this modem will bind with.
* \param[in] rfm22b_id The rfm22b device.
* \param[in] bindings The array of bindings.
*/
void PIOS_RFM22B_SetBindings(uint32_t rfm22b_id, const uint32_t bindingPairIDs[], const uint8_t mainPortSettings[],
const uint8_t flexiPortSettings[], const uint8_t vcpPortSettings[], const uint8_t comSpeeds[])
{ {
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if(!PIOS_RFM22B_validate(rfm22b_dev)) if(!PIOS_RFM22B_validate(rfm22b_dev))
return; return;
rfm22b_dev->com_config_cb = cb; // This modem will be considered a coordinator if any bindings have been set.
rfm22b_dev->coordinator = false;
for (uint32_t i = 0; i < OPLINKSETTINGS_BINDINGS_NUMELEM; ++i) {
rfm22b_dev->bindings[i].pairID = bindingPairIDs[i];
rfm22b_dev->bindings[i].main_port = mainPortSettings[i];
rfm22b_dev->bindings[i].flexi_port = flexiPortSettings[i];
rfm22b_dev->bindings[i].vcp_port = vcpPortSettings[i];
rfm22b_dev->bindings[i].com_speed = comSpeeds[i];
rfm22b_dev->coordinator |= (rfm22b_dev->bindings[i].pairID != 0);
}
} }
/** /**
@ -806,7 +810,7 @@ void PIOS_RFM22B_GetStats(uint32_t rfm22b_id, struct rfm22b_stats *stats) {
*stats = rfm22b_dev->stats; *stats = rfm22b_dev->stats;
} }
/** /**
* Get the stats of the oter radio devices that are in range. * Get the stats of the oter radio devices that are in range.
* \param[out] device_ids A pointer to the array to store the device IDs. * \param[out] device_ids A pointer to the array to store the device IDs.
* \param[out] RSSIs A pointer to the array to store the RSSI values in. * \param[out] RSSIs A pointer to the array to store the RSSI values in.
@ -839,7 +843,41 @@ bool PIOS_RFM22B_LinkStatus(uint32_t rfm22b_id)
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if(!PIOS_RFM22B_validate(rfm22b_dev)) if(!PIOS_RFM22B_validate(rfm22b_dev))
return false; return false;
return (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED) && (rfm22b_dev->stats.link_quality > RFM22B_LINK_QUALITY_THRESHOLD); return (rfm22_isConnected(rfm22b_dev) && (rfm22b_dev->stats.link_quality > RFM22B_LINK_QUALITY_THRESHOLD));
}
/**
* Send a PPM packet with the given channel values.
* \param[in] rfm22b_id The rfm22b device.
* \param[in] channels The channel values.
* \param[in] nchannels The number of channels.
* Returns true if there is a valid connection to paired radio, false otherwise.
*/
void PIOS_RFM22B_SendPPM(uint32_t rfm22b_id, const uint16_t *channels, uint8_t nchannels)
{
#ifdef PIOS_PPM_RECEIVER
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_validate(rfm22b_dev)) {
return;
}
// Only send PPM if we're connected
if (!rfm22_isConnected(rfm22b_dev)) {
return;
}
// See if we have any valid channels.
uint8_t nchan = (nchannels <= PIOS_PPM_NUM_INPUTS) ? nchannels : PIOS_PPM_NUM_INPUTS;
for (uint8_t i = 0; i < nchan; ++i) {
rfm22b_dev->ppm_packet.channels[i] = channels[i];
}
// Send the PPM packet.
rfm22b_dev->ppm_packet.header.destination_id = rfm22b_dev->destination_id;
rfm22b_dev->ppm_packet.header.type = PACKET_TYPE_PPM;
rfm22b_dev->ppm_packet.header.data_size = PH_PPM_DATA_SIZE(&(rfm22b_dev->ppm_packet));
rfm22b_dev->send_ppm = true;
#endif
} }
/** /**
@ -849,7 +887,7 @@ static void PIOS_RFM22B_Task(void *parameters)
{ {
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)parameters; struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)parameters;
if (!PIOS_RFM22B_validate(rfm22b_dev)) if (!PIOS_RFM22B_validate(rfm22b_dev))
return; return;
portTickType lastEventTicks = xTaskGetTickCount(); portTickType lastEventTicks = xTaskGetTickCount();
portTickType lastStatusTicks = lastEventTicks; portTickType lastStatusTicks = lastEventTicks;
portTickType lastPPMTicks = lastEventTicks; portTickType lastPPMTicks = lastEventTicks;
@ -892,17 +930,21 @@ static void PIOS_RFM22B_Task(void *parameters)
} }
} }
// Change channels if necessary.
if ((rfm22b_dev->state == RFM22B_STATE_RX_MODE) || (rfm22b_dev->state == RFM22B_STATE_WAIT_PREAMBLE)) {
rfm22_changeChannel(rfm22b_dev);
}
portTickType curTicks = xTaskGetTickCount(); portTickType curTicks = xTaskGetTickCount();
uint32_t last_rec_ms = (rfm22b_dev->rx_complete_ticks == 0) ? 0 : timeDifferenceMs(rfm22b_dev->rx_complete_ticks, curTicks);
// Have we been sending this packet too long? // Have we been sending this packet too long?
if ((rfm22b_dev->packet_start_ticks > 0) && (timeDifferenceMs(rfm22b_dev->packet_start_ticks, curTicks) > (rfm22b_dev->max_packet_time * 3))) if ((rfm22b_dev->packet_start_ticks > 0) && (timeDifferenceMs(rfm22b_dev->packet_start_ticks, curTicks) > (rfm22b_dev->max_packet_time * 3))) {
rfm22_process_event(rfm22b_dev, RFM22B_EVENT_TIMEOUT); rfm22_process_event(rfm22b_dev, RFM22B_EVENT_TIMEOUT);
// Have it been too long since we received a packet // Has it been too long since we received a packet
else if ((rfm22b_dev->rx_complete_ticks > 0) && (timeDifferenceMs(rfm22b_dev->rx_complete_ticks, curTicks) > DISCONNECT_TIMEOUT_MS)) } else if (last_rec_ms > DISCONNECT_TIMEOUT_MS) {
rfm22_process_event(rfm22b_dev, RFM22B_EVENT_ERROR); rfm22_process_event(rfm22b_dev, RFM22B_EVENT_ERROR);
} else {
else
{
// Are we waiting for an ACK? // Are we waiting for an ACK?
if (rfm22b_dev->prev_tx_packet) if (rfm22b_dev->prev_tx_packet)
@ -926,7 +968,7 @@ static void PIOS_RFM22B_Task(void *parameters)
} }
// Queue up a status packet if it's time. // Queue up a status packet if it's time.
if (timeDifferenceMs(lastStatusTicks, curTicks) > RADIOSTATS_UPDATE_PERIOD_MS) if ((timeDifferenceMs(lastStatusTicks, curTicks) > RADIOSTATS_UPDATE_PERIOD_MS) || (last_rec_ms > rfm22b_dev->max_packet_time * 4))
{ {
rfm22_sendStatus(rfm22b_dev); rfm22_sendStatus(rfm22b_dev);
lastStatusTicks = curTicks; lastStatusTicks = curTicks;
@ -937,11 +979,17 @@ static void PIOS_RFM22B_Task(void *parameters)
// Send a packet if it's our time slice // Send a packet if it's our time slice
rfm22b_dev->time_to_send = (((curTicks - rfm22b_dev->time_to_send_offset) & 0x6) == 0); rfm22b_dev->time_to_send = (((curTicks - rfm22b_dev->time_to_send_offset) & 0x6) == 0);
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM #if defined(PIOS_RFM22B_DEBUG_ON_TELEM) || defined(PIOS_RFM22B_DEBUG_ON_RCVR)
if (rfm22b_dev->time_to_send) if (rfm22b_dev->time_to_send) {
D4_LED_ON; D4_LED_ON;
else } else {
D4_LED_OFF; D4_LED_OFF;
}
if (rfm22_inChannelBuffer(rfm22b_dev)) {
D3_LED_ON;
} else {
D3_LED_OFF;
}
#endif #endif
if (rfm22b_dev->time_to_send) if (rfm22b_dev->time_to_send)
rfm22_process_event(rfm22b_dev, RFM22B_EVENT_TX_START); rfm22_process_event(rfm22b_dev, RFM22B_EVENT_TX_START);
@ -965,11 +1013,11 @@ static void rfm22_setDatarate(struct pios_rfm22b_dev * rfm22b_dev, enum rfm22b_d
{ {
uint32_t datarate_bps = data_rate[datarate]; uint32_t datarate_bps = data_rate[datarate];
rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(datarate_bps) + 0.5); rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(datarate_bps) + 0.5);
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED) if (rfm22_isConnected(rfm22b_dev))
{ {
// Generate a pseudo-random number from 0-8 to add to the delay // Generate a pseudo-random number from 0-8 to add to the delay
uint8_t random = PIOS_CRC_updateByte(0, (uint8_t)(xTaskGetTickCount() & 0xff)) & 0x03; uint8_t random = PIOS_CRC_updateByte(0, (uint8_t)(xTaskGetTickCount() & 0xff)) & 0x03;
rfm22b_dev->max_ack_delay = (uint16_t)((float)(sizeof(PHPacketHeader) * 8 * 1000) / (float)(datarate_bps) + 0.5) * 4 + random; rfm22b_dev->max_ack_delay = (uint16_t)((float)((sizeof(PHAckNackPacket) * 8 + TX_PREAMBLE_NIBBLES * 4) * 1000) / (float)(datarate_bps) + 0.5) * 4 + 4 + random;
} }
else else
rfm22b_dev->max_ack_delay = CONNECT_ATTEMPT_PERIOD_MS; rfm22b_dev->max_ack_delay = CONNECT_ATTEMPT_PERIOD_MS;
@ -996,6 +1044,8 @@ static void rfm22_setDatarate(struct pios_rfm22b_dev * rfm22b_dev, enum rfm22b_d
rfm22_write(rfm22b_dev, 0x24, reg_24[datarate]); rfm22_write(rfm22b_dev, 0x24, reg_24[datarate]);
// rfm22_clk_recovery_timing_loop_gain0 // rfm22_clk_recovery_timing_loop_gain0
rfm22_write(rfm22b_dev, 0x25, reg_25[datarate]); rfm22_write(rfm22b_dev, 0x25, reg_25[datarate]);
// rfm22_agc_override1
rfm22_write(rfm22b_dev, RFM22_agc_override1, reg_69[datarate]);
// rfm22_afc_limiter // rfm22_afc_limiter
rfm22_write(rfm22b_dev, 0x2A, reg_2A[datarate]); rfm22_write(rfm22b_dev, 0x2A, reg_2A[datarate]);
@ -1018,21 +1068,13 @@ static void rfm22_setDatarate(struct pios_rfm22b_dev * rfm22b_dev, enum rfm22b_d
// rfm22_frequency_deviation // rfm22_frequency_deviation
rfm22_write(rfm22b_dev, 0x72, reg_72[datarate]); rfm22_write(rfm22b_dev, 0x72, reg_72[datarate]);
// rfm22_cpcuu
rfm22_write(rfm22b_dev, 0x58, reg_58[datarate]);
rfm22_write(rfm22b_dev, RFM22_ook_counter_value1, 0x00); rfm22_write(rfm22b_dev, RFM22_ook_counter_value1, 0x00);
rfm22_write(rfm22b_dev, RFM22_ook_counter_value2, 0x00); rfm22_write(rfm22b_dev, RFM22_ook_counter_value2, 0x00);
} }
void PIOS_RFM22B_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening)
{
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if(!PIOS_RFM22B_validate(rfm22b_dev))
return;
rfm22b_dev->datarate = datarate;
// Re-initialize the radio device.
PIOS_RFM22B_InjectEvent(rfm22b_dev, RFM22B_EVENT_INITIALIZE, false);
}
// ************************************ // ************************************
// SPI read/write // SPI read/write
@ -1085,13 +1127,13 @@ static void rfm22_write(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr, uint8_
* toggle the NSS line * toggle the NSS line
* @param[in] addr The address of the RFM22b register to write * @param[in] addr The address of the RFM22b register to write
* @param[in] data The data to write to that register * @param[in] data The data to write to that register
static void rfm22_write_noclaim(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr, uint8_t data) static void rfm22_write_noclaim(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr, uint8_t data)
{ {
uint8_t buf[2] = {addr | 0x80, data}; uint8_t buf[2] = {addr | 0x80, data};
rfm22_assertCs(rfm22b_dev); rfm22_assertCs(rfm22b_dev);
PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, buf, NULL, sizeof(buf), NULL); PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, buf, NULL, sizeof(buf), NULL);
rfm22_deassertCs(rfm22b_dev); rfm22_deassertCs(rfm22b_dev);
} }
*/ */
/** /**
@ -1169,61 +1211,61 @@ static void rfm22_process_event(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rf
// ************************************ // ************************************
static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint32_t frequency_hz) static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint32_t min_frequency, uint32_t max_frequency, uint32_t step_size)
{ {
if (frequency_hz < rfm22b_dev->min_frequency) uint32_t frequency_hz = min_frequency;
frequency_hz = rfm22b_dev->min_frequency;
else if (frequency_hz > rfm22b_dev->max_frequency)
frequency_hz = rfm22b_dev->max_frequency;
// holds the hbsel (1 or 2) // holds the hbsel (1 or 2)
uint8_t hbsel; uint8_t hbsel;
if (frequency_hz < 480000000) if (frequency_hz < 480000000)
hbsel = 1; hbsel = 0;
else else
hbsel = 2; hbsel = 1;
uint8_t fb = (uint8_t)(frequency_hz / (10000000 * hbsel)); float freq_mhz = (float)(frequency_hz) / 1000000.0;
float xtal_freq_khz = 30000;
float sfreq = freq_mhz / (10.0 * (xtal_freq_khz / 30000.0) * (1 + hbsel));
uint32_t fb = (uint32_t)sfreq - 24 + (64 + 32 * hbsel);
uint32_t fc = (uint32_t)((sfreq - (uint32_t)sfreq) * 64000.0);
uint8_t fch = (fc >> 8) & 0xff;
uint8_t fcl = fc & 0xff;
uint32_t fc = (uint32_t)(frequency_hz - (10000000 * hbsel * fb)); // Calculate the number of frequency hopping channels.
rfm22b_dev->num_channels = (step_size == 0) ? 1 : (uint16_t)((max_frequency - min_frequency) / step_size);
fc = (fc * 64u) / (10000ul * hbsel); // initialize the frequency hopping step size (specified in 10khz increments).
fb -= 24; uint32_t freq_hop_step_size = step_size / 10000;
if (freq_hop_step_size > 255) {
if (hbsel > 1) freq_hop_step_size = 255;
fb |= RFM22_fbs_hbsel; }
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_step_size, (uint8_t)freq_hop_step_size);
fb |= RFM22_fbs_sbse; // is this the RX LO polarity?
// frequency hopping channel (0-255) // frequency hopping channel (0-255)
rfm22b_dev->frequency_step_size = 156.25f * hbsel; rfm22b_dev->frequency_step_size = 156.25f * hbsel;
// frequency hopping channel (0-255) // frequency hopping channel (0-255)
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_channel_select, rfm22b_dev->frequency_hop_channel); rfm22b_dev->frequency_hop_channel = 0;
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_channel_select, 0);
// no frequency offset // no frequency offset
rfm22_write(rfm22b_dev, RFM22_frequency_offset1, 0); rfm22_write(rfm22b_dev, RFM22_frequency_offset1, 0);
// no frequency offset
rfm22_write(rfm22b_dev, RFM22_frequency_offset2, 0); rfm22_write(rfm22b_dev, RFM22_frequency_offset2, 0);
// set the carrier frequency // set the carrier frequency
rfm22_write(rfm22b_dev, RFM22_frequency_band_select, fb); rfm22_write(rfm22b_dev, RFM22_frequency_band_select, fb & 0xff);
rfm22_write(rfm22b_dev, RFM22_nominal_carrier_frequency1, fc >> 8); rfm22_write(rfm22b_dev, RFM22_nominal_carrier_frequency1, fch);
rfm22_write(rfm22b_dev, RFM22_nominal_carrier_frequency0, fc & 0xff); rfm22_write(rfm22b_dev, RFM22_nominal_carrier_frequency0, fcl);
} }
/* static bool rfm22_setFreqHopChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t channel)
static void rfm22_setFreqHopChannel(uint8_t channel) {
{ // set the frequency hopping channel // set the frequency hopping channel
g_rfm22b_dev->frequency_hop_channel = channel; if (rfm22b_dev->frequency_hop_channel == channel)
return false;
rfm22b_dev->frequency_hop_channel = channel;
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_channel_select, channel); rfm22_write(rfm22b_dev, RFM22_frequency_hopping_channel_select, channel);
return true;
} }
static uint32_t rfm22_freqHopSize(void)
{ // return the frequency hopping step size
return ((uint32_t)g_rfm22b_dev->frequency_hop_step_size_reg * 10000);
}
*/
static void rfm22_calculateLinkQuality(struct pios_rfm22b_dev *rfm22b_dev) static void rfm22_calculateLinkQuality(struct pios_rfm22b_dev *rfm22b_dev)
{ {
// Add the RX packet statistics // Add the RX packet statistics
@ -1267,13 +1309,11 @@ static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev
{ {
// Are we already in Rx mode? // Are we already in Rx mode?
if (rfm22b_dev->in_rx_mode) if (rfm22b_dev->in_rx_mode)
return RFM22B_EVENT_NUM_EVENTS; return RFM22B_EVENT_NUM_EVENTS;
rfm22b_dev->packet_start_ticks = 0; rfm22b_dev->packet_start_ticks = 0;
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM #if defined(PIOS_RFM22B_DEBUG_ON_TELEM) || defined(PIOS_RFM22B_DEBUG_ON_RCVR)
D2_LED_ON; D2_LED_ON;
D3_LED_TOGGLE; #endif // PIOS_RFM22B_DEBUG_ON_TELEM
#endif
// disable interrupts // disable interrupts
rfm22_write(rfm22b_dev, RFM22_interrupt_enable1, 0x00); rfm22_write(rfm22b_dev, RFM22_interrupt_enable1, 0x00);
@ -1319,6 +1359,10 @@ static bool rfm22_ready_to_send(struct pios_rfm22b_dev *rfm22b_dev)
if (rfm22b_dev->prev_tx_packet || rfm22b_dev->send_ppm || rfm22b_dev->send_status) if (rfm22b_dev->prev_tx_packet || rfm22b_dev->send_ppm || rfm22b_dev->send_status)
return true; return true;
// Are we not connected yet?
if (!rfm22_isConnected(rfm22b_dev))
return true;
// Is there some data ready to sent? // Is there some data ready to sent?
PHPacketHandle dp = &rfm22b_dev->data_packet; PHPacketHandle dp = &rfm22b_dev->data_packet;
if (dp->header.data_size > 0) if (dp->header.data_size > 0)
@ -1332,49 +1376,51 @@ static bool rfm22_ready_to_send(struct pios_rfm22b_dev *rfm22b_dev)
return false; return false;
} }
static bool rfm22_isConnected(struct pios_rfm22b_dev *rfm22b_dev)
{
return (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED);
}
static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev)
{ {
PHPacketHandle p = NULL; PHPacketHandle p = NULL;
// Don't send if it's not our turn. // Don't send if it's not our turn.
if (!rfm22b_dev->time_to_send) if (!rfm22b_dev->time_to_send || (rfm22_inChannelBuffer(rfm22b_dev) && rfm22_isConnected(rfm22b_dev)))
return RFM22B_EVENT_RX_MODE; return RFM22B_EVENT_RX_MODE;
// See if there's a packet ready to send. // See if there's a packet ready to send.
if (rfm22b_dev->tx_packet) if (rfm22b_dev->tx_packet)
p = rfm22b_dev->tx_packet; p = rfm22b_dev->tx_packet;
// Are we waiting for an ACK? else {
else
{
// Don't send a packet if we're waiting for an ACK // Don't send a packet if we're waiting for an ACK
if (rfm22b_dev->prev_tx_packet) if (rfm22b_dev->prev_tx_packet)
return RFM22B_EVENT_RX_MODE; return RFM22B_EVENT_RX_MODE;
if (!p && rfm22b_dev->send_connection_request) // Send a connection request?
{ if (!p && rfm22b_dev->send_connection_request) {
p = (PHPacketHandle)&(rfm22b_dev->con_packet); p = (PHPacketHandle)&(rfm22b_dev->con_packet);
rfm22b_dev->send_connection_request = false; rfm22b_dev->send_connection_request = false;
} }
#ifdef PIOS_PPM_RECEIVER #ifdef PIOS_PPM_RECEIVER
if (!p && rfm22b_dev->send_ppm) // Send a PPM packet?
{ if (!p && rfm22b_dev->send_ppm) {
p = (PHPacketHandle)&(rfm22b_dev->ppm_packet); p = (PHPacketHandle)&(rfm22b_dev->ppm_packet);
rfm22b_dev->send_ppm = false; rfm22b_dev->send_ppm = false;
} }
#endif #endif
if (!p && rfm22b_dev->send_status) // Send status?
{ if (!p && rfm22b_dev->send_status) {
p = (PHPacketHandle)&(rfm22b_dev->status_packet); p = (PHPacketHandle)&(rfm22b_dev->status_packet);
rfm22b_dev->send_status = false; rfm22b_dev->send_status = false;
} }
if (!p) // Try to get some data to send
{ if (!p) {
// Try to get some data to send
bool need_yield = false; bool need_yield = false;
p = &rfm22b_dev->data_packet; p = &rfm22b_dev->data_packet;
p->header.type = PACKET_TYPE_DATA; p->header.type = PACKET_TYPE_DATA;
@ -1383,7 +1429,7 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev)
p->header.data_size = (rfm22b_dev->tx_out_cb)(rfm22b_dev->tx_out_context, p->data, PH_MAX_DATA, NULL, &need_yield); p->header.data_size = (rfm22b_dev->tx_out_cb)(rfm22b_dev->tx_out_context, p->data, PH_MAX_DATA, NULL, &need_yield);
// Don't send any data until we're connected. // Don't send any data until we're connected.
if (rfm22b_dev->stats.link_state != OPLINKSTATUS_LINKSTATE_CONNECTED) if (!rfm22_isConnected(rfm22b_dev))
p->header.data_size = 0; p->header.data_size = 0;
if (p->header.data_size == 0) if (p->header.data_size == 0)
p = NULL; p = NULL;
@ -1398,14 +1444,17 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev)
// We're transitioning out of Rx mode. // We're transitioning out of Rx mode.
rfm22b_dev->in_rx_mode = false; rfm22b_dev->in_rx_mode = false;
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM #if defined(PIOS_RFM22B_DEBUG_ON_TELEM) || defined(PIOS_RFM22B_DEBUG_ON_RCVR)
D1_LED_ON; D1_LED_ON;
D2_LED_OFF; D2_LED_OFF;
D3_LED_TOGGLE;
#endif #endif
// Change the channel if necessary.
if (((p->header.type != PACKET_TYPE_ACK) && (p->header.type != PACKET_TYPE_ACK_RTS)) ||
(rfm22b_dev->rx_packet.header.type != PACKET_TYPE_CON_REQUEST))
rfm22_changeChannel(rfm22b_dev);
// Add the error correcting code. // Add the error correcting code.
p->header.source_id = rfm22b_dev->deviceID;
encode_data((unsigned char*)p, PHPacketSize(p), (unsigned char*)p); encode_data((unsigned char*)p, PHPacketSize(p), (unsigned char*)p);
rfm22b_dev->tx_packet = p; rfm22b_dev->tx_packet = p;
@ -1438,10 +1487,6 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev)
rfm22_write(rfm22b_dev, RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | rfm22_write(rfm22b_dev, RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo |
RFM22_mmc2_modtyp_gfsk); RFM22_mmc2_modtyp_gfsk);
// set the tx power
rfm22_write(rfm22b_dev, RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 |
RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | rfm22b_dev->tx_power);
// clear FIFOs // clear FIFOs
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, 0x00); rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, 0x00);
@ -1476,20 +1521,23 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev)
static void rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev) static void rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev)
{ {
// Only send status if we're connected // The coordinator doesn't send status.
if (rfm22b_dev->stats.link_state != OPLINKSTATUS_LINKSTATE_CONNECTED) if (rfm22b_dev->coordinator)
return; return;
// Update the link quality metric. // Update the link quality metric.
rfm22_calculateLinkQuality(rfm22b_dev); rfm22_calculateLinkQuality(rfm22b_dev);
// Queue the status message // Queue the status message
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED) if (rfm22_isConnected(rfm22b_dev))
rfm22b_dev->status_packet.header.destination_id = rfm22b_dev->destination_id; rfm22b_dev->status_packet.header.destination_id = rfm22b_dev->destination_id;
else if (rfm22b_dev->coordinator)
return;
else else
rfm22b_dev->status_packet.header.destination_id = 0xffffffff; // Broadcast rfm22b_dev->status_packet.header.destination_id = 0xffffffff; // Broadcast
rfm22b_dev->status_packet.header.type = PACKET_TYPE_STATUS; rfm22b_dev->status_packet.header.type = PACKET_TYPE_STATUS;
rfm22b_dev->status_packet.header.data_size = PH_STATUS_DATA_SIZE(&(rfm22b_dev->status_packet)); rfm22b_dev->status_packet.header.data_size = PH_STATUS_DATA_SIZE(&(rfm22b_dev->status_packet));
rfm22b_dev->status_packet.source_id = rfm22b_dev->deviceID;
rfm22b_dev->status_packet.link_quality = rfm22b_dev->stats.link_quality; rfm22b_dev->status_packet.link_quality = rfm22b_dev->stats.link_quality;
rfm22b_dev->status_packet.received_rssi = rfm22b_dev->rssi_dBm; rfm22b_dev->status_packet.received_rssi = rfm22b_dev->rssi_dBm;
rfm22b_dev->send_status = true; rfm22b_dev->send_status = true;
@ -1501,12 +1549,14 @@ static void rfm22_sendPPM(struct pios_rfm22b_dev *rfm22b_dev)
{ {
#ifdef PIOS_PPM_RECEIVER #ifdef PIOS_PPM_RECEIVER
// Only send PPM if we're connected // Only send PPM if we're connected
if (rfm22b_dev->stats.link_state != OPLINKSTATUS_LINKSTATE_CONNECTED) if (!rfm22_isConnected(rfm22b_dev)) {
return; return;
}
// Just return if the PPM receiver is not configured. // Just return if the PPM receiver is not configured.
if (PIOS_PPM_RECEIVER == 0) if (PIOS_PPM_RECEIVER == 0) {
return; return;
}
// See if we have any valid channels. // See if we have any valid channels.
bool valid_input_detected = false; bool valid_input_detected = false;
@ -1589,10 +1639,6 @@ static enum pios_rfm22b_event rfm22_detectPreamble(struct pios_rfm22b_dev *rfm22
if (rfm22b_dev->packet_start_ticks == 0) if (rfm22b_dev->packet_start_ticks == 0)
rfm22b_dev->packet_start_ticks = 1; rfm22b_dev->packet_start_ticks = 1;
RX_LED_ON; RX_LED_ON;
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
D3_LED_TOGGLE;
#endif
return RFM22B_EVENT_PREAMBLE_DETECTED; return RFM22B_EVENT_PREAMBLE_DETECTED;
} }
@ -1653,8 +1699,7 @@ static bool rfm22_receivePacket(struct pios_rfm22b_dev *rfm22b_dev, PHPacketHand
if (!ack_nack_packet && (good_packet || corrected_packet)) if (!ack_nack_packet && (good_packet || corrected_packet))
{ {
uint16_t seq_num = p->header.seq_num; uint16_t seq_num = p->header.seq_num;
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED) if (rfm22_isConnected(rfm22b_dev)) {
{
static bool first_time = true; static bool first_time = true;
uint16_t missed_packets = 0; uint16_t missed_packets = 0;
if (first_time) if (first_time)
@ -1771,6 +1816,16 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev)
bool rx_need_yield; bool rx_need_yield;
if (rfm22b_dev->rx_in_cb) if (rfm22b_dev->rx_in_cb)
(rfm22b_dev->rx_in_cb)(rfm22b_dev->rx_in_context, rfm22b_dev->rx_packet.data, rfm22b_dev->rx_packet.header.data_size, NULL, &rx_need_yield); (rfm22b_dev->rx_in_cb)(rfm22b_dev->rx_in_context, rfm22b_dev->rx_packet.data, rfm22b_dev->rx_packet.header.data_size, NULL, &rx_need_yield);
#ifdef RFM22B_TEST_DROPPED_PACKETS
// Inject radnom missed ACKs
{
static uint8_t crc = 0;
static uint8_t cntr = 0;
crc = PIOS_CRC_updateByte(crc, cntr++);
if ((crc & 0x7) == 0)
ret_event = RFM22B_EVENT_RX_MODE;
}
#endif
break; break;
} }
case PACKET_TYPE_DUPLICATE_DATA: case PACKET_TYPE_DUPLICATE_DATA:
@ -1784,20 +1839,41 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev)
break; break;
case PACKET_TYPE_PPM: case PACKET_TYPE_PPM:
{ {
#if defined(PIOS_INCLUDE_GCSRCVR) || (defined(PIOS_INCLUDE_PPM_OUT) && defined(PIOS_PPM_OUTPUT)) || defined(PIOS_INCLUDE_RFM22B_RCVR)
PHPpmPacketHandle ppmp = (PHPpmPacketHandle)&(rfm22b_dev->rx_packet); PHPpmPacketHandle ppmp = (PHPpmPacketHandle)&(rfm22b_dev->rx_packet);
#if defined(PIOS_INCLUDE_GCSRCVR) || (defined(PIOS_INCLUDE_PPM_OUT) && defined(PIOS_PPM_OUTPUT))
bool ppm_output = false;
#endif
#endif
#if defined(PIOS_INCLUDE_RFM22B_RCVR)
ppm_output = true;
for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) { for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) {
rfm22b_dev->ppm_channel[i] = ppmp->channels[i]; rfm22b_dev->ppm_channel[i] = ppmp->channels[i];
#if defined(PIOS_INCLUDE_PPM_OUT) && defined(PIOS_PPM_OUTPUT)
if (PIOS_PPM_OUTPUT)
PIOS_PPM_OUT_Set(PIOS_PPM_OUTPUT, i, ppmp->channels[i]);
#endif /* PIOS_INCLUDE_PPM_OUT && PIOS_PPM_OUTPUT */
} }
rfm22b_dev->ppm_fresh = true; #endif
#if defined(PIOS_INCLUDE_PPM_OUT) && defined(PIOS_PPM_OUTPUT)
if (PIOS_PPM_OUTPUT) {
ppm_output = true;
for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) {
PIOS_PPM_OUT_Set(PIOS_PPM_OUTPUT, i, ppmp->channels[i]);
}
}
#endif
#if defined(PIOS_INCLUDE_GCSRCVR)
if (!ppm_output) {
GCSReceiverData gcsRcvr;
for (uint8_t i = 0; (i < PIOS_RFM22B_RCVR_MAX_CHANNELS) && (i < GCSRECEIVER_CHANNEL_NUMELEM); ++i) {
gcsRcvr.Channel[i] = ppmp->channels[i];
}
GCSReceiverSet(&gcsRcvr);
}
#endif
break; break;
} }
default: default:
break; break;
} }
} }
else else
ret_event = RFM22B_EVENT_RX_ERROR; ret_event = RFM22B_EVENT_RX_ERROR;
@ -1805,9 +1881,8 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev)
rfm22b_dev->rx_complete_ticks = xTaskGetTickCount(); rfm22b_dev->rx_complete_ticks = xTaskGetTickCount();
if (rfm22b_dev->rx_complete_ticks == 0) if (rfm22b_dev->rx_complete_ticks == 0)
rfm22b_dev->rx_complete_ticks = 1; rfm22b_dev->rx_complete_ticks = 1;
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM #if defined(PIOS_RFM22B_DEBUG_ON_TELEM) || defined(PIOS_RFM22B_DEBUG_ON_RCVR)
D2_LED_OFF; D2_LED_OFF;
D3_LED_TOGGLE;
#endif #endif
} }
@ -1841,10 +1916,6 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev)
if (!rfm22_readStatus(rfm22b_dev)) if (!rfm22_readStatus(rfm22b_dev))
return RFM22B_EVENT_FAILURE; return RFM22B_EVENT_FAILURE;
// FIFO under/over flow error.
//if (rfm22b_dev->int_status1 & RFM22_is1_ifferr)
//return RFM22B_EVENT_FAILURE;
// TX FIFO almost empty, it needs filling up // TX FIFO almost empty, it needs filling up
if (rfm22b_dev->int_status1 & RFM22_is1_ixtffaem) if (rfm22b_dev->int_status1 & RFM22_is1_ixtffaem)
{ {
@ -1865,28 +1936,47 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev)
// Packet has been sent // Packet has been sent
else if (rfm22b_dev->int_status1 & RFM22_is1_ipksent) else if (rfm22b_dev->int_status1 & RFM22_is1_ipksent)
{ {
portTickType curTicks = xTaskGetTickCount();
rfm22b_dev->stats.tx_byte_count += PH_PACKET_SIZE(rfm22b_dev->tx_packet); rfm22b_dev->stats.tx_byte_count += PH_PACKET_SIZE(rfm22b_dev->tx_packet);
// Is this an ACK? // Is this an ACK?
bool is_ack = ((rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK) || (rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK_RTS)); bool is_ack = ((rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK) || (rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK_RTS));
//ret_event = is_ack ? RFM22B_EVENT_TX_START : RFM22B_EVENT_RX_MODE;
ret_event = RFM22B_EVENT_RX_MODE; ret_event = RFM22B_EVENT_RX_MODE;
if (is_ack) if (is_ack) {
{
// If this is an ACK for a connection request message we need to // If this is an ACK for a connection request message we need to
// configure this modem from the connection request message. // configure this modem from the connection request message.
if (rfm22b_dev->rx_packet.header.type == PACKET_TYPE_CON_REQUEST) if (rfm22b_dev->rx_packet.header.type == PACKET_TYPE_CON_REQUEST) {
rfm22_setConnectionParameters(rfm22b_dev); rfm22_setConnectionParameters(rfm22b_dev);
} } else if (rfm22b_dev->coordinator && !rfm22_isConnected(rfm22b_dev) && (rfm22b_dev->rx_packet.header.type == PACKET_TYPE_STATUS)) {
else if (rfm22b_dev->tx_packet->header.type != PACKET_TYPE_NACK)
{ // Send a connection request message if we're not connected, and this is a status message from a modem that we're bound to.
PHStatusPacketHandle status = (PHStatusPacketHandle)&(rfm22b_dev->rx_packet);
uint32_t source_id = status->source_id;
for (uint8_t i = 0; OPLINKSETTINGS_BINDINGS_NUMELEM; ++i) {
if (rfm22b_dev->bindings[i].pairID == source_id) {
rfm22b_dev->cur_binding = i;
ret_event = RFM22B_EVENT_REQUEST_CONNECTION;
break;
}
}
}
// Change the channel
// On the remote side, we initialize the time delta when we finish sending the ACK for the connection request message.
if (rfm22b_dev->rx_packet.header.type == PACKET_TYPE_CON_REQUEST) {
rfm22b_dev->time_delta = portMAX_DELAY - curTicks;
}
} else if (rfm22b_dev->tx_packet->header.type != PACKET_TYPE_NACK) {
// We need to wait for an ACK if this packet it not an ACK or NACK. // We need to wait for an ACK if this packet it not an ACK or NACK.
rfm22b_dev->prev_tx_packet = rfm22b_dev->tx_packet; rfm22b_dev->prev_tx_packet = rfm22b_dev->tx_packet;
rfm22b_dev->tx_complete_ticks = xTaskGetTickCount(); rfm22b_dev->tx_complete_ticks = xTaskGetTickCount();
} }
// Set the Tx period // Set the Tx period
portTickType curTicks = xTaskGetTickCount();
if (rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK) if (rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK)
rfm22b_dev->time_to_send_offset = curTicks + 0x4; rfm22b_dev->time_to_send_offset = curTicks + 0x4;
else if (rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK_RTS) else if (rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK_RTS)
@ -1896,9 +1986,8 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev)
// Start a new transaction // Start a new transaction
rfm22b_dev->packet_start_ticks = 0; rfm22b_dev->packet_start_ticks = 0;
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM #if defined(PIOS_RFM22B_DEBUG_ON_TELEM) || defined(PIOS_RFM22B_DEBUG_ON_RCVR)
D1_LED_OFF; D1_LED_OFF;
D3_LED_TOGGLE;
#endif #endif
} }
@ -1919,10 +2008,11 @@ static enum pios_rfm22b_event rfm22_txFailure(struct pios_rfm22b_dev *rfm22b_dev
static enum pios_rfm22b_event rfm22_sendAck(struct pios_rfm22b_dev *rfm22b_dev) static enum pios_rfm22b_event rfm22_sendAck(struct pios_rfm22b_dev *rfm22b_dev)
{ {
PHAckNackPacketHandle aph = (PHAckNackPacketHandle)(&(rfm22b_dev->ack_nack_packet)); PHAckNackPacketHandle aph = (PHAckNackPacketHandle)(&(rfm22b_dev->ack_nack_packet));
aph->header.destination_id = rfm22b_dev->rx_packet.header.source_id; aph->header.destination_id = rfm22b_dev->destination_id;
aph->header.type = rfm22_ready_to_send(rfm22b_dev) ? PACKET_TYPE_ACK_RTS : PACKET_TYPE_ACK; aph->header.type = rfm22_ready_to_send(rfm22b_dev) ? PACKET_TYPE_ACK_RTS : PACKET_TYPE_ACK;
aph->header.data_size = PH_ACK_NACK_DATA_SIZE(aph); aph->header.data_size = PH_ACK_NACK_DATA_SIZE(aph);
aph->header.seq_num = rfm22b_dev->rx_packet.header.seq_num; aph->header.seq_num = rfm22b_dev->rx_packet.header.seq_num;
aph->packet_recv_time = rfm22_coordinatorTime(rfm22b_dev, rfm22b_dev->rx_complete_ticks);
rfm22b_dev->tx_packet = (PHPacketHandle)aph; rfm22b_dev->tx_packet = (PHPacketHandle)aph;
rfm22b_dev->time_to_send = true; rfm22b_dev->time_to_send = true;
return RFM22B_EVENT_TX_START; return RFM22B_EVENT_TX_START;
@ -1935,7 +2025,7 @@ static enum pios_rfm22b_event rfm22_sendAck(struct pios_rfm22b_dev *rfm22b_dev)
static enum pios_rfm22b_event rfm22_sendNack(struct pios_rfm22b_dev *rfm22b_dev) static enum pios_rfm22b_event rfm22_sendNack(struct pios_rfm22b_dev *rfm22b_dev)
{ {
PHAckNackPacketHandle aph = (PHAckNackPacketHandle)(&(rfm22b_dev->ack_nack_packet)); PHAckNackPacketHandle aph = (PHAckNackPacketHandle)(&(rfm22b_dev->ack_nack_packet));
aph->header.destination_id = rfm22b_dev->rx_packet.header.source_id; aph->header.destination_id = rfm22b_dev->destination_id;
aph->header.type = PACKET_TYPE_NACK; aph->header.type = PACKET_TYPE_NACK;
aph->header.data_size = PH_ACK_NACK_DATA_SIZE(aph); aph->header.data_size = PH_ACK_NACK_DATA_SIZE(aph);
aph->header.seq_num = rfm22b_dev->rx_packet.header.seq_num; aph->header.seq_num = rfm22b_dev->rx_packet.header.seq_num;
@ -1957,8 +2047,7 @@ static enum pios_rfm22b_event rfm22_receiveAck(struct pios_rfm22b_dev *rfm22b_de
rfm22b_dev->prev_tx_packet = NULL; rfm22b_dev->prev_tx_packet = NULL;
// Was this a connection request? // Was this a connection request?
switch (prev->header.type) switch (prev->header.type) {
{
case PACKET_TYPE_CON_REQUEST: case PACKET_TYPE_CON_REQUEST:
rfm22_setConnectionParameters(rfm22b_dev); rfm22_setConnectionParameters(rfm22b_dev);
break; break;
@ -1967,15 +2056,27 @@ static enum pios_rfm22b_event rfm22_receiveAck(struct pios_rfm22b_dev *rfm22b_de
break; break;
} }
// On the coordinator side, we initialize the time delta when we receive the ACK for the connection request message.
if (prev->header.type == PACKET_TYPE_CON_REQUEST) {
rfm22b_dev->time_delta = portMAX_DELAY - rfm22b_dev->rx_complete_ticks;
} else if (!rfm22b_dev->coordinator) {
PHAckNackPacketHandle aph = (PHAckNackPacketHandle)(&(rfm22b_dev->rx_packet));
portTickType local_tx_time = rfm22_coordinatorTime(rfm22b_dev, rfm22b_dev->tx_complete_ticks);
portTickType remote_rx_time = aph->packet_recv_time;
// Adjust the time delta based on the difference between our estimated time offset and the coordinator offset.
// This is not working yet
rfm22b_dev->time_delta += remote_rx_time - local_tx_time;
}
// Reset the resend count
rfm22b_dev->cur_resent_count = 0;
// Should we try to start another TX? // Should we try to start another TX?
if (rfm22b_dev->rx_packet.header.type == PACKET_TYPE_ACK) if (rfm22b_dev->rx_packet.header.type == PACKET_TYPE_ACK) {
{
rfm22b_dev->time_to_send_offset = curTicks; rfm22b_dev->time_to_send_offset = curTicks;
rfm22b_dev->time_to_send = true; rfm22b_dev->time_to_send = true;
return RFM22B_EVENT_TX_START; return RFM22B_EVENT_TX_START;
} } else {
else
{
rfm22b_dev->time_to_send_offset = curTicks + 0x4; rfm22b_dev->time_to_send_offset = curTicks + 0x4;
return RFM22B_EVENT_RX_MODE; return RFM22B_EVENT_RX_MODE;
} }
@ -1987,11 +2088,15 @@ static enum pios_rfm22b_event rfm22_receiveAck(struct pios_rfm22b_dev *rfm22b_de
*/ */
static enum pios_rfm22b_event rfm22_receiveNack(struct pios_rfm22b_dev *rfm22b_dev) static enum pios_rfm22b_event rfm22_receiveNack(struct pios_rfm22b_dev *rfm22b_dev)
{ {
// Resend the previous TX packet. // Resend the previous TX packet.
rfm22b_dev->tx_packet = rfm22b_dev->prev_tx_packet; rfm22b_dev->tx_packet = rfm22b_dev->prev_tx_packet;
rfm22b_dev->prev_tx_packet = NULL; rfm22b_dev->prev_tx_packet = NULL;
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED)
// Increment the reset packet counter if we're connected.
if (rfm22_isConnected(rfm22b_dev)) {
rfm22b_add_rx_status(rfm22b_dev, RFM22B_RESENT_TX_PACKET); rfm22b_add_rx_status(rfm22b_dev, RFM22B_RESENT_TX_PACKET);
}
rfm22b_dev->time_to_send = true; rfm22b_dev->time_to_send = true;
return RFM22B_EVENT_TX_START; return RFM22B_EVENT_TX_START;
} }
@ -2005,9 +2110,10 @@ static enum pios_rfm22b_event rfm22_receiveStatus(struct pios_rfm22b_dev *rfm22b
PHStatusPacketHandle status = (PHStatusPacketHandle)&(rfm22b_dev->rx_packet); PHStatusPacketHandle status = (PHStatusPacketHandle)&(rfm22b_dev->rx_packet);
int8_t rssi = rfm22b_dev->rssi_dBm; int8_t rssi = rfm22b_dev->rssi_dBm;
int8_t afc = rfm22b_dev->afc_correction_Hz; int8_t afc = rfm22b_dev->afc_correction_Hz;
uint32_t id = status->header.source_id; uint32_t id = status->source_id;
bool found = false;
// Have we seen this device recently? // Have we seen this device recently?
bool found = false;
uint8_t id_idx = 0; uint8_t id_idx = 0;
for ( ; id_idx < OPLINKSTATUS_PAIRIDS_NUMELEM; ++id_idx) for ( ; id_idx < OPLINKSTATUS_PAIRIDS_NUMELEM; ++id_idx)
if(rfm22b_dev->pair_stats[id_idx].pairID == id) if(rfm22b_dev->pair_stats[id_idx].pairID == id)
@ -2025,19 +2131,16 @@ static enum pios_rfm22b_event rfm22_receiveStatus(struct pios_rfm22b_dev *rfm22b
} }
// If we haven't seen it, find a slot to put it in. // If we haven't seen it, find a slot to put it in.
if (!found) else
{ {
uint8_t min_idx = 0; uint8_t min_idx = 0;
if(id != rfm22b_dev->destination_id) int8_t min_rssi = rfm22b_dev->pair_stats[0].rssi;
for (id_idx = 1; id_idx < OPLINKSTATUS_PAIRIDS_NUMELEM; ++id_idx)
{ {
int8_t min_rssi = rfm22b_dev->pair_stats[0].rssi; if(rfm22b_dev->pair_stats[id_idx].rssi < min_rssi)
for (id_idx = 1; id_idx < OPLINKSTATUS_PAIRIDS_NUMELEM; ++id_idx)
{ {
if(rfm22b_dev->pair_stats[id_idx].rssi < min_rssi) min_rssi = rfm22b_dev->pair_stats[id_idx].rssi;
{ min_idx = id_idx;
min_rssi = rfm22b_dev->pair_stats[id_idx].rssi;
min_idx = id_idx;
}
} }
} }
rfm22b_dev->pair_stats[min_idx].pairID = id; rfm22b_dev->pair_stats[min_idx].pairID = id;
@ -2049,14 +2152,6 @@ static enum pios_rfm22b_event rfm22_receiveStatus(struct pios_rfm22b_dev *rfm22b
return RFM22B_EVENT_RX_COMPLETE; return RFM22B_EVENT_RX_COMPLETE;
} }
static enum pios_rfm22b_event rfm22_initConnection(struct pios_rfm22b_dev *rfm22b_dev)
{
if (rfm22b_dev->coordinator)
return RFM22B_EVENT_REQUEST_CONNECTION;
else
return RFM22B_EVENT_WAIT_FOR_CONNECTION;
}
static enum pios_rfm22b_event rfm22_requestConnection(struct pios_rfm22b_dev *rfm22b_dev) static enum pios_rfm22b_event rfm22_requestConnection(struct pios_rfm22b_dev *rfm22b_dev)
{ {
PHConnectionPacketHandle cph = &(rfm22b_dev->con_packet); PHConnectionPacketHandle cph = &(rfm22b_dev->con_packet);
@ -2065,16 +2160,18 @@ static enum pios_rfm22b_event rfm22_requestConnection(struct pios_rfm22b_dev *rf
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_CONNECTING; rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_CONNECTING;
// Fill in the connection request // Fill in the connection request
rfm22b_dev->destination_id = rfm22b_dev->bindings[rfm22b_dev->cur_binding].pairID;
cph->header.destination_id = rfm22b_dev->destination_id; cph->header.destination_id = rfm22b_dev->destination_id;
cph->header.type = PACKET_TYPE_CON_REQUEST; cph->header.type = PACKET_TYPE_CON_REQUEST;
cph->header.data_size = PH_CONNECTION_DATA_SIZE(&(rfm22b_dev->con_packet)); cph->header.data_size = PH_CONNECTION_DATA_SIZE(&(rfm22b_dev->con_packet));
cph->datarate = rfm22b_dev->datarate; cph->source_id = rfm22b_dev->deviceID;
cph->frequency_hz = rfm22b_dev->frequency_hz; cph->main_port = rfm22b_dev->bindings[rfm22b_dev->cur_binding].main_port;
cph->min_frequency = rfm22b_dev->min_frequency; cph->flexi_port = rfm22b_dev->bindings[rfm22b_dev->cur_binding].flexi_port;
cph->max_frequency = rfm22b_dev->max_frequency; cph->vcp_port = rfm22b_dev->bindings[rfm22b_dev->cur_binding].vcp_port;
cph->max_tx_power = rfm22b_dev->tx_power; cph->com_speed = rfm22b_dev->bindings[rfm22b_dev->cur_binding].com_speed;
rfm22b_dev->time_to_send = true; rfm22b_dev->time_to_send = true;
rfm22b_dev->send_connection_request = true; rfm22b_dev->send_connection_request = true;
rfm22b_dev->prev_tx_packet = NULL;
return RFM22B_EVENT_TX_START; return RFM22B_EVENT_TX_START;
} }
@ -2086,16 +2183,45 @@ static void rfm22_setConnectionParameters(struct pios_rfm22b_dev *rfm22b_dev)
// Set our connection state to connected // Set our connection state to connected
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_CONNECTED; rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_CONNECTED;
// Configure this modem from the connection request message.
rfm22_setDatarate(rfm22b_dev, cph->datarate, true);
PIOS_RFM22B_SetTxPower((uint32_t)rfm22b_dev, cph->max_tx_power);
rfm22b_dev->min_frequency = cph->min_frequency;
rfm22b_dev->max_frequency = cph->max_frequency;
rfm22_setNominalCarrierFrequency(rfm22b_dev, cph->frequency_hz);
// Call the com port configuration function // Call the com port configuration function
if (rfm22b_dev->com_config_cb && !rfm22b_dev->coordinator) if (rfm22b_dev->com_config_cb)
rfm22b_dev->com_config_cb(cph->port, cph->com_speed); rfm22b_dev->com_config_cb(cph->main_port, cph->flexi_port, cph->vcp_port, cph->com_speed,
cph->min_frequency, cph->max_frequency, cph->channel_spacing);
// Configure this modem from the connection request message.
rfm22_setNominalCarrierFrequency(rfm22b_dev, cph->min_frequency, cph->max_frequency, cph->channel_spacing);
rfm22_setDatarate(rfm22b_dev, rfm22b_dev->datarate, true);
}
static portTickType rfm22_coordinatorTime(struct pios_rfm22b_dev *rfm22b_dev, portTickType ticks)
{
return ticks + rfm22b_dev->time_delta;
}
static bool rfm22_inChannelBuffer(struct pios_rfm22b_dev *rfm22b_dev)
{
portTickType time = rfm22_coordinatorTime(rfm22b_dev, xTaskGetTickCount());
uint8_t window = (uint8_t)(time & 0x7e);
return ((window == 0x7f) || (window == 0));
}
static uint8_t rfm22_calcChannel(struct pios_rfm22b_dev *rfm22b_dev)
{
portTickType time = rfm22_coordinatorTime(rfm22b_dev, xTaskGetTickCount());
// We change channels every 128 ms.
uint16_t n = (time >> 7) & 0xffff;
// The channel is calculated using the 16 bit CRC as the pseudo random number generator.
n = PIOS_CRC16_updateByte(n, 0);
float num_channels = rfm22b_dev->num_channels;
return (uint8_t)(num_channels * (float)n / (float)0xffff);
}
static bool rfm22_changeChannel(struct pios_rfm22b_dev *rfm22b_dev)
{
if (rfm22_isConnected(rfm22b_dev)) {
return rfm22_setFreqHopChannel(rfm22b_dev, rfm22_calcChannel(rfm22b_dev));
}
return false;
} }
static enum pios_rfm22b_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm22b_dev) static enum pios_rfm22b_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm22b_dev)
@ -2109,9 +2235,9 @@ static enum pios_rfm22b_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm
memcpy((uint8_t*)lcph, (uint8_t*)cph, PH_PACKET_SIZE((PHPacketHandle)cph)); memcpy((uint8_t*)lcph, (uint8_t*)cph, PH_PACKET_SIZE((PHPacketHandle)cph));
// Set the destination ID to the source of the connection request message. // Set the destination ID to the source of the connection request message.
PIOS_RFM22B_SetDestinationId((uint32_t)rfm22b_dev, cph->header.source_id); rfm22b_dev->destination_id = cph->source_id;
return RFM22B_EVENT_CONNECTION_ACCEPTED; return RFM22B_EVENT_DEFAULT;
} }
// ************************************ // ************************************
@ -2130,8 +2256,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
rfm22_clearLEDs(); rfm22_clearLEDs();
// Initialize the detected device statistics. // Initialize the detected device statistics.
for (uint8_t i = 0; i < OPLINKSTATUS_PAIRIDS_NUMELEM; ++i) for (uint8_t i = 0; i < OPLINKSTATUS_PAIRIDS_NUMELEM; ++i) {
{
rfm22b_dev->pair_stats[i].pairID = 0; rfm22b_dev->pair_stats[i].pairID = 0;
rfm22b_dev->pair_stats[i].rssi = -127; rfm22b_dev->pair_stats[i].rssi = -127;
rfm22b_dev->pair_stats[i].afc_correction = 0; rfm22b_dev->pair_stats[i].afc_correction = 0;
@ -2144,37 +2269,41 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
// Initialize the state // Initialize the state
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_DISCONNECTED; rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_DISCONNECTED;
rfm22b_dev->tx_power = RFM22B_DEFAULT_TX_POWER;
rfm22b_dev->destination_id = 0xffffffff; rfm22b_dev->destination_id = 0xffffffff;
rfm22b_dev->time_to_send = false; rfm22b_dev->time_to_send = false;
rfm22b_dev->time_to_send_offset = 0; rfm22b_dev->time_to_send_offset = 0;
rfm22b_dev->send_status = false; rfm22b_dev->send_status = false;
rfm22b_dev->send_connection_request = false; rfm22b_dev->send_connection_request = false;
rfm22b_dev->cur_resent_count = 0;
// Initialize the packets. // Initialize the packets.
rfm22b_dev->rx_packet_len = 0; rfm22b_dev->rx_packet_len = 0;
rfm22b_dev->tx_packet = NULL; rfm22b_dev->tx_packet = NULL;
rfm22b_dev->prev_tx_packet = NULL; rfm22b_dev->prev_tx_packet = NULL;
rfm22b_dev->stats.tx_seq = 0;
rfm22b_dev->stats.rx_seq = 0;
rfm22b_dev->data_packet.header.data_size = 0; rfm22b_dev->data_packet.header.data_size = 0;
rfm22b_dev->in_rx_mode = false; rfm22b_dev->in_rx_mode = false;
// Initialize the devide state
rfm22b_dev->device_status = rfm22b_dev->int_status1 = rfm22b_dev->int_status2 = rfm22b_dev->ezmac_status = 0;
rfm22b_dev->rx_buffer_wr = 0;
rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0;
rfm22b_dev->frequency_hop_channel = 0;
rfm22b_dev->afc_correction_Hz = 0;
rfm22b_dev->packet_start_ticks = 0;
rfm22b_dev->tx_complete_ticks = 0;
rfm22b_dev->rx_complete_ticks = 0;
// software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B) // software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B)
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl1, RFM22_opfc1_swres); rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl1, RFM22_opfc1_swres);
// wait 26ms for (int i = 50; i > 0; i--) {
PIOS_DELAY_WaitmS(26);
for (int i = 50; i > 0; i--)
{
// wait 1ms
PIOS_DELAY_WaitmS(1);
// read the status registers // read the status registers
rfm22b_dev->int_status1 = rfm22_read(rfm22b_dev, RFM22_interrupt_status1); rfm22b_dev->int_status1 = rfm22_read(rfm22b_dev, RFM22_interrupt_status1);
rfm22b_dev->int_status2 = rfm22_read(rfm22b_dev, RFM22_interrupt_status2); rfm22b_dev->int_status2 = rfm22_read(rfm22b_dev, RFM22_interrupt_status2);
if (rfm22b_dev->int_status2 & RFM22_is2_ichiprdy) break; if (rfm22b_dev->int_status2 & RFM22_is2_ichiprdy) break;
// wait 1ms
PIOS_DELAY_WaitmS(1);
} }
// **************** // ****************
@ -2189,23 +2318,6 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
rfm22_write(rfm22b_dev, RFM22_interrupt_enable1, 0x00); rfm22_write(rfm22b_dev, RFM22_interrupt_enable1, 0x00);
rfm22_write(rfm22b_dev, RFM22_interrupt_enable2, 0x00); rfm22_write(rfm22b_dev, RFM22_interrupt_enable2, 0x00);
// ****************
rfm22b_dev->device_status = rfm22b_dev->int_status1 = rfm22b_dev->int_status2 = rfm22b_dev->ezmac_status = 0;
rfm22b_dev->rx_buffer_wr = 0;
rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0;
rfm22b_dev->frequency_hop_channel = 0;
rfm22b_dev->afc_correction_Hz = 0;
rfm22b_dev->packet_start_ticks = 0;
rfm22b_dev->tx_complete_ticks = 0;
rfm22b_dev->rx_complete_ticks = 0;
// ****************
// read the RF chip ID bytes // read the RF chip ID bytes
// read the device type // read the device type
@ -2235,18 +2347,9 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
return RFM22B_EVENT_FATAL_ERROR; return RFM22B_EVENT_FATAL_ERROR;
} }
// ****************
// set the minimum and maximum carrier frequency allowed
rfm22b_dev->min_frequency = RFM22B_DEFAULT_MIN_FREQUENCY;
rfm22b_dev->max_frequency = RFM22B_DEFAULT_MAX_FREQUENCY;
rfm22b_dev->frequency_hz = RFM22B_DEFAULT_FREQUENCY;
// ****************
// calibrate our RF module to be exactly on frequency .. different for every module // calibrate our RF module to be exactly on frequency .. different for every module
rfm22_write(rfm22b_dev, RFM22_xtal_osc_load_cap, OSC_LOAD_CAP); rfm22_write(rfm22b_dev, RFM22_xtal_osc_load_cap, OSC_LOAD_CAP);
// ****************
// disable Low Duty Cycle Mode // disable Low Duty Cycle Mode
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, 0x00); rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, 0x00);
@ -2260,21 +2363,18 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
// GPIO port use default value // GPIO port use default value
rfm22_write(rfm22b_dev, RFM22_io_port_config, RFM22_io_port_default); rfm22_write(rfm22b_dev, RFM22_io_port_config, RFM22_io_port_default);
if (rfm22b_dev->cfg.gpio_direction == GPIO0_TX_GPIO1_RX) { if (rfm22b_dev->cfg.gpio_direction == GPIO0_TX_GPIO1_RX) {
rfm22_write(rfm22b_dev, RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch) // GPIO0 = TX State (to control RF Switch)
rfm22_write(rfm22b_dev, RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch) rfm22_write(rfm22b_dev, RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate);
// GPIO1 = RX State (to control RF Switch)
rfm22_write(rfm22b_dev, RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate);
} else { } else {
rfm22_write(rfm22b_dev, RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_rxstate); // GPIO0 = TX State (to control RF Switch) // GPIO0 = TX State (to control RF Switch)
rfm22_write(rfm22b_dev, RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_txstate); // GPIO1 = RX State (to control RF Switch) rfm22_write(rfm22b_dev, RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_rxstate);
// GPIO1 = RX State (to control RF Switch)
rfm22_write(rfm22b_dev, RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_txstate);
} }
rfm22_write(rfm22b_dev, RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca); // GPIO2 = Clear Channel Assessment // GPIO2 = Clear Channel Assessment
rfm22_write(rfm22b_dev, RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca);
// ****************
// initialize the frequency hopping step size
uint32_t freq_hop_step_size = 50000;
freq_hop_step_size /= 10000; // in 10kHz increments
if (freq_hop_step_size > 255) freq_hop_step_size = 255;
rfm22b_dev->frequency_hop_step_size_reg = freq_hop_step_size;
// FIFO mode, GFSK modulation // FIFO mode, GFSK modulation
uint8_t fd_bit = rfm22_read(rfm22b_dev, RFM22_modulation_mode_control2) & RFM22_mmc2_fd; uint8_t fd_bit = rfm22_read(rfm22b_dev, RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
@ -2315,18 +2415,18 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
// no header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header. // no header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header.
rfm22_write(rfm22b_dev, RFM22_header_control2, RFM22_header_cntl2_hdlen_none | rfm22_write(rfm22b_dev, RFM22_header_control2, RFM22_header_cntl2_hdlen_none |
RFM22_header_cntl2_synclen_3210 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); RFM22_header_cntl2_synclen_3210 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01));
#else #else
// header control - using a 4 by header with broadcast of 0xffffffff // header control - using a 4 by header with broadcast of 0xffffffff
rfm22_write(rfm22b_dev, RFM22_header_control1, rfm22_write(rfm22b_dev, RFM22_header_control1,
RFM22_header_cntl1_bcen_0 | RFM22_header_cntl1_bcen_0 |
RFM22_header_cntl1_bcen_1 | RFM22_header_cntl1_bcen_1 |
RFM22_header_cntl1_bcen_2 | RFM22_header_cntl1_bcen_2 |
RFM22_header_cntl1_bcen_3 | RFM22_header_cntl1_bcen_3 |
RFM22_header_cntl1_hdch_0 | RFM22_header_cntl1_hdch_0 |
RFM22_header_cntl1_hdch_1 | RFM22_header_cntl1_hdch_1 |
RFM22_header_cntl1_hdch_2 | RFM22_header_cntl1_hdch_2 |
RFM22_header_cntl1_hdch_3); RFM22_header_cntl1_hdch_3);
// Check all bit of all bytes of the header // Check all bit of all bytes of the header
rfm22_write(rfm22b_dev, RFM22_header_enable0, 0xff); rfm22_write(rfm22b_dev, RFM22_header_enable0, 0xff);
rfm22_write(rfm22b_dev, RFM22_header_enable1, 0xff); rfm22_write(rfm22b_dev, RFM22_header_enable1, 0xff);
@ -2340,9 +2440,9 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
rfm22_write(rfm22b_dev, RFM22_check_header3, (id >> 24) & 0xff); rfm22_write(rfm22b_dev, RFM22_check_header3, (id >> 24) & 0xff);
// 4 header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header. // 4 header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header.
rfm22_write(rfm22b_dev, RFM22_header_control2, rfm22_write(rfm22b_dev, RFM22_header_control2,
RFM22_header_cntl2_hdlen_3210 | RFM22_header_cntl2_hdlen_3210 |
RFM22_header_cntl2_synclen_3210 | RFM22_header_cntl2_synclen_3210 |
((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); ((TX_PREAMBLE_NIBBLES >> 8) & 0x01));
#endif #endif
// sync word // sync word
@ -2351,13 +2451,8 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
rfm22_write(rfm22b_dev, RFM22_sync_word1, SYNC_BYTE_3); rfm22_write(rfm22b_dev, RFM22_sync_word1, SYNC_BYTE_3);
rfm22_write(rfm22b_dev, RFM22_sync_word0, SYNC_BYTE_4); rfm22_write(rfm22b_dev, RFM22_sync_word0, SYNC_BYTE_4);
rfm22_write(rfm22b_dev, RFM22_agc_override1, RFM22_agc_ovr1_agcen);
// set frequency hopping channel step size (multiples of 10kHz)
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_step_size, rfm22b_dev->frequency_hop_step_size_reg);
// set the tx power // set the tx power
rfm22_write(rfm22b_dev, RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | rfm22b_dev->tx_power); rfm22_write(rfm22b_dev, RFM22_tx_power, RFM22_tx_pwr_lna_sw | rfm22b_dev->tx_power);
// TX FIFO Almost Full Threshold (0 - 63) // TX FIFO Almost Full Threshold (0 - 63)
rfm22_write(rfm22b_dev, RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); rfm22_write(rfm22b_dev, RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK);
@ -2372,7 +2467,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
rfm22_write(rfm22b_dev, RFM22_xtal_osc_load_cap, rfm22b_dev->cfg.RFXtalCap); rfm22_write(rfm22b_dev, RFM22_xtal_osc_load_cap, rfm22b_dev->cfg.RFXtalCap);
// Initialize the frequency and datarate to te default. // Initialize the frequency and datarate to te default.
rfm22_setNominalCarrierFrequency(rfm22b_dev, RFM22B_DEFAULT_FREQUENCY); rfm22_setNominalCarrierFrequency(rfm22b_dev, rfm22b_dev->init_frequency, rfm22b_dev->init_frequency, RFM22B_FREQUENCY_HOP_STEP_SIZE);
rfm22_setDatarate(rfm22b_dev, RFM22B_DEFAULT_RX_DATARATE, true); rfm22_setDatarate(rfm22b_dev, RFM22B_DEFAULT_RX_DATARATE, true);
return RFM22B_EVENT_INITIALIZED; return RFM22B_EVENT_INITIALIZED;
@ -2382,7 +2477,7 @@ static void rfm22_clearLEDs() {
LINK_LED_OFF; LINK_LED_OFF;
RX_LED_OFF; RX_LED_OFF;
TX_LED_OFF; TX_LED_OFF;
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM #if defined(PIOS_RFM22B_DEBUG_ON_TELEM) || defined(PIOS_RFM22B_DEBUG_ON_RCVR)
D1_LED_OFF; D1_LED_OFF;
D2_LED_OFF; D2_LED_OFF;
D3_LED_OFF; D3_LED_OFF;
@ -2402,7 +2497,7 @@ static enum pios_rfm22b_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev)
rfm22b_dev->rx_buffer_wr = 0; rfm22b_dev->rx_buffer_wr = 0;
TX_LED_OFF; TX_LED_OFF;
RX_LED_OFF; RX_LED_OFF;
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM #if defined(PIOS_RFM22B_DEBUG_ON_TELEM) || defined(PIOS_RFM22B_DEBUG_ON_RCVR)
D1_LED_OFF; D1_LED_OFF;
D2_LED_OFF; D2_LED_OFF;
D3_LED_OFF; D3_LED_OFF;

View File

@ -62,9 +62,6 @@ 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; struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_validate(rfm22b_dev)) if (!PIOS_RFM22B_validate(rfm22b_dev))
return; return;
// This is only allowed for coordinators.
if (!rfm22b_dev->coordinator)
return;
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex. // 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; enum rfm22b_datarate datarate = RFM22_datarate_64000;
if (baud <= 1024) if (baud <= 1024)
@ -78,12 +75,12 @@ static void PIOS_RFM22B_COM_ChangeBaud(uint32_t rfm22b_id, uint32_t baud)
else if (baud <= 19200) else if (baud <= 19200)
datarate = RFM22_datarate_32000; datarate = RFM22_datarate_32000;
else if (baud <= 38400) else if (baud <= 38400)
datarate = RFM22_datarate_64000; datarate = RFM22_datarate_57600;
else if (baud <= 57600) else if (baud <= 57600)
datarate = RFM22_datarate_128000; datarate = RFM22_datarate_128000;
else if (baud <= 115200) else if (baud <= 115200)
datarate = RFM22_datarate_192000; datarate = RFM22_datarate_192000;
PIOS_RFM22B_SetDatarate(rfm22b_id, datarate, true); rfm22b_dev->datarate = datarate;
} }
static void PIOS_RFM22B_COM_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail) static void PIOS_RFM22B_COM_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail)

View File

@ -34,6 +34,7 @@
#include <packet_handler.h> #include <packet_handler.h>
#include <oplinksettings.h> #include <oplinksettings.h>
/* Constant definitions */
enum gpio_direction {GPIO0_TX_GPIO1_RX, GPIO0_RX_GPIO1_TX}; enum gpio_direction {GPIO0_TX_GPIO1_RX, GPIO0_RX_GPIO1_TX};
/* Global Types */ /* Global Types */
@ -67,10 +68,11 @@ enum rfm22b_datarate {
RFM22_datarate_19200 = 7, RFM22_datarate_19200 = 7,
RFM22_datarate_24000 = 8, RFM22_datarate_24000 = 8,
RFM22_datarate_32000 = 9, RFM22_datarate_32000 = 9,
RFM22_datarate_64000 = 10, RFM22_datarate_57600 = 10,
RFM22_datarate_128000 = 11, RFM22_datarate_64000 = 11,
RFM22_datarate_192000 = 12, RFM22_datarate_128000 = 12,
RFM22_datarate_256000 = 13, RFM22_datarate_192000 = 13,
RFM22_datarate_256000 = 14,
}; };
struct rfm22b_stats { struct rfm22b_stats {
@ -96,18 +98,22 @@ struct rfm22b_stats {
}; };
/* Callback function prototypes */ /* Callback function prototypes */
typedef void (*PIOS_RFM22B_ComConfigCallback)(OPLinkSettingsOutputConnectionOptions com_port, OPLinkSettingsComSpeedOptions com_speed); typedef void (*PIOS_RFM22B_ComConfigCallback)(OPLinkSettingsRemoteMainPortOptions main_port, OPLinkSettingsRemoteFlexiPortOptions flexi_port,
OPLinkSettingsRemoteVCPPortOptions vcp_port, OPLinkSettingsComSpeedOptions com_speed,
uint32_t min_frequency, uint32_t max_frequency, uint32_t channel_spacing);
/* Public Functions */ /* Public Functions */
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 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_SetFrequencyRange(uint32_t rfm22b_id, uint32_t min_frequency, uint32_t max_frequency); 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_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr);
extern void PIOS_RFM22B_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening); extern void PIOS_RFM22B_SetFrequencyRange(uint32_t rfm22b_id, uint32_t min_freq, uint32_t max_freq, uint32_t step_size);
extern void PIOS_RFM22B_SetInitialFrequency(uint32_t rfm22b_id, uint32_t init_freq);
extern void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id); extern void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id);
extern void PIOS_RFM22B_SetCoordinator(uint32_t rfm22b_id, bool coordinator);
extern void PIOS_RFM22B_SetRemoteComConfig(uint32_t rfm22b_id, OPLinkSettingsOutputConnectionOptions com_port, OPLinkSettingsComSpeedOptions com_speed);
extern void PIOS_RFM22B_SetComConfigCallback(uint32_t rfm22b_id, PIOS_RFM22B_ComConfigCallback cb); extern void PIOS_RFM22B_SetComConfigCallback(uint32_t rfm22b_id, PIOS_RFM22B_ComConfigCallback cb);
extern void PIOS_RFM22B_SetBindings(uint32_t rfm22b_id, const uint32_t bindingPairIDs[], const uint8_t mainPortSettings[],
const uint8_t flexiPortSettings[], const uint8_t vcpPortSettings[], const uint8_t comSpeeds[]);
extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id);
extern bool PIOS_RFM22B_IsCoordinator(uint32_t rfb22b_id);
extern void PIOS_RFM22B_GetStats(uint32_t rfm22b_id, struct rfm22b_stats *stats); extern void PIOS_RFM22B_GetStats(uint32_t rfm22b_id, struct rfm22b_stats *stats);
extern uint8_t PIOS_RFM2B_GetPairStats(uint32_t rfm22b_id, uint32_t *device_ids, int8_t *RSSIs, uint8_t max_pairs); extern uint8_t PIOS_RFM2B_GetPairStats(uint32_t rfm22b_id, uint32_t *device_ids, int8_t *RSSIs, uint8_t max_pairs);
extern bool PIOS_RFM22B_LinkStatus(uint32_t rfm22b_id); extern bool PIOS_RFM22B_LinkStatus(uint32_t rfm22b_id);

View File

@ -1,17 +1,17 @@
/** /**
****************************************************************************** ******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer * @addtogroup PIOS PIOS Core hardware abstraction layer
* @{ * @{
* @addtogroup PIOS_RFM22B Radio Functions * @addtogroup PIOS_RFM22B Radio Functions
* @brief PIOS interface for RFM22B Radio * @brief PIOS interface for RFM22B Radio
* @{ * @{
* *
* @file pios_rfm22b_priv.h * @file pios_rfm22b_priv.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief RFM22B private definitions. * @brief RFM22B private definitions.
* @see The GNU Public License (GPL) Version 3 * @see The GNU Public License (GPL) Version 3
* *
*****************************************************************************/ *****************************************************************************/
/* /*
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -444,28 +444,28 @@
#define RFM22_adc8_control 0x4F // R/W #define RFM22_adc8_control 0x4F // R/W
/* /*
#define RFM22_analog_test_bus 0x50 // R/W #define RFM22_analog_test_bus 0x50 // R/W
#define RFM22_digital_test_bus 0x51 // R/W #define RFM22_digital_test_bus 0x51 // R/W
#define RFM22_tx_ramp_control 0x52 // R/W #define RFM22_tx_ramp_control 0x52 // R/W
#define RFM22_pll_tune_time 0x53 // R/W #define RFM22_pll_tune_time 0x53 // R/W
#define RFM22_calibration_control 0x55 // R/W #define RFM22_calibration_control 0x55 // R/W
#define RFM22_modem_test 0x56 // R/W #define RFM22_modem_test 0x56 // R/W
#define RFM22_chargepump_test 0x57 // R/W #define RFM22_chargepump_test 0x57 // R/W
#define RFM22_chargepump_current_trimming_override 0x58 // R/W #define RFM22_chargepump_current_trimming_override 0x58 // R/W
#define RFM22_divider_current_trimming 0x59 // R/W #define RFM22_divider_current_trimming 0x59 // R/W
#define RFM22_vco_current_trimming 0x5A // R/W #define RFM22_vco_current_trimming 0x5A // R/W
#define RFM22_vco_calibration_override 0x5B // R/W #define RFM22_vco_calibration_override 0x5B // R/W
#define RFM22_synthersizer_test 0x5C // R/W #define RFM22_synthersizer_test 0x5C // R/W
#define RFM22_block_enable_override1 0x5D // R/W #define RFM22_block_enable_override1 0x5D // R/W
#define RFM22_block_enable_override2 0x5E // R/W #define RFM22_block_enable_override2 0x5E // R/W
#define RFM22_block_enable_override3 0x5F // R/W #define RFM22_block_enable_override3 0x5F // R/W
*/ */
#define RFM22_channel_filter_coeff_addr 0x60 // R/W #define RFM22_channel_filter_coeff_addr 0x60 // R/W
#define RFM22_ch_fil_coeff_ad_inv_pre_th_mask 0xF0 // #define RFM22_ch_fil_coeff_ad_inv_pre_th_mask 0xF0 //
@ -482,14 +482,14 @@
#define RFM22_xtal_osc_por_ctrl_bufovr 0x02 // Output Buffer Enable Override. #define RFM22_xtal_osc_por_ctrl_bufovr 0x02 // Output Buffer Enable Override.
#define RFM22_xtal_osc_por_ctrl_enbuf 0x01 // Output Buffer Enable. #define RFM22_xtal_osc_por_ctrl_enbuf 0x01 // Output Buffer Enable.
/* /*
#define RFM22_rc_osc_coarse_calbration_override 0x63 // R/W #define RFM22_rc_osc_coarse_calbration_override 0x63 // R/W
#define RFM22_rc_osc_fine_calbration_override 0x64 // R/W #define RFM22_rc_osc_fine_calbration_override 0x64 // R/W
#define RFM22_ldo_control_override 0x65 // R/W #define RFM22_ldo_control_override 0x65 // R/W
#define RFM22_ldo_level_setting 0x66 // R/W #define RFM22_ldo_level_setting 0x66 // R/W
#define RFM22_deltasigma_adc_tuning1 0x67 // R/W #define RFM22_deltasigma_adc_tuning1 0x67 // R/W
#define RFM22_deltasigma_adc_tuning2 0x68 // R/W #define RFM22_deltasigma_adc_tuning2 0x68 // R/W
*/ */
#define RFM22_agc_override1 0x69 // R/W #define RFM22_agc_override1 0x69 // R/W
#define RFM22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0. #define RFM22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0.
@ -504,10 +504,6 @@
#define RFM22_tx_power 0x6D // R/W #define RFM22_tx_power 0x6D // R/W
#define RFM22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times. #define RFM22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times.
#define RFM22_tx_pwr_papeaklvl_0 0x10 // " "
#define RFM22_tx_pwr_papeaklvl_1 0x20 // PA Peak Detect Level (direct from register). 00 = 6.5, 01 = 7, 10 = 7.5, 11 = 8, 00 = default
#define RFM22_tx_pwr_papeaken 0x40 // PA Peak Detector Enable.
#define RFM22_tx_pwr_papeakval 0x80 // PA Peak Detector Value Read Register. Reading a 1 in this register when the papeaken=1 then the PA drain voltage is too high and the match network needs adjusting for optimal efficiency.
#define RFM22_tx_data_rate1 0x6E // R/W #define RFM22_tx_data_rate1 0x6E // R/W
#define RFM22_tx_data_rate0 0x6F // R/W #define RFM22_tx_data_rate0 0x6F // R/W
@ -578,12 +574,8 @@ enum pios_rfm22b_dev_magic {
enum pios_rfm22b_state { enum pios_rfm22b_state {
RFM22B_STATE_UNINITIALIZED, RFM22B_STATE_UNINITIALIZED,
RFM22B_STATE_INITIALIZING, RFM22B_STATE_INITIALIZING,
RFM22B_STATE_INITIALIZED,
RFM22B_STATE_INITIATING_CONNECTION,
RFM22B_STATE_WAIT_FOR_CONNECTION,
RFM22B_STATE_REQUESTING_CONNECTION, RFM22B_STATE_REQUESTING_CONNECTION,
RFM22B_STATE_ACCEPTING_CONNECTION, RFM22B_STATE_ACCEPTING_CONNECTION,
RFM22B_STATE_CONNECTION_ACCEPTED,
RFM22B_STATE_RX_MODE, RFM22B_STATE_RX_MODE,
RFM22B_STATE_WAIT_PREAMBLE, RFM22B_STATE_WAIT_PREAMBLE,
RFM22B_STATE_WAIT_SYNC, RFM22B_STATE_WAIT_SYNC,
@ -605,13 +597,12 @@ enum pios_rfm22b_state {
}; };
enum pios_rfm22b_event { enum pios_rfm22b_event {
RFM22B_EVENT_DEFAULT,
RFM22B_EVENT_INT_RECEIVED, RFM22B_EVENT_INT_RECEIVED,
RFM22B_EVENT_INITIALIZE, RFM22B_EVENT_INITIALIZE,
RFM22B_EVENT_INITIALIZED, RFM22B_EVENT_INITIALIZED,
RFM22B_EVENT_REQUEST_CONNECTION, RFM22B_EVENT_REQUEST_CONNECTION,
RFM22B_EVENT_WAIT_FOR_CONNECTION,
RFM22B_EVENT_CONNECTION_REQUESTED, RFM22B_EVENT_CONNECTION_REQUESTED,
RFM22B_EVENT_CONNECTION_ACCEPTED,
RFM22B_EVENT_PACKET_ACKED, RFM22B_EVENT_PACKET_ACKED,
RFM22B_EVENT_PACKET_NACKED, RFM22B_EVENT_PACKET_NACKED,
RFM22B_EVENT_ACK_TIMEOUT, RFM22B_EVENT_ACK_TIMEOUT,
@ -645,6 +636,14 @@ typedef struct {
uint8_t lastContact; uint8_t lastContact;
} rfm22b_pair_stats; } rfm22b_pair_stats;
typedef struct {
uint32_t pairID;
OPLinkSettingsRemoteMainPortOptions main_port;
OPLinkSettingsRemoteFlexiPortOptions flexi_port;
OPLinkSettingsRemoteVCPPortOptions vcp_port;
OPLinkSettingsComSpeedOptions com_speed;
} rfm22b_binding;
struct pios_rfm22b_dev { struct pios_rfm22b_dev {
enum pios_rfm22b_dev_magic magic; enum pios_rfm22b_dev_magic magic;
struct pios_rfm22b_cfg cfg; struct pios_rfm22b_cfg cfg;
@ -659,6 +658,10 @@ struct pios_rfm22b_dev {
// The destination ID // The destination ID
uint32_t destination_id; uint32_t destination_id;
// The list of bound radios.
rfm22b_binding bindings[OPLINKSETTINGS_BINDINGS_NUMELEM];
uint8_t cur_binding;
// Is this device a coordinator? // Is this device a coordinator?
bool coordinator; bool coordinator;
@ -714,9 +717,6 @@ struct pios_rfm22b_dev {
// RSSI in dBm // RSSI in dBm
int8_t rssi_dBm; int8_t rssi_dBm;
// The packet queue handle
xQueueHandle packetQueue;
// The tx data packet // The tx data packet
PHPacket data_packet; PHPacket data_packet;
// The current tx packet // The current tx packet
@ -758,14 +758,17 @@ struct pios_rfm22b_dev {
bool send_ppm; bool send_ppm;
bool send_connection_request; bool send_connection_request;
bool time_to_send; bool time_to_send;
uint8_t time_to_send_offset;
// The minimum frequency // The offset between our clock and the global send clock
uint32_t min_frequency; uint8_t time_to_send_offset;
// The maximum frequency // The number of times that the current packet has been resent.
uint32_t max_frequency; uint8_t cur_resent_count;
// The current nominal frequency
uint32_t frequency_hz; // The initial frequency
uint32_t init_frequency;
// The number of frequency hopping channels.
uint16_t num_channels;
// The frequency hopping step size // The frequency hopping step size
float frequency_step_size; float frequency_step_size;
// current frequency hop channel // current frequency hop channel
@ -775,17 +778,24 @@ struct pios_rfm22b_dev {
// afc correction reading (in Hz) // afc correction reading (in Hz)
int8_t afc_correction_Hz; int8_t afc_correction_Hz;
// The maximum time (ms) that it should take to transmit / receive a packet. // The packet timers.
uint32_t max_packet_time;
portTickType packet_start_ticks; portTickType packet_start_ticks;
portTickType tx_complete_ticks; portTickType tx_complete_ticks;
portTickType rx_complete_ticks; portTickType rx_complete_ticks;
portTickType time_delta;
// The maximum time (ms) that it should take to transmit / receive a packet.
uint32_t max_packet_time;
// The maximum time to wait for an ACK.
uint8_t max_ack_delay; uint8_t max_ack_delay;
#ifdef PIOS_INCLUDE_RFM22B_RCVR
// The PPM channel values // The PPM channel values
uint16_t ppm_channel[PIOS_RFM22B_RCVR_MAX_CHANNELS]; uint16_t ppm_channel[PIOS_RFM22B_RCVR_MAX_CHANNELS];
uint8_t ppm_supv_timer; uint8_t ppm_supv_timer;
bool ppm_fresh; bool ppm_fresh;
#endif
}; };
@ -803,6 +813,6 @@ extern const struct pios_com_driver pios_rfm22b_com_driver;
#endif /* PIOS_RFM22B_PRIV_H */ #endif /* PIOS_RFM22B_PRIV_H */
/** /**
* @} * @}
* @} * @}
*/ */

View File

@ -58,7 +58,7 @@ endif
# Use file-extension c for "c-only"-files # Use file-extension c for "c-only"-files
ifndef TESTAPP ifndef TESTAPP
## Application Core ## Application Core
SRC += ${OPMODULEDIR}/System/systemmod.c SRC += $(OPMODULEDIR)/System/systemmod.c
SRC += $(OPSYSTEM)/coptercontrol.c SRC += $(OPSYSTEM)/coptercontrol.c
SRC += $(OPSYSTEM)/pios_board.c SRC += $(OPSYSTEM)/pios_board.c
SRC += $(OPSYSTEM)/pios_usb_board_data.c SRC += $(OPSYSTEM)/pios_usb_board_data.c

View File

@ -44,7 +44,7 @@ CFLAGS += -ffast-math
# Use file-extension c for "c-only"-files # Use file-extension c for "c-only"-files
ifndef TESTAPP ifndef TESTAPP
## Application Core ## Application Core
SRC += ${OPMODULEDIR}/System/systemmod.c SRC += $(OPMODULEDIR)/System/systemmod.c
SRC += $(OPSYSTEM)/osd.c SRC += $(OPSYSTEM)/osd.c
SRC += $(OPSYSTEM)/pios_board.c SRC += $(OPSYSTEM)/pios_board.c
SRC += $(OPSYSTEM)/pios_usb_board_data.c SRC += $(OPSYSTEM)/pios_usb_board_data.c

View File

@ -36,7 +36,7 @@ OPTMODULES =
# Use file-extension c for "c-only"-files # Use file-extension c for "c-only"-files
ifndef TESTAPP ifndef TESTAPP
## Application Core ## Application Core
SRC += ${OPMODULEDIR}/PipXtreme/pipxtrememod.c SRC += $(OPMODULEDIR)/PipXtreme/pipxtrememod.c
SRC += $(OPSYSTEM)/pipxtreme.c SRC += $(OPSYSTEM)/pipxtreme.c
SRC += $(OPSYSTEM)/pios_board.c SRC += $(OPSYSTEM)/pios_board.c
SRC += $(OPSYSTEM)/pios_usb_board_data.c SRC += $(OPSYSTEM)/pios_usb_board_data.c

View File

@ -90,7 +90,7 @@
/* #define PIOS_INCLUDE_PPM_FLEXI */ /* #define PIOS_INCLUDE_PPM_FLEXI */
/* #define PIOS_INCLUDE_DSM */ /* #define PIOS_INCLUDE_DSM */
/* #define PIOS_INCLUDE_SBUS */ /* #define PIOS_INCLUDE_SBUS */
/* #define PIOS_INCLUDE_GCSRCVR */ #define PIOS_INCLUDE_GCSRCVR
/* PIOS abstract receiver interface */ /* PIOS abstract receiver interface */
#define PIOS_INCLUDE_RCVR #define PIOS_INCLUDE_RCVR

View File

@ -1,17 +1,16 @@
/* -*- Mode: c; c-basic-offset: 2; tab-width: 2; indent-tabs-mode: t -*- */
/** /**
****************************************************************************** ******************************************************************************
* @addtogroup OpenPilotSystem OpenPilot System * @addtogroup OpenPilotSystem OpenPilot System
* @{ * @{
* @addtogroup OpenPilotCore OpenPilot Core * @addtogroup OpenPilotCore OpenPilot Core
* @{ * @{
* *
* @file pios_board.c * @file pios_board.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Defines board specific static initializers for hardware for the OpenPilot board. * @brief Defines board specific static initializers for hardware for the OpenPilot board.
* @see The GNU Public License (GPL) Version 3 * @see The GNU Public License (GPL) Version 3
* *
*****************************************************************************/ *****************************************************************************/
/* /*
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -33,9 +32,6 @@
#include <oplinksettings.h> #include <oplinksettings.h>
#include <board_hw_defs.c> #include <board_hw_defs.c>
#define PIOS_COM_TELEM_RX_BUF_LEN 256
#define PIOS_COM_TELEM_TX_BUF_LEN 256
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 256 #define PIOS_COM_TELEM_USB_RX_BUF_LEN 256
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 256 #define PIOS_COM_TELEM_USB_TX_BUF_LEN 256
@ -45,9 +41,12 @@
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 256 #define PIOS_COM_RFM22B_RF_RX_BUF_LEN 256
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 256 #define PIOS_COM_RFM22B_RF_TX_BUF_LEN 256
#define PIOS_COM_TELEM_RX_BUF_LEN 256
#define PIOS_COM_TELEM_TX_BUF_LEN 256
uint32_t pios_com_telem_usb_id = 0; uint32_t pios_com_telem_usb_id = 0;
uint32_t pios_com_telem_vcp_id = 0; uint32_t pios_com_telem_vcp_id = 0;
uint32_t pios_com_telem_uart_telem_id = 0; uint32_t pios_com_telem_uart_main_id = 0;
uint32_t pios_com_telem_uart_flexi_id = 0; uint32_t pios_com_telem_uart_flexi_id = 0;
uint32_t pios_com_telemetry_id = 0; uint32_t pios_com_telemetry_id = 0;
#if defined(PIOS_INCLUDE_PPM) #if defined(PIOS_INCLUDE_PPM)
@ -61,6 +60,8 @@ uint32_t pios_rfm22b_id = 0;
uint32_t pios_com_rfm22b_id = 0; uint32_t pios_com_rfm22b_id = 0;
uint32_t pios_com_radio_id = 0; uint32_t pios_com_radio_id = 0;
#endif #endif
uint8_t *pios_uart_rx_buffer;
uint8_t *pios_uart_tx_buffer;
/** /**
* PIOS_Board_Init() * PIOS_Board_Init()
@ -154,8 +155,8 @@ void PIOS_Board_Init(void) {
PIOS_Assert(rx_buffer); PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer); PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
PIOS_Assert(0); PIOS_Assert(0);
} }
} }
@ -173,70 +174,13 @@ void PIOS_Board_Init(void) {
PIOS_Assert(rx_buffer); PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer); PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, if (PIOS_COM_Init(&pios_com_telem_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
rx_buffer, PIOS_COM_TELEM_VCP_RX_BUF_LEN, rx_buffer, PIOS_COM_TELEM_VCP_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_VCP_TX_BUF_LEN)) { tx_buffer, PIOS_COM_TELEM_VCP_TX_BUF_LEN)) {
PIOS_Assert(0); PIOS_Assert(0);
} }
} }
#endif #endif
/* Configure the telemetry serial port */
#ifndef PIOS_RFM22B_DEBUG_ON_TELEM
{
uint32_t pios_usart1_id;
if (PIOS_USART_Init(&pios_usart1_id, &pios_usart_serial_cfg)) {
PIOS_Assert(0);
}
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_RX_BUF_LEN);
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_TX_BUF_LEN);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_uart_telem_id, &pios_usart_com_driver, pios_usart1_id,
rx_buffer, PIOS_COM_TELEM_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
#endif
/* Configure PPM input */
switch (oplinkSettings.PPM) {
#if defined(PIOS_INCLUDE_PPM)
case OPLINKSETTINGS_PPM_INPUT:
{
uint32_t pios_ppm_id;
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg);
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id))
PIOS_Assert(0);
break;
}
#endif /* PIOS_INCLUDE_PPM */
#if defined(PIOS_INCLUDE_PPM_OUT)
case OPLINKSETTINGS_PPM_OUTPUT:
PIOS_PPM_Out_Init(&pios_ppm_out_id, &pios_ppm_out_cfg);
break;
#endif /* PIOS_INCLUDE_PPM_OUT */
default:
{
/* Configure the flexi serial port if PPM not selected */
uint32_t pios_usart3_id;
if (PIOS_USART_Init(&pios_usart3_id, &pios_usart_telem_flexi_cfg)) {
PIOS_Assert(0);
}
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RX_BUF_LEN);
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_TX_BUF_LEN);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_uart_flexi_id, &pios_usart_com_driver, pios_usart3_id,
rx_buffer, PIOS_COM_TELEM_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
}
/* Initalize the RFM22B radio COM device. */ /* Initalize the RFM22B radio COM device. */
#if defined(PIOS_INCLUDE_RFM22B) #if defined(PIOS_INCLUDE_RFM22B)
@ -253,13 +197,21 @@ void PIOS_Board_Init(void) {
PIOS_Assert(rx_buffer); PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer); PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_rfm22b_id, &pios_rfm22b_com_driver, pios_rfm22b_id, if (PIOS_COM_Init(&pios_com_rfm22b_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN, rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN,
tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) { tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) {
PIOS_Assert(0); PIOS_Assert(0);
} }
/* Set the RFM22B bindings. */
PIOS_RFM22B_SetBindings(pios_rfm22b_id, oplinkSettings.Bindings, oplinkSettings.RemoteMainPort,
oplinkSettings.RemoteFlexiPort, oplinkSettings.RemoteVCPPort, oplinkSettings.ComSpeed);
} }
#endif /* PIOS_INCLUDE_RFM22B */ #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);
/* Remap AFIO pin */ /* Remap AFIO pin */
GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
@ -269,6 +221,75 @@ void PIOS_Board_Init(void) {
PIOS_GPIO_Init(); PIOS_GPIO_Init();
} }
void PIOS_InitUartMainPort()
{
#ifndef PIOS_RFM22B_DEBUG_ON_TELEM
uint32_t pios_usart1_id;
if (PIOS_USART_Init(&pios_usart1_id, &pios_usart_serial_cfg)) {
PIOS_Assert(0);
}
PIOS_Assert(pios_uart_rx_buffer);
PIOS_Assert(pios_uart_tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_uart_main_id, &pios_usart_com_driver, pios_usart1_id,
pios_uart_rx_buffer, PIOS_COM_TELEM_RX_BUF_LEN,
pios_uart_tx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) {
PIOS_Assert(0);
}
#endif
}
void PIOS_InitUartFlexiPort()
{
uint32_t pios_usart3_id;
if (PIOS_USART_Init(&pios_usart3_id, &pios_usart_telem_flexi_cfg)) {
PIOS_Assert(0);
}
PIOS_Assert(pios_uart_rx_buffer);
PIOS_Assert(pios_uart_tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_uart_flexi_id, &pios_usart_com_driver, pios_usart3_id,
pios_uart_rx_buffer, PIOS_COM_TELEM_RX_BUF_LEN,
pios_uart_tx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
void PIOS_InitPPMMainPort(bool input)
{
#if defined(PIOS_INCLUDE_PPM)
/* PPM input is configured on the coordinator modem and output on the remote modem. */
if (input)
{
uint32_t pios_ppm_id;
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_main_cfg);
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id))
PIOS_Assert(0);
}
// For some reason, PPM output on the main port doesn't work.
#endif /* PIOS_INCLUDE_PPM */
}
void PIOS_InitPPMFlexiPort(bool input)
{
#if defined(PIOS_INCLUDE_PPM)
/* PPM input is configured on the coordinator modem and output on the remote modem. */
if (input)
{
uint32_t pios_ppm_id;
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_flexi_cfg);
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id))
PIOS_Assert(0);
}
#if defined(PIOS_INCLUDE_PPM_OUT)
else
{
PIOS_PPM_Out_Init(&pios_ppm_out_id, &pios_ppm_out_cfg);
}
#endif /* PIOS_INCLUDE_PPM_OUT */
#endif /* PIOS_INCLUDE_PPM */
}
/** /**
* @} * @}
*/ */

View File

@ -63,7 +63,7 @@ CFLAGS += -ffast-math
# Use file-extension c for "c-only"-files # Use file-extension c for "c-only"-files
ifndef TESTAPP ifndef TESTAPP
## Application Core ## Application Core
SRC += ${OPMODULEDIR}/System/systemmod.c SRC += $(OPMODULEDIR)/System/systemmod.c
SRC += $(OPSYSTEM)/revolution.c SRC += $(OPSYSTEM)/revolution.c
SRC += $(OPSYSTEM)/pios_board.c SRC += $(OPSYSTEM)/pios_board.c
SRC += $(OPSYSTEM)/pios_usb_board_data.c SRC += $(OPSYSTEM)/pios_usb_board_data.c

View File

@ -40,6 +40,13 @@
#include "hwsettings.h" #include "hwsettings.h"
#include "manualcontrolsettings.h" #include "manualcontrolsettings.h"
#if defined(PIOS_INCLUDE_RFM22B)
// Forward declarations
static void configureComCallback(OPLinkSettingsRemoteMainPortOptions main_port, OPLinkSettingsRemoteFlexiPortOptions flexi_port,
OPLinkSettingsRemoteVCPPortOptions vcp_port, OPLinkSettingsComSpeedOptions com_speed,
uint32_t min_frequency, uint32_t max_frequency, uint32_t channel_spacing);
#endif
/** /**
* Sensor configurations * Sensor configurations
*/ */
@ -634,6 +641,10 @@ void PIOS_Board_Init(void) {
#if defined(PIOS_INCLUDE_RFM22B) #if defined(PIOS_INCLUDE_RFM22B)
uint8_t hwsettings_radioport; uint8_t hwsettings_radioport;
HwSettingsRadioPortGet(&hwsettings_radioport); HwSettingsRadioPortGet(&hwsettings_radioport);
uint8_t hwsettings_maxrfpower;
HwSettingsMaxRFPowerGet(&hwsettings_maxrfpower);
uint32_t hwsettings_deffreq;
HwSettingsDefaultFrequencyGet(&hwsettings_deffreq);
switch (hwsettings_radioport) { switch (hwsettings_radioport) {
case HWSETTINGS_RADIOPORT_DISABLED: case HWSETTINGS_RADIOPORT_DISABLED:
break; break;
@ -645,6 +656,41 @@ void PIOS_Board_Init(void) {
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) { if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) {
PIOS_Assert(0); PIOS_Assert(0);
} }
// Set the modem parameters and reinitilize the modem.
PIOS_RFM22B_SetInitialFrequency(pios_rfm22b_id, hwsettings_deffreq);
switch (hwsettings_maxrfpower)
{
case OPLINKSETTINGS_MAXRFPOWER_125:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0);
break;
case OPLINKSETTINGS_MAXRFPOWER_16:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1);
break;
case OPLINKSETTINGS_MAXRFPOWER_316:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2);
break;
case OPLINKSETTINGS_MAXRFPOWER_63:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3);
break;
case OPLINKSETTINGS_MAXRFPOWER_126:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4);
break;
case OPLINKSETTINGS_MAXRFPOWER_25:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5);
break;
case OPLINKSETTINGS_MAXRFPOWER_50:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6);
break;
case OPLINKSETTINGS_MAXRFPOWER_100:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7);
break;
default:
// do nothing
break;
}
PIOS_RFM22B_Reinit(pios_rfm22b_id);
#ifdef PIOS_INCLUDE_RFM22B_COM #ifdef PIOS_INCLUDE_RFM22B_COM
uint8_t *rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); uint8_t *rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN);
uint8_t *tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); uint8_t *tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN);
@ -663,6 +709,10 @@ void PIOS_Board_Init(void) {
PIOS_Assert(0); PIOS_Assert(0);
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPLINK] = pios_rfm22b_rcvr_id; pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPLINK] = pios_rfm22b_rcvr_id;
#endif #endif
// Set the com port configuration callback.
PIOS_RFM22B_SetComConfigCallback(pios_rfm22b_id, &configureComCallback);
break; break;
} }
} }
@ -758,6 +808,52 @@ void PIOS_Board_Init(void) {
} }
#if defined(PIOS_INCLUDE_RFM22B)
/**
* Configure the radio com port based on a configuration event from the remote coordinator.
* \param[in] main_port The main com port options
* \param[in] flexi_port The flexi com port options
* \param[in] vcp_port The USB virtual com port options
* \param[in] com_speed The com port speed
*/
static void configureComCallback(OPLinkSettingsRemoteMainPortOptions main_port, OPLinkSettingsRemoteFlexiPortOptions flexi_port,
OPLinkSettingsRemoteVCPPortOptions vcp_port, OPLinkSettingsComSpeedOptions com_speed,
uint32_t min_frequency, uint32_t max_frequency, uint32_t channel_spacing)
{
uint32_t comBaud = 9600;
switch (com_speed) {
case OPLINKSETTINGS_COMSPEED_2400:
comBaud = 2400;
break;
case OPLINKSETTINGS_COMSPEED_4800:
comBaud = 4800;
break;
case OPLINKSETTINGS_COMSPEED_9600:
comBaud = 9600;
break;
case OPLINKSETTINGS_COMSPEED_19200:
comBaud = 19200;
break;
case OPLINKSETTINGS_COMSPEED_38400:
comBaud = 38400;
break;
case OPLINKSETTINGS_COMSPEED_57600:
comBaud = 57600;
break;
case OPLINKSETTINGS_COMSPEED_115200:
comBaud = 115200;
break;
}
if (PIOS_COM_TELEM_RF) {
PIOS_COM_ChangeBaud(PIOS_COM_TELEM_RF, comBaud);
}
// Set the frequency range.
PIOS_RFM22B_SetFrequencyRange(pios_rfm22b_id, min_frequency, max_frequency, channel_spacing);
}
#endif
/** /**
* @} * @}
* @} * @}

View File

@ -62,7 +62,7 @@ CFLAGS += -ffast-math
# Use file-extension c for "c-only"-files # Use file-extension c for "c-only"-files
ifndef TESTAPP ifndef TESTAPP
## Application Core ## Application Core
SRC += ${OPMODULEDIR}/System/systemmod.c SRC += $(OPMODULEDIR)/System/systemmod.c
SRC += $(OPSYSTEM)/revolution.c SRC += $(OPSYSTEM)/revolution.c
SRC += $(OPSYSTEM)/pios_board.c SRC += $(OPSYSTEM)/pios_board.c
SRC += $(OPSYSTEM)/pios_usb_board_data.c SRC += $(OPSYSTEM)/pios_usb_board_data.c

View File

@ -410,6 +410,19 @@ static const struct pios_tim_channel pios_tim_ppm_flexi_port = {
.remap = GPIO_PartialRemap2_TIM2, .remap = GPIO_PartialRemap2_TIM2,
}; };
static const struct pios_tim_channel pios_tim_ppm_main_port = {
.timer = TIM1,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Mode = GPIO_Mode_IPD,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
};
#endif /* PIOS_INCLUDE_TIM */ #endif /* PIOS_INCLUDE_TIM */
#if defined(PIOS_INCLUDE_USART) #if defined(PIOS_INCLUDE_USART)
@ -541,7 +554,7 @@ void PIOS_RTC_IRQ_Handler (void)
#if defined(PIOS_INCLUDE_PPM) #if defined(PIOS_INCLUDE_PPM)
#include <pios_ppm_priv.h> #include <pios_ppm_priv.h>
const struct pios_ppm_cfg pios_ppm_cfg = { const struct pios_ppm_cfg pios_ppm_flexi_cfg = {
.tim_ic_init = { .tim_ic_init = {
.TIM_ICPolarity = TIM_ICPolarity_Rising, .TIM_ICPolarity = TIM_ICPolarity_Rising,
.TIM_ICSelection = TIM_ICSelection_DirectTI, .TIM_ICSelection = TIM_ICSelection_DirectTI,
@ -552,6 +565,17 @@ const struct pios_ppm_cfg pios_ppm_cfg = {
.num_channels = 1, .num_channels = 1,
}; };
const struct pios_ppm_cfg pios_ppm_main_cfg = {
.tim_ic_init = {
.TIM_ICPolarity = TIM_ICPolarity_Rising,
.TIM_ICSelection = TIM_ICSelection_DirectTI,
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
.TIM_ICFilter = 0x0,
},
.channels = &pios_tim_ppm_main_port,
.num_channels = 1,
};
#endif /* PIOS_INCLUDE_PPM */ #endif /* PIOS_INCLUDE_PPM */
/* /*

View File

@ -75,6 +75,56 @@ static const struct pios_led pios_leds_v2[] = {
}, },
}, },
}, },
#ifdef PIOS_RFM22B_DEBUG_ON_SERVO
[PIOS_LED_D1] = {
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_13,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
},
[PIOS_LED_D2] = {
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_14,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
},
[PIOS_LED_D3] = {
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
},
[PIOS_LED_D4] = {
.pin = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
},
#endif
}; };
static const struct pios_led_cfg pios_led_v2_cfg = { static const struct pios_led_cfg pios_led_v2_cfg = {

View File

@ -16,7 +16,7 @@
<IPconnection> <IPconnection>
<Current> <Current>
<arr_1> <arr_1>
<Port>1</Port> <Port>9000</Port>
<UseTCP>0</UseTCP> <UseTCP>0</UseTCP>
</arr_1> </arr_1>
<size>1</size> <size>1</size>

View File

@ -13,6 +13,15 @@
<StyleSheet>default</StyleSheet> <StyleSheet>default</StyleSheet>
<UDPMirror>false</UDPMirror> <UDPMirror>false</UDPMirror>
</General> </General>
<IPconnection>
<Current>
<arr_1>
<Port>9000</Port>
<UseTCP>0</UseTCP>
</arr_1>
<size>1</size>
</Current>
</IPconnection>
<KeyBindings> <KeyBindings>
<size>0</size> <size>0</size>
</KeyBindings> </KeyBindings>

View File

@ -13,6 +13,15 @@
<StyleSheet>default</StyleSheet> <StyleSheet>default</StyleSheet>
<UDPMirror>false</UDPMirror> <UDPMirror>false</UDPMirror>
</General> </General>
<IPconnection>
<Current>
<arr_1>
<Port>9000</Port>
<UseTCP>0</UseTCP>
</arr_1>
<size>1</size>
</Current>
</IPconnection>
<KeyBindings> <KeyBindings>
<size>0</size> <size>0</size>
</KeyBindings> </KeyBindings>

View File

@ -28,7 +28,7 @@
#define LKS94PROJECTION_H #define LKS94PROJECTION_H
#include <QVector> #include <QVector>
#include "cmath" #include "cmath"
#include "../pureprojection.h" #include <opmapcontrol/src/internals/pureprojection.h>
namespace projections { namespace projections {

View File

@ -27,6 +27,7 @@
#include "configpipxtremewidget.h" #include "configpipxtremewidget.h"
#include <coreplugin/generalsettings.h>
#include <oplinksettings.h> #include <oplinksettings.h>
#include <oplinkstatus.h> #include <oplinkstatus.h>
@ -46,28 +47,28 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
} }
// Connect to the OPLinkSettings object updates // Connect to the OPLinkSettings object updates
oplinkSettingsObj = dynamic_cast<UAVDataObject*>(objManager->getObject("OPLinkSettings")); oplinkSettingsObj = dynamic_cast<OPLinkSettings*>(objManager->getObject("OPLinkSettings"));
if (oplinkSettingsObj != NULL ) { if (oplinkSettingsObj != NULL ) {
connect(oplinkSettingsObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateSettings(UAVObject*))); connect(oplinkSettingsObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateSettings(UAVObject*)));
} else { } else {
qDebug() << "Error: Object is unknown (OPLinkSettings)."; qDebug() << "Error: Object is unknown (OPLinkSettings).";
} }
autoLoadWidgets(); autoLoadWidgets();
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_oplink->Apply->setVisible(false);
addApplySaveButtons(m_oplink->Apply, m_oplink->Save); addApplySaveButtons(m_oplink->Apply, m_oplink->Save);
addUAVObjectToWidgetRelation("OPLinkSettings", "Coordinator", m_oplink->Coordinator); addUAVObjectToWidgetRelation("OPLinkSettings", "MainPort", m_oplink->MainPort);
addUAVObjectToWidgetRelation("OPLinkSettings", "UAVTalk", m_oplink->UAVTalk); addUAVObjectToWidgetRelation("OPLinkSettings", "FlexiPort", m_oplink->FlexiPort);
addUAVObjectToWidgetRelation("OPLinkSettings", "PPM", m_oplink->PPM); addUAVObjectToWidgetRelation("OPLinkSettings", "VCPPort", m_oplink->VCPPort);
addUAVObjectToWidgetRelation("OPLinkSettings", "InputConnection", m_oplink->InputConnection);
addUAVObjectToWidgetRelation("OPLinkSettings", "OutputConnection", m_oplink->OutputConnection);
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower); addUAVObjectToWidgetRelation("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
addUAVObjectToWidgetRelation("OPLinkSettings", "SendTimeout", m_oplink->SendTimeout); addUAVObjectToWidgetRelation("OPLinkSettings", "MinFrequency", m_oplink->MinimumFrequency);
addUAVObjectToWidgetRelation("OPLinkSettings", "MinPacketSize", m_oplink->MinPacketSize); addUAVObjectToWidgetRelation("OPLinkSettings", "MaxFrequency", m_oplink->MaximumFrequency);
addUAVObjectToWidgetRelation("OPLinkSettings", "FrequencyCalibration", m_oplink->FrequencyCalibration); addUAVObjectToWidgetRelation("OPLinkSettings", "InitFrequency", m_oplink->InitFrequency);
addUAVObjectToWidgetRelation("OPLinkSettings", "MinFrequency", m_oplink->MinFrequency); addUAVObjectToWidgetRelation("OPLinkSettings", "ChannelSpacing", m_oplink->StepSize);
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxFrequency", m_oplink->MaxFrequency);
addUAVObjectToWidgetRelation("OPLinkStatus", "DeviceID", m_oplink->DeviceID);
addUAVObjectToWidgetRelation("OPLinkStatus", "RxGood", m_oplink->Good); addUAVObjectToWidgetRelation("OPLinkStatus", "RxGood", m_oplink->Good);
addUAVObjectToWidgetRelation("OPLinkStatus", "RxCorrected", m_oplink->Corrected); addUAVObjectToWidgetRelation("OPLinkStatus", "RxCorrected", m_oplink->Corrected);
addUAVObjectToWidgetRelation("OPLinkStatus", "RxErrors", m_oplink->Errors); addUAVObjectToWidgetRelation("OPLinkStatus", "RxErrors", m_oplink->Errors);
@ -80,19 +81,89 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
addUAVObjectToWidgetRelation("OPLinkStatus", "Resets", m_oplink->Resets); addUAVObjectToWidgetRelation("OPLinkStatus", "Resets", m_oplink->Resets);
addUAVObjectToWidgetRelation("OPLinkStatus", "Timeouts", m_oplink->Timeouts); addUAVObjectToWidgetRelation("OPLinkStatus", "Timeouts", m_oplink->Timeouts);
addUAVObjectToWidgetRelation("OPLinkStatus", "RSSI", m_oplink->RSSI); addUAVObjectToWidgetRelation("OPLinkStatus", "RSSI", m_oplink->RSSI);
addUAVObjectToWidgetRelation("OPLinkStatus", "AFCCorrection", m_oplink->AFCCorrection); addUAVObjectToWidgetRelation("OPLinkStatus", "HeapRemaining", m_oplink->FreeHeap);
addUAVObjectToWidgetRelation("OPLinkStatus", "LinkQuality", m_oplink->LinkQuality); addUAVObjectToWidgetRelation("OPLinkStatus", "LinkQuality", m_oplink->LinkQuality);
addUAVObjectToWidgetRelation("OPLinkStatus", "RXSeq", m_oplink->RXSeq); addUAVObjectToWidgetRelation("OPLinkStatus", "RXSeq", m_oplink->RXSeq);
addUAVObjectToWidgetRelation("OPLinkStatus", "TXSeq", m_oplink->TXSeq); addUAVObjectToWidgetRelation("OPLinkStatus", "TXSeq", m_oplink->TXSeq);
addUAVObjectToWidgetRelation("OPLinkStatus", "RXRate", m_oplink->RXRate); addUAVObjectToWidgetRelation("OPLinkStatus", "RXRate", m_oplink->RXRate);
addUAVObjectToWidgetRelation("OPLinkStatus", "TXRate", m_oplink->TXRate); addUAVObjectToWidgetRelation("OPLinkStatus", "TXRate", m_oplink->TXRate);
// Connect to the pair ID radio buttons. signalMapperAddBinding = new QSignalMapper(this);
connect(m_oplink->PairSelectB, SIGNAL(toggled(bool)), this, SLOT(pairBToggled(bool))); signalMapperRemBinding = new QSignalMapper(this);
connect(m_oplink->PairSelect1, SIGNAL(toggled(bool)), this, SLOT(pair1Toggled(bool))); connect(m_oplink->BindingAdd_1, SIGNAL(clicked()), signalMapperAddBinding, SLOT(map()));
connect(m_oplink->PairSelect2, SIGNAL(toggled(bool)), this, SLOT(pair2Toggled(bool))); signalMapperAddBinding->setMapping(m_oplink->BindingAdd_1, (QWidget*)(m_oplink->BindingID_1));
connect(m_oplink->PairSelect3, SIGNAL(toggled(bool)), this, SLOT(pair3Toggled(bool))); connect(m_oplink->BindingRemove_1, SIGNAL(clicked()), signalMapperRemBinding, SLOT(map()));
connect(m_oplink->PairSelect4, SIGNAL(toggled(bool)), this, SLOT(pair4Toggled(bool))); signalMapperRemBinding->setMapping(m_oplink->BindingRemove_1, (QWidget*)(m_oplink->BindingID_1));
addUAVObjectToWidgetRelation("OPLinkSettings", "Bindings", m_oplink->BindingID_1, "0");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteMainPort", m_oplink->RemoteMainPort_1, "0");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteFlexiPort", m_oplink->RemoteFlexiPort_1, "0");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteVCPPort", m_oplink->RemoteVCPPort_1, "0");
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed_1, "0");
connect(m_oplink->BindingAdd_2, SIGNAL(clicked()), signalMapperAddBinding, SLOT(map()));
signalMapperAddBinding->setMapping(m_oplink->BindingAdd_2, (QWidget*)(m_oplink->BindingID_2));
connect(m_oplink->BindingRemove_2, SIGNAL(clicked()), signalMapperRemBinding, SLOT(map()));
signalMapperRemBinding->setMapping(m_oplink->BindingRemove_2, (QWidget*)(m_oplink->BindingID_2));
addUAVObjectToWidgetRelation("OPLinkSettings", "Bindings", m_oplink->BindingID_2, "1");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteMainPort", m_oplink->RemoteMainPort_2, "1");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteFlexiPort", m_oplink->RemoteFlexiPort_2, "1");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteVCPPort", m_oplink->RemoteVCPPort_2, "1");
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed_2, "1");
connect(m_oplink->BindingAdd_3, SIGNAL(clicked()), signalMapperAddBinding, SLOT(map()));
signalMapperAddBinding->setMapping(m_oplink->BindingAdd_3, (QWidget*)(m_oplink->BindingID_3));
connect(m_oplink->BindingRemove_3, SIGNAL(clicked()), signalMapperRemBinding, SLOT(map()));
signalMapperRemBinding->setMapping(m_oplink->BindingRemove_3, (QWidget*)(m_oplink->BindingID_3));
addUAVObjectToWidgetRelation("OPLinkSettings", "Bindings", m_oplink->BindingID_3, "2");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteMainPort", m_oplink->RemoteMainPort_3, "2");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteFlexiPort", m_oplink->RemoteFlexiPort_3, "2");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteVCPPort", m_oplink->RemoteVCPPort_3, "2");
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed_3, "2");
connect(m_oplink->BindingAdd_4, SIGNAL(clicked()), signalMapperAddBinding, SLOT(map()));
signalMapperAddBinding->setMapping(m_oplink->BindingAdd_4, (QWidget*)(m_oplink->BindingID_4));
connect(m_oplink->BindingRemove_4, SIGNAL(clicked()), signalMapperRemBinding, SLOT(map()));
signalMapperRemBinding->setMapping(m_oplink->BindingRemove_4, (QWidget*)(m_oplink->BindingID_4));
addUAVObjectToWidgetRelation("OPLinkSettings", "Bindings", m_oplink->BindingID_4, "3");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteMainPort", m_oplink->RemoteMainPort_4, "3");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteFlexiPort", m_oplink->RemoteFlexiPort_4, "3");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteVCPPort", m_oplink->RemoteVCPPort_4, "3");
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed_4, "3");
connect(m_oplink->BindingAdd_5, SIGNAL(clicked()), signalMapperAddBinding, SLOT(map()));
signalMapperAddBinding->setMapping(m_oplink->BindingAdd_5, (QWidget*)(m_oplink->BindingID_5));
connect(m_oplink->BindingRemove_5, SIGNAL(clicked()), signalMapperRemBinding, SLOT(map()));
signalMapperRemBinding->setMapping(m_oplink->BindingRemove_5, (QWidget*)(m_oplink->BindingID_5));
addUAVObjectToWidgetRelation("OPLinkSettings", "Bindings", m_oplink->BindingID_5, "4");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteMainPort", m_oplink->RemoteMainPort_5, "4");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteFlexiPort", m_oplink->RemoteFlexiPort_5, "4");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteVCPPort", m_oplink->RemoteVCPPort_5, "4");
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed_5, "4");
connect(m_oplink->BindingAdd_6, SIGNAL(clicked()), signalMapperAddBinding, SLOT(map()));
signalMapperAddBinding->setMapping(m_oplink->BindingAdd_6, (QWidget*)(m_oplink->BindingID_6));
connect(m_oplink->BindingRemove_6, SIGNAL(clicked()), signalMapperRemBinding, SLOT(map()));
signalMapperRemBinding->setMapping(m_oplink->BindingRemove_6, (QWidget*)(m_oplink->BindingID_6));
addUAVObjectToWidgetRelation("OPLinkSettings", "Bindings", m_oplink->BindingID_6, "5");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteMainPort", m_oplink->RemoteMainPort_6, "5");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteFlexiPort", m_oplink->RemoteFlexiPort_6, "5");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteVCPPort", m_oplink->RemoteVCPPort_6, "5");
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed_6, "5");
connect(m_oplink->BindingAdd_7, SIGNAL(clicked()), signalMapperAddBinding, SLOT(map()));
signalMapperAddBinding->setMapping(m_oplink->BindingAdd_7, (QWidget*)(m_oplink->BindingID_7));
connect(m_oplink->BindingRemove_7, SIGNAL(clicked()), signalMapperRemBinding, SLOT(map()));
signalMapperRemBinding->setMapping(m_oplink->BindingRemove_7, (QWidget*)(m_oplink->BindingID_7));
addUAVObjectToWidgetRelation("OPLinkSettings", "Bindings", m_oplink->BindingID_7, "6");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteMainPort", m_oplink->RemoteMainPort_7, "6");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteFlexiPort", m_oplink->RemoteFlexiPort_7, "6");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteVCPPort", m_oplink->RemoteVCPPort_7, "6");
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed_7, "6");
connect(m_oplink->BindingAdd_8, SIGNAL(clicked()), signalMapperAddBinding, SLOT(map()));
signalMapperAddBinding->setMapping(m_oplink->BindingAdd_8, (QWidget*)(m_oplink->BindingID_8));
connect(m_oplink->BindingRemove_8, SIGNAL(clicked()), signalMapperRemBinding, SLOT(map()));
signalMapperRemBinding->setMapping(m_oplink->BindingRemove_8, (QWidget*)(m_oplink->BindingID_8));
addUAVObjectToWidgetRelation("OPLinkSettings", "Bindings", m_oplink->BindingID_8, "7");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteMainPort", m_oplink->RemoteMainPort_8, "7");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteFlexiPort", m_oplink->RemoteFlexiPort_8, "7");
addUAVObjectToWidgetRelation("OPLinkSettings", "RemoteVCPPort", m_oplink->RemoteVCPPort_8, "7");
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed_8, "7");
connect(signalMapperAddBinding, SIGNAL(mapped(QWidget *)), this, SLOT(addBinding(QWidget *)));
connect(signalMapperRemBinding, SIGNAL(mapped(QWidget *)), this, SLOT(removeBinding(QWidget *)));
//Add scroll bar when necessary //Add scroll bar when necessary
QScrollArea *scroll = new QScrollArea; QScrollArea *scroll = new QScrollArea;
@ -108,38 +179,8 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
ConfigPipXtremeWidget::~ConfigPipXtremeWidget() ConfigPipXtremeWidget::~ConfigPipXtremeWidget()
{ {
// Do nothing delete signalMapperAddBinding;
} delete signalMapperRemBinding;
void ConfigPipXtremeWidget::refreshValues()
{
}
void ConfigPipXtremeWidget::applySettings()
{
OPLinkSettings *oplinkSettings = OPLinkSettings::GetInstance(getObjectManager());
OPLinkSettings::DataFields oplinkSettingsData = oplinkSettings->getData();
// Get the pair ID.
quint32 pairID = 0;
bool okay;
if (m_oplink->PairSelect1->isChecked())
pairID = m_oplink->PairID1->text().toUInt(&okay, 16);
else if (m_oplink->PairSelect2->isChecked())
pairID = m_oplink->PairID2->text().toUInt(&okay, 16);
else if (m_oplink->PairSelect3->isChecked())
pairID = m_oplink->PairID3->text().toUInt(&okay, 16);
else if (m_oplink->PairSelect4->isChecked())
pairID = m_oplink->PairID4->text().toUInt(&okay, 16);
oplinkSettingsData.PairID = pairID;
oplinkSettings->setData(oplinkSettingsData);
}
void ConfigPipXtremeWidget::saveSettings()
{
//applySettings();
UAVObject *obj = OPLinkSettings::GetInstance(getObjectManager());
saveObjectToSD(obj);
} }
/*! /*!
@ -152,34 +193,24 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
if (!settingsUpdated) if (!settingsUpdated)
oplinkSettingsObj->requestUpdate(); oplinkSettingsObj->requestUpdate();
// Get the current pairID
OPLinkSettings *oplinkSettings = OPLinkSettings::GetInstance(getObjectManager());
quint32 pairID = 0;
if (oplinkSettings)
pairID = oplinkSettings->getPairID();
// Update the detected devices. // Update the detected devices.
UAVObjectField* pairIdField = object->getField("PairIDs"); UAVObjectField* pairIdField = object->getField("PairIDs");
if (pairIdField) { if (pairIdField) {
quint32 pairid1 = pairIdField->getValue(0).toUInt(); quint32 pairid1 = pairIdField->getValue(0).toUInt();
m_oplink->PairID1->setText(QString::number(pairid1, 16).toUpper()); m_oplink->PairID1->setText(QString::number(pairid1, 16).toUpper());
m_oplink->PairID1->setEnabled(false); m_oplink->PairID1->setEnabled(false);
m_oplink->PairSelect1->setChecked(pairID && (pairID == pairid1));
m_oplink->PairSelect1->setEnabled(pairid1); m_oplink->PairSelect1->setEnabled(pairid1);
quint32 pairid2 = pairIdField->getValue(1).toUInt(); quint32 pairid2 = pairIdField->getValue(1).toUInt();
m_oplink->PairID2->setText(QString::number(pairIdField->getValue(1).toUInt(), 16).toUpper()); m_oplink->PairID2->setText(QString::number(pairIdField->getValue(1).toUInt(), 16).toUpper());
m_oplink->PairID2->setEnabled(false); m_oplink->PairID2->setEnabled(false);
m_oplink->PairSelect2->setChecked(pairID && (pairID == pairid2));
m_oplink->PairSelect2->setEnabled(pairid2); m_oplink->PairSelect2->setEnabled(pairid2);
quint32 pairid3 = pairIdField->getValue(2).toUInt(); quint32 pairid3 = pairIdField->getValue(2).toUInt();
m_oplink->PairID3->setText(QString::number(pairIdField->getValue(2).toUInt(), 16).toUpper()); m_oplink->PairID3->setText(QString::number(pairIdField->getValue(2).toUInt(), 16).toUpper());
m_oplink->PairID3->setEnabled(false); m_oplink->PairID3->setEnabled(false);
m_oplink->PairSelect3->setChecked(pairID && (pairID == pairid3));
m_oplink->PairSelect3->setEnabled(pairid3); m_oplink->PairSelect3->setEnabled(pairid3);
quint32 pairid4 = pairIdField->getValue(3).toUInt(); quint32 pairid4 = pairIdField->getValue(3).toUInt();
m_oplink->PairID4->setText(QString::number(pairIdField->getValue(3).toUInt(), 16).toUpper()); m_oplink->PairID4->setText(QString::number(pairIdField->getValue(3).toUInt(), 16).toUpper());
m_oplink->PairID4->setEnabled(false); m_oplink->PairID4->setEnabled(false);
m_oplink->PairSelect4->setChecked(pairID && (pairID == pairid4));
m_oplink->PairSelect4->setEnabled(pairid4); m_oplink->PairSelect4->setEnabled(pairid4);
} else { } else {
qDebug() << "PipXtremeGadgetWidget: Count not read PairID field."; qDebug() << "PipXtremeGadgetWidget: Count not read PairID field.";
@ -245,17 +276,6 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
qDebug() << "PipXtremeGadgetWidget: Count not read Description field."; qDebug() << "PipXtremeGadgetWidget: Count not read Description field.";
} }
// Update the DeviceID field
UAVObjectField* idField = object->getField("DeviceID");
if (idField) {
m_oplink->DeviceID->setText(QString::number(idField->getValue().toUInt(), 16).toUpper());
} else {
qDebug() << "PipXtremeGadgetWidget: Count not read DeviceID field.";
}
// Update the PairID field
m_oplink->PairID->setText(QString::number(pairID, 16).toUpper());
// Update the link state // Update the link state
UAVObjectField* linkField = object->getField("LinkState"); UAVObjectField* linkField = object->getField("LinkState");
if (linkField) { if (linkField) {
@ -270,13 +290,13 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
*/ */
void ConfigPipXtremeWidget::updateSettings(UAVObject *object) void ConfigPipXtremeWidget::updateSettings(UAVObject *object)
{ {
Q_UNUSED(object); Q_UNUSED(object);
if (!settingsUpdated) if (!settingsUpdated)
{ {
settingsUpdated = true; settingsUpdated = true;
enableControls(true); enableControls(true);
} }
} }
void ConfigPipXtremeWidget::disconnected() void ConfigPipXtremeWidget::disconnected()
@ -288,52 +308,32 @@ void ConfigPipXtremeWidget::disconnected()
} }
} }
void ConfigPipXtremeWidget::pairIDToggled(bool checked, quint8 idx) void ConfigPipXtremeWidget::addBinding(QWidget *w)
{ {
if(checked) if(QLineEdit *le = qobject_cast<QLineEdit *>(w)) {
{
OPLinkStatus *oplinkStatus = OPLinkStatus::GetInstance(getObjectManager());
OPLinkSettings *oplinkSettings = OPLinkSettings::GetInstance(getObjectManager());
if (oplinkStatus && oplinkSettings) // Get the pair ID out of the selection widget
{ quint32 pairID = 0;
if (idx == 4) bool okay;
{ if (m_oplink->PairSelect1->isChecked())
oplinkSettings->setPairID(0); pairID = m_oplink->PairID1->text().toUInt(&okay, 16);
} else if (m_oplink->PairSelect2->isChecked())
else pairID = m_oplink->PairID2->text().toUInt(&okay, 16);
{ else if (m_oplink->PairSelect3->isChecked())
quint32 pairID = oplinkStatus->getPairIDs(idx); pairID = m_oplink->PairID3->text().toUInt(&okay, 16);
if (pairID) else if (m_oplink->PairSelect4->isChecked())
oplinkSettings->setPairID(pairID); pairID = m_oplink->PairID4->text().toUInt(&okay, 16);
}
} // Store the ID in the first open slot (or the last slot if all are full).
} le->setText(QString::number(pairID, 16).toUpper());
}
} }
void ConfigPipXtremeWidget::pair1Toggled(bool checked) void ConfigPipXtremeWidget::removeBinding(QWidget *w)
{ {
pairIDToggled(checked, 0); if(QLineEdit *le = qobject_cast<QLineEdit *>(w)) {
} le->setText(QString::number(0, 16).toUpper());
}
void ConfigPipXtremeWidget::pair2Toggled(bool checked)
{
pairIDToggled(checked, 1);
}
void ConfigPipXtremeWidget::pair3Toggled(bool checked)
{
pairIDToggled(checked, 2);
}
void ConfigPipXtremeWidget::pair4Toggled(bool checked)
{
pairIDToggled(checked, 3);
}
void ConfigPipXtremeWidget::pairBToggled(bool checked)
{
pairIDToggled(checked, 4);
} }
/** /**

View File

@ -27,6 +27,8 @@
#ifndef CONFIGPIPXTREMEWIDGET_H #ifndef CONFIGPIPXTREMEWIDGET_H
#define CONFIGPIPXTREMEWIDGET_H #define CONFIGPIPXTREMEWIDGET_H
#include <oplinksettings.h>
#include "ui_pipxtreme.h" #include "ui_pipxtreme.h"
#include "configtaskwidget.h" #include "configtaskwidget.h"
@ -46,24 +48,22 @@ private:
Ui_PipXtremeWidget *m_oplink; Ui_PipXtremeWidget *m_oplink;
// The OPLink status UAVObject // The OPLink status UAVObject
UAVDataObject* oplinkStatusObj; UAVDataObject *oplinkStatusObj;
// The OPLink ssettins UAVObject // The OPLink ssettins UAVObject
UAVDataObject* oplinkSettingsObj; OPLinkSettings* oplinkSettingsObj;
// Are the settings current?
bool settingsUpdated; bool settingsUpdated;
// Signal mappers to add arguments to signals.
QSignalMapper *signalMapperAddBinding;
QSignalMapper *signalMapperRemBinding;
private slots: private slots:
void refreshValues();
void applySettings();
void saveSettings();
void disconnected(); void disconnected();
void pairIDToggled(bool checked, quint8 idx); void addBinding(QWidget *w);
void pair1Toggled(bool checked); void removeBinding(QWidget *w);
void pair2Toggled(bool checked);
void pair3Toggled(bool checked);
void pair4Toggled(bool checked);
void pairBToggled(bool checked);
}; };
#endif // CONFIGTXPIDWIDGET_H #endif // CONFIGTXPIDWIDGET_H

View File

@ -64,7 +64,9 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
addUAVObjectToWidgetRelation("HwSettings","GPSSpeed",m_ui->cbMainGPSSpeed); addUAVObjectToWidgetRelation("HwSettings","GPSSpeed",m_ui->cbMainGPSSpeed);
addUAVObjectToWidgetRelation("HwSettings","ComUsbBridgeSpeed",m_ui->cbMainComSpeed); addUAVObjectToWidgetRelation("HwSettings","ComUsbBridgeSpeed",m_ui->cbMainComSpeed);
addUAVObjectToWidgetRelation("HwSettings","RadioPort",m_ui->cbModem); addUAVObjectToWidgetRelation("HwSettings", "RadioPort", m_ui->cbModem);
addUAVObjectToWidgetRelation("HwSettings", "MaxRFPower", m_ui->cbTxPower);
addUAVObjectToWidgetRelation("HwSettings", "DefaultFrequency", m_ui->leInitFreq);
connect(m_ui->cchwHelp,SIGNAL(clicked()),this,SLOT(openHelp())); connect(m_ui->cchwHelp,SIGNAL(clicked()),this,SLOT(openHelp()));
@ -101,6 +103,7 @@ void ConfigRevoHWWidget::refreshWidgetsValues(UAVObject *obj)
usbVCPPortChanged(0); usbVCPPortChanged(0);
mainPortChanged(0); mainPortChanged(0);
flexiPortChanged(0); flexiPortChanged(0);
modemPortChanged(0);
} }
void ConfigRevoHWWidget::updateObjectsFromWidgets() void ConfigRevoHWWidget::updateObjectsFromWidgets()
@ -288,6 +291,15 @@ void ConfigRevoHWWidget::modemPortChanged(int index)
if(m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) { if(m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED); m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
} }
m_ui->lblTxPower->setVisible(true);
m_ui->cbTxPower->setVisible(true);
m_ui->lblInitFreq->setVisible(true);
m_ui->leInitFreq->setVisible(true);
} else {
m_ui->lblTxPower->setVisible(false);
m_ui->cbTxPower->setVisible(false);
m_ui->lblInitFreq->setVisible(false);
m_ui->leInitFreq->setVisible(false);
} }
} }

View File

@ -169,9 +169,6 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="13" column="2">
<widget class="QComboBox" name="cbModem"/>
</item>
<item row="3" column="0"> <item row="3" column="0">
<widget class="QComboBox" name="cbRcvr"/> <widget class="QComboBox" name="cbRcvr"/>
</item> </item>
@ -375,6 +372,39 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="13" column="2">
<widget class="QComboBox" name="cbModem"/>
</item>
<item row="14" column="2">
<widget class="QLabel" name="lblTxPower">
<property name="text">
<string>Max Tx Power (mW)</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="15" column="2">
<widget class="QComboBox" name="cbTxPower"/>
</item>
<item row="16" column="2">
<widget class="QLabel" name="lblInitFreq">
<property name="text">
<string>Initial Frequency (Hz)</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="17" column="2">
<widget class="QLineEdit" name="leInitFreq">
<property name="toolTip">
<string extracomment="The initial connection frequency (Hz)"/>
</property>
</widget>
</item>
<item row="14" column="1"> <item row="14" column="1">
<widget class="QLabel" name="lblFlexiSpeed"> <widget class="QLabel" name="lblFlexiSpeed">
<property name="text"> <property name="text">

View File

@ -23,36 +23,10 @@
<enum>QFrame::Raised</enum> <enum>QFrame::Raised</enum>
</property> </property>
<layout class="QGridLayout" name="gridLayout"> <layout class="QGridLayout" name="gridLayout">
<item row="1" column="0" colspan="2"> <item row="4" column="0" colspan="2">
<layout class="QHBoxLayout" name="horizontalLayout_12"> <layout class="QHBoxLayout" name="horizontalLayout_12"/>
<item>
<widget class="QGraphicsView" name="graphicsView_Spectrum">
<property name="backgroundBrush">
<brush brushstyle="NoBrush">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</property>
<property name="foregroundBrush">
<brush brushstyle="NoBrush">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</property>
<property name="interactive">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item> </item>
<item row="2" column="0" colspan="2"> <item row="5" column="0" colspan="2">
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QVBoxLayout" name="verticalLayout">
<item> <item>
<widget class="QLabel" name="message"> <widget class="QLabel" name="message">
@ -139,235 +113,15 @@
</item> </item>
</layout> </layout>
</item> </item>
<item row="0" column="0"> <item row="2" column="0" colspan="2">
<widget class="QFrame" name="frame_2"> <widget class="QFrame" name="frame_4">
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::StyledPanel</enum> <enum>QFrame::StyledPanel</enum>
</property> </property>
<property name="frameShadow"> <property name="frameShadow">
<enum>QFrame::Raised</enum> <enum>QFrame::Raised</enum>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_2"> <layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QGroupBox" name="groupBox_2">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="title">
<string>Pairing</string>
</property>
<layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="0">
<widget class="QRadioButton" name="PairSelectB">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="PairIDB">
<property name="enabled">
<bool>false</bool>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>Broadcast</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="PaidIDBLabel">
<property name="text">
<string>Broadcast Address</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QRadioButton" name="PairSelect1">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="PairID1">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="placeholderText">
<string>12345678</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar1">
<property name="minimum">
<number>-127</number>
</property>
<property name="maximum">
<number>0</number>
</property>
<property name="value">
<number>-127</number>
</property>
<property name="textVisible">
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel1">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QRadioButton" name="PairSelect2">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLineEdit" name="PairID2">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar2">
<property name="minimum">
<number>-127</number>
</property>
<property name="maximum">
<number>0</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="textVisible">
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel2">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QRadioButton" name="PairSelect3">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QLineEdit" name="PairID3">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar3">
<property name="minimum">
<number>-127</number>
</property>
<property name="maximum">
<number>0</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="textVisible">
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel3">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QRadioButton" name="PairSelect4">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QLineEdit" name="PairID4">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar4">
<property name="minimum">
<number>-127</number>
</property>
<property name="maximum">
<number>0</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="textVisible">
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel4">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item> <item>
<widget class="QGroupBox" name="groupBox_3"> <widget class="QGroupBox" name="groupBox_3">
<property name="minimumSize"> <property name="minimumSize">
@ -418,13 +172,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="frame"> <property name="frame">
<bool>false</bool> <bool>false</bool>
@ -479,13 +233,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="frame"> <property name="frame">
<bool>true</bool> <bool>true</bool>
@ -498,7 +252,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="0"> <item row="0" column="4">
<widget class="QLabel" name="DeviceIDLabel"> <widget class="QLabel" name="DeviceIDLabel">
<property name="text"> <property name="text">
<string>Device ID</string> <string>Device ID</string>
@ -508,7 +262,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="1"> <item row="0" column="5">
<widget class="QLineEdit" name="DeviceID"> <widget class="QLineEdit" name="DeviceID">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -530,13 +284,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="frame"> <property name="frame">
<bool>false</bool> <bool>false</bool>
@ -552,55 +306,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="0"> <item row="0" column="6">
<widget class="QLabel" name="PairIDLabel">
<property name="text">
<string>Pair ID</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QLineEdit" name="PairID">
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="placeholderText">
<string>90ABCDEF</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_11"> <widget class="QLabel" name="label_11">
<property name="text"> <property name="text">
<string>Link State</string> <string>Link State</string>
@ -610,7 +316,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="4" column="1"> <item row="0" column="7">
<widget class="QLineEdit" name="LinkState"> <widget class="QLineEdit" name="LinkState">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed"> <sizepolicy hsizetype="Expanding" vsizetype="Fixed">
@ -641,13 +347,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 3px; padding: 0 3px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set> <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
@ -660,7 +366,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="0"> <item row="1" column="4">
<widget class="QLabel" name="LinkQualityLabel"> <widget class="QLabel" name="LinkQualityLabel">
<property name="text"> <property name="text">
<string>Link Quality</string> <string>Link Quality</string>
@ -670,7 +376,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="1"> <item row="1" column="5">
<widget class="QLineEdit" name="LinkQuality"> <widget class="QLineEdit" name="LinkQuality">
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
@ -686,13 +392,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="frame"> <property name="frame">
<bool>false</bool> <bool>false</bool>
@ -702,7 +408,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="6" column="0"> <item row="1" column="6">
<widget class="QLabel" name="RSSILabel"> <widget class="QLabel" name="RSSILabel">
<property name="text"> <property name="text">
<string>RSSI</string> <string>RSSI</string>
@ -712,7 +418,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="6" column="1"> <item row="1" column="7">
<widget class="QLineEdit" name="RSSI"> <widget class="QLineEdit" name="RSSI">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -734,59 +440,20 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
</property> </property>
</widget> </widget>
</item> </item>
<item row="7" column="0"> <item row="2" column="4">
<widget class="QLabel" name="RxAFCLabel">
<property name="text">
<string>AFC Corr.</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QLineEdit" name="AFCCorrection">
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="8" column="0">
<widget class="QLabel" name="TXSeqLabel"> <widget class="QLabel" name="TXSeqLabel">
<property name="text"> <property name="text">
<string>TX Seq. No.</string> <string>TX Seq. No.</string>
@ -796,7 +463,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="8" column="1"> <item row="2" column="5">
<widget class="QLineEdit" name="TXSeq"> <widget class="QLineEdit" name="TXSeq">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -818,13 +485,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="frame"> <property name="frame">
<bool>false</bool> <bool>false</bool>
@ -834,7 +501,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="9" column="0"> <item row="2" column="6">
<widget class="QLabel" name="TXRateLabel"> <widget class="QLabel" name="TXRateLabel">
<property name="text"> <property name="text">
<string>TX Rate (B/s)</string> <string>TX Rate (B/s)</string>
@ -844,7 +511,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="9" column="1"> <item row="2" column="7">
<widget class="QLineEdit" name="TXRate"> <widget class="QLineEdit" name="TXRate">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -866,13 +533,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="frame"> <property name="frame">
<bool>false</bool> <bool>false</bool>
@ -882,7 +549,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="10" column="0"> <item row="3" column="4">
<widget class="QLabel" name="RXSeqLabel"> <widget class="QLabel" name="RXSeqLabel">
<property name="text"> <property name="text">
<string>RX Seq. No.</string> <string>RX Seq. No.</string>
@ -892,7 +559,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="10" column="1"> <item row="3" column="5">
<widget class="QLineEdit" name="RXSeq"> <widget class="QLineEdit" name="RXSeq">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -914,13 +581,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="frame"> <property name="frame">
<bool>false</bool> <bool>false</bool>
@ -930,7 +597,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="11" column="0"> <item row="3" column="6">
<widget class="QLabel" name="RXRateLabel"> <widget class="QLabel" name="RXRateLabel">
<property name="text"> <property name="text">
<string>RX Rate (B/s)</string> <string>RX Rate (B/s)</string>
@ -940,7 +607,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="11" column="1"> <item row="3" column="7">
<widget class="QLineEdit" name="RXRate"> <widget class="QLineEdit" name="RXRate">
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
@ -956,13 +623,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="frame"> <property name="frame">
<bool>false</bool> <bool>false</bool>
@ -972,7 +639,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="2"> <item row="2" column="0">
<widget class="QLabel" name="GoodLabel"> <widget class="QLabel" name="GoodLabel">
<property name="text"> <property name="text">
<string>RX Good</string> <string>RX Good</string>
@ -982,7 +649,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="3"> <item row="2" column="1">
<widget class="QLineEdit" name="Good"> <widget class="QLineEdit" name="Good">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -1013,13 +680,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set> <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
@ -1029,7 +696,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="2"> <item row="3" column="0">
<widget class="QLabel" name="CorrectedLabel"> <widget class="QLabel" name="CorrectedLabel">
<property name="text"> <property name="text">
<string>RX Corrected</string> <string>RX Corrected</string>
@ -1039,7 +706,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="3"> <item row="3" column="1">
<widget class="QLineEdit" name="Corrected"> <widget class="QLineEdit" name="Corrected">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -1070,13 +737,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set> <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
@ -1086,7 +753,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="4" column="2"> <item row="5" column="0">
<widget class="QLabel" name="ErrorsLabel"> <widget class="QLabel" name="ErrorsLabel">
<property name="text"> <property name="text">
<string>RX Errors</string> <string>RX Errors</string>
@ -1096,7 +763,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="4" column="3"> <item row="5" column="1">
<widget class="QLineEdit" name="Errors"> <widget class="QLineEdit" name="Errors">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -1121,13 +788,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set> <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
@ -1137,7 +804,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="2"> <item row="6" column="0">
<widget class="QLabel" name="MissedPacketsLabel"> <widget class="QLabel" name="MissedPacketsLabel">
<property name="text"> <property name="text">
<string>RX Missed</string> <string>RX Missed</string>
@ -1147,7 +814,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="3"> <item row="6" column="1">
<widget class="QLineEdit" name="Missed"> <widget class="QLineEdit" name="Missed">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -1178,13 +845,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set> <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
@ -1194,6 +861,321 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="2">
<widget class="QLabel" name="DroppedLabel">
<property name="text">
<string>TX Dropped</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QLineEdit" name="Dropped">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>The number of packets that were unable to be transmitted</string>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QLabel" name="ResentLabel">
<property name="text">
<string>TX Resent</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QLineEdit" name="Resent">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>The number of packets that were unable to be transmitted</string>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="5" column="2">
<widget class="QLabel" name="TxFailureLabel">
<property name="text">
<string>Tx Failure</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="5" column="3">
<widget class="QLineEdit" name="TxFailure">
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="5" column="4">
<widget class="QLabel" name="FreeHeapLabel">
<property name="text">
<string>Free Heap</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="5" column="5">
<widget class="QLineEdit" name="FreeHeap">
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="5" column="6">
<widget class="QLabel" name="UAVTalkErrorsLabel">
<property name="text">
<string>UAVTalk Errors</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="5" column="7">
<widget class="QLineEdit" name="UAVTalkErrors">
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="6" column="7">
<widget class="QLineEdit" name="Resets">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="6" column="6">
<widget class="QLabel" name="ResetsLabel">
<property name="text">
<string>Resets</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="6" column="5">
<widget class="QLineEdit" name="Timeouts">
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="6" column="4">
<widget class="QLabel" name="TimeoutsLabel">
<property name="text">
<string>Timeouts</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="6" column="2"> <item row="6" column="2">
<widget class="QLabel" name="RxFailureLabel"> <widget class="QLabel" name="RxFailureLabel">
<property name="text"> <property name="text">
@ -1235,13 +1217,13 @@
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QLineEdit { <string notr="true">QLineEdit {
border: none; border: none;
border-radius: 1px; border-radius: 1px;
padding: 0 4px; padding: 0 4px;
background: rgba(0, 0, 0, 16); background: rgba(0, 0, 0, 16);
/* background: transparent; */ /* background: transparent; */
/* selection-background-color: darkgray;*/ /* selection-background-color: darkgray;*/
}</string> }</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set> <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
@ -1251,288 +1233,1192 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="7" column="2">
<widget class="QLabel" name="DroppedLabel">
<property name="text">
<string>TX Dropped</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="7" column="3">
<widget class="QLineEdit" name="Dropped">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>The number of packets that were unable to be transmitted</string>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="8" column="2">
<widget class="QLabel" name="ResentLabel">
<property name="text">
<string>TX Resent</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="8" column="3">
<widget class="QLineEdit" name="Resent">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>The number of packets that were unable to be transmitted</string>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="9" column="2">
<widget class="QLabel" name="TxFailureLabel">
<property name="text">
<string>Tx Failure</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="9" column="3">
<widget class="QLineEdit" name="TxFailure">
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="10" column="2">
<widget class="QLabel" name="UAVTalkErrorsLabel">
<property name="text">
<string>UAVTalk Errors</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="10" column="3">
<widget class="QLineEdit" name="UAVTalkErrors">
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="11" column="2">
<widget class="QLabel" name="ResetsLabel">
<property name="text">
<string>Resets</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="11" column="3">
<widget class="QLineEdit" name="Resets">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="12" column="2">
<widget class="QLabel" name="TimeoutsLabel">
<property name="text">
<string>Timeouts</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="12" column="3">
<widget class="QLineEdit" name="Timeouts">
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout> </layout>
</widget> </widget>
</item> </item>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox_2">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="title">
<string>Remote Modems</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QFrame" name="PairingFrame">
<layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="0">
<widget class="QRadioButton" name="PairSelect1">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel4">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar4">
<property name="minimum">
<number>-127</number>
</property>
<property name="maximum">
<number>0</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="textVisible">
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel2">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="PairID2">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar2">
<property name="minimum">
<number>-127</number>
</property>
<property name="maximum">
<number>0</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="textVisible">
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel1">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar1">
<property name="minimum">
<number>-127</number>
</property>
<property name="maximum">
<number>0</number>
</property>
<property name="value">
<number>-127</number>
</property>
<property name="textVisible">
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QLineEdit" name="PairID4">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel3">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="PairID1">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="placeholderText">
<string>12345678</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QRadioButton" name="PairSelect3">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar3">
<property name="minimum">
<number>-127</number>
</property>
<property name="maximum">
<number>0</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="textVisible">
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QRadioButton" name="PairSelect2">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLineEdit" name="PairID3">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QRadioButton" name="PairSelect4">
<property name="text">
<string/>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="0" colspan="2">
<widget class="QGroupBox" name="groupBox_4">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="title">
<string>Bindings</string>
</property>
<layout class="QGridLayout" name="gridLayout_6">
<item row="0" column="0">
<widget class="QLabel" name="DeviceIDLabel_3">
<property name="text">
<string>Add</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="DeviceIDLabel_4">
<property name="text">
<string>Clear</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="DeviceIDLabel_2">
<property name="text">
<string>Device ID</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="RemoteMainPortLabel">
<property name="text">
<string>Main Port</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="RemoteFlexiPortLabel">
<property name="text">
<string>Flexi Port</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="5">
<widget class="QLabel" name="RemoteVCPPortLabel">
<property name="text">
<string>VCP Port</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="6">
<widget class="QLabel" name="ComSpeedLabel">
<property name="text">
<string>COM Speed</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="0" colspan="7">
<widget class="QScrollArea" name="scrollArea">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>757</width>
<height>244</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout_7">
<item row="0" column="0">
<widget class="QPushButton" name="BindingAdd_1">
<property name="text">
<string>Add &gt;&gt;</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QPushButton" name="BindingRemove_1">
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="BindingID_1">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="placeholderText">
<string>12345678</string>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QComboBox" name="RemoteMainPort_1">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote main port</string>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QComboBox" name="RemoteFlexiPort_1">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote flexi port</string>
</property>
</widget>
</item>
<item row="0" column="5">
<widget class="QComboBox" name="RemoteVCPPort_1">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote USB virtual com port</string>
</property>
</widget>
</item>
<item row="0" column="6">
<widget class="QComboBox" name="ComSpeed_1">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the telemetry port speed</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QPushButton" name="BindingAdd_2">
<property name="text">
<string>Add &gt;&gt;</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QPushButton" name="BindingRemove_2">
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="BindingID_2">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="placeholderText">
<string>12345678</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QComboBox" name="RemoteMainPort_2">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote main port</string>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QComboBox" name="RemoteFlexiPort_2">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote flexi port</string>
</property>
</widget>
</item>
<item row="1" column="5">
<widget class="QComboBox" name="RemoteVCPPort_2">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote USB virtual com port</string>
</property>
</widget>
</item>
<item row="1" column="6">
<widget class="QComboBox" name="ComSpeed_2">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the telemetry port speed</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QPushButton" name="BindingAdd_3">
<property name="text">
<string>Add &gt;&gt;</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QPushButton" name="BindingRemove_3">
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="BindingID_3">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="placeholderText">
<string>12345678</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QComboBox" name="RemoteMainPort_3">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote main port</string>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QComboBox" name="RemoteFlexiPort_3">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote flexi port</string>
</property>
</widget>
</item>
<item row="2" column="5">
<widget class="QComboBox" name="RemoteVCPPort_3">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote USB virtual com port</string>
</property>
</widget>
</item>
<item row="2" column="6">
<widget class="QComboBox" name="ComSpeed_3">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the telemetry port speed</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QPushButton" name="BindingAdd_4">
<property name="text">
<string>Add &gt;&gt;</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QPushButton" name="BindingRemove_4">
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QLineEdit" name="BindingID_4">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="placeholderText">
<string>12345678</string>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QComboBox" name="RemoteMainPort_4">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote main port</string>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QComboBox" name="RemoteFlexiPort_4">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote flexi port</string>
</property>
</widget>
</item>
<item row="3" column="5">
<widget class="QComboBox" name="RemoteVCPPort_4">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote USB virtual com port</string>
</property>
</widget>
</item>
<item row="3" column="6">
<widget class="QComboBox" name="ComSpeed_4">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the telemetry port speed</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QPushButton" name="BindingAdd_5">
<property name="text">
<string>Add &gt;&gt;</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QPushButton" name="BindingRemove_5">
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QLineEdit" name="BindingID_5">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="placeholderText">
<string>12345678</string>
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QComboBox" name="RemoteMainPort_5">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote main port</string>
</property>
</widget>
</item>
<item row="4" column="4">
<widget class="QComboBox" name="RemoteFlexiPort_5">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote flexi port</string>
</property>
</widget>
</item>
<item row="4" column="5">
<widget class="QComboBox" name="RemoteVCPPort_5">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote USB virtual com port</string>
</property>
</widget>
</item>
<item row="4" column="6">
<widget class="QComboBox" name="ComSpeed_5">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the telemetry port speed</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QPushButton" name="BindingAdd_6">
<property name="text">
<string>Add &gt;&gt;</string>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QPushButton" name="BindingRemove_6">
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="5" column="2">
<widget class="QLineEdit" name="BindingID_6">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="placeholderText">
<string>12345678</string>
</property>
</widget>
</item>
<item row="5" column="3">
<widget class="QComboBox" name="RemoteMainPort_6">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote main port</string>
</property>
</widget>
</item>
<item row="5" column="4">
<widget class="QComboBox" name="RemoteFlexiPort_6">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote flexi port</string>
</property>
</widget>
</item>
<item row="5" column="5">
<widget class="QComboBox" name="RemoteVCPPort_6">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote USB virtual com port</string>
</property>
</widget>
</item>
<item row="5" column="6">
<widget class="QComboBox" name="ComSpeed_6">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the telemetry port speed</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QPushButton" name="BindingAdd_7">
<property name="text">
<string>Add &gt;&gt;</string>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QPushButton" name="BindingRemove_7">
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="6" column="2">
<widget class="QLineEdit" name="BindingID_7">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="placeholderText">
<string>12345678</string>
</property>
</widget>
</item>
<item row="6" column="3">
<widget class="QComboBox" name="RemoteMainPort_7">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote main port</string>
</property>
</widget>
</item>
<item row="6" column="4">
<widget class="QComboBox" name="RemoteFlexiPort_7">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote flexi port</string>
</property>
</widget>
</item>
<item row="6" column="5">
<widget class="QComboBox" name="RemoteVCPPort_7">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote USB virtual com port</string>
</property>
</widget>
</item>
<item row="6" column="6">
<widget class="QComboBox" name="ComSpeed_7">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the telemetry port speed</string>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QPushButton" name="BindingAdd_8">
<property name="text">
<string>Add &gt;&gt;</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QPushButton" name="BindingRemove_8">
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="7" column="2">
<widget class="QLineEdit" name="BindingID_8">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>101</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 4px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="placeholderText">
<string>12345678</string>
</property>
</widget>
</item>
<item row="7" column="3">
<widget class="QComboBox" name="RemoteMainPort_8">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote main port</string>
</property>
</widget>
</item>
<item row="7" column="4">
<widget class="QComboBox" name="RemoteFlexiPort_8">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote flexi port</string>
</property>
</widget>
</item>
<item row="7" column="5">
<widget class="QComboBox" name="RemoteVCPPort_8">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the remote USB virtual com port</string>
</property>
</widget>
</item>
<item row="7" column="6">
<widget class="QComboBox" name="ComSpeed_8">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the telemetry port speed</string>
</property>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
</item>
<item row="0" column="1"> <item row="0" column="1">
<widget class="QGroupBox" name="groupBox"> <widget class="QGroupBox" name="groupBox">
<property name="sizePolicy"> <property name="sizePolicy">
@ -1551,24 +2437,90 @@
<string>Configuration</string> <string>Configuration</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout_2"> <layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="1"> <item row="0" column="0">
<widget class="QCheckBox" name="Coordinator"> <widget class="QLabel" name="MainPortLabel">
<property name="text">
<string>Coordinator</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QCheckBox" name="UAVTalk">
<property name="text">
<string>UAVTalk</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="PPMLabel">
<property name="text"> <property name="text">
<string>PPM</string> <string>Main Port</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" 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="0" column="2">
<widget class="QLabel" name="MinimumFrequencyLabel">
<property name="text">
<string>Min Freq</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLineEdit" name="MinimumFrequency">
<property name="toolTip">
<string extracomment="The minimum transmit frequency (Hz)"/>
</property>
</widget>
</item>
<item row="1" 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="1" 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="1" column="2">
<widget class="QLabel" name="MaximumFrequencyLabel">
<property name="text">
<string>Max Freq</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLineEdit" name="MaximumFrequency">
<property name="toolTip">
<string extracomment="The maximum transmit frequency (Hz)"/>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="VCPPortLabel">
<property name="text">
<string>VCP Port</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -1576,7 +2528,7 @@
</widget> </widget>
</item> </item>
<item row="2" column="1"> <item row="2" column="1">
<widget class="QComboBox" name="PPM"> <widget class="QComboBox" name="VCPPort">
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>16777215</width> <width>16777215</width>
@ -1584,14 +2536,31 @@
</size> </size>
</property> </property>
<property name="toolTip"> <property name="toolTip">
<string>Choose the PPM function</string> <string>Choose the function for the USB virtual com port</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLabel" name="InitFrequencyLabel">
<property name="text">
<string>Initial Freq</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QLineEdit" name="InitFrequency">
<property name="toolTip">
<string extracomment="The initial transmit frequency (Hz)"/>
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="0"> <item row="3" column="0">
<widget class="QLabel" name="InputConnectionLabel"> <widget class="QLabel" name="MaxRFTxPowerLabel">
<property name="text"> <property name="text">
<string>Input Connection</string> <string>Max Power</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -1599,75 +2568,6 @@
</widget> </widget>
</item> </item>
<item row="3" column="1"> <item row="3" column="1">
<widget class="QComboBox" name="InputConnection">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose which port to communicate over on this modem</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="OutputConnectionLabel">
<property name="text">
<string>Output Connection</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="OutputConnection">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose which port to communicate over on the remote modem</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="5" column="1">
<widget class="QComboBox" name="ComSpeed">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the telemetry port speed</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="MaxRFTxPowerLabel">
<property name="text">
<string>Max RF Tx Power(mW)</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QComboBox" name="MaxRFTxPower"> <widget class="QComboBox" name="MaxRFTxPower">
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
@ -1676,7 +2576,7 @@
</size> </size>
</property> </property>
<property name="toolTip"> <property name="toolTip">
<string>Set the maximum TX output power the modem will use</string> <string>Set the maximum TX output power the modem will use (mW)</string>
</property> </property>
<property name="layoutDirection"> <property name="layoutDirection">
<enum>Qt::LeftToRight</enum> <enum>Qt::LeftToRight</enum>
@ -1686,284 +2586,39 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="7" column="0"> <item row="3" column="2">
<widget class="QLabel" name="SendTimeoutLabel"> <widget class="QLabel" name="StepSizeLabel">
<property name="text"> <property name="text">
<string>Send Timeout (ms)</string> <string>Step Size</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item row="7" column="1"> <item row="3" column="3">
<widget class="QSpinBox" name="SendTimeout"> <widget class="QLineEdit" name="StepSize">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip"> <property name="toolTip">
<string>Set the send timeout</string> <string extracomment="The channel spacing (Hz)"/>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="maximum">
<number>255</number>
</property> </property>
</widget> </widget>
</item> </item>
<item row="8" column="0">
<widget class="QLabel" name="MinPacketSizeLabel">
<property name="text">
<string>Min Packet Size</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="8" column="1">
<widget class="QSpinBox" name="MinPacketSize">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the minimum packet size</string>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="maximum">
<number>255</number>
</property>
</widget>
</item>
<item row="9" column="0">
<widget class="QLabel" name="FreqCalLabel">
<property name="text">
<string>Frequency Calibration</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="FrequencyCalibration">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Calibrate the modems RF carrier frequency</string>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="maximum">
<number>255</number>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Min. Frequency (Hz)</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="10" column="1">
<widget class="QSpinBox" name="MinFrequency">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the modems minimum RF carrier frequency</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="minimum">
<number>400000000</number>
</property>
<property name="maximum">
<number>1000000000</number>
</property>
<property name="singleStep">
<number>100000</number>
</property>
</widget>
</item>
<item row="11" column="0">
<widget class="QLabel" name="MaxFrequencyLabel">
<property name="text">
<string>Max. Frequency (Hz)</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="11" column="1">
<widget class="QSpinBox" name="MaxFrequency">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Set the modems maximum RF carrier frequency</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="minimum">
<number>400000000</number>
</property>
<property name="maximum">
<number>1000000000</number>
</property>
<property name="singleStep">
<number>100000</number>
</property>
</widget>
</item>
<item row="12" column="0" colspan="2">
<widget class="QGroupBox" name="groupBox_4">
<property name="title">
<string>AES Encryption</string>
</property>
<layout class="QGridLayout" name="gridLayout_5">
<item row="0" column="0" colspan="2">
<widget class="QLineEdit" name="AESKey">
<property name="font">
<font>
<family>Courier New</family>
<pointsize>9</pointsize>
</font>
</property>
<property name="toolTip">
<string>The AES encryption key - has to be the same key on the remote modem.</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="maxLength">
<number>32</number>
</property>
<property name="frame">
<bool>true</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QPushButton" name="AESKeyRandom">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Radomise the AES encryption key</string>
</property>
<property name="text">
<string> Rand</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QCheckBox" name="AESEnable">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Enable/Disable AES encryption</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string>Enable</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="13" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="3" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</widget> </widget>
</item> </item>
@ -1980,32 +2635,7 @@
<tabstop>PairID4</tabstop> <tabstop>PairID4</tabstop>
<tabstop>FirmwareVersion</tabstop> <tabstop>FirmwareVersion</tabstop>
<tabstop>SerialNumber</tabstop> <tabstop>SerialNumber</tabstop>
<tabstop>DeviceID</tabstop>
<tabstop>LinkState</tabstop>
<tabstop>RxAFC</tabstop>
<tabstop>Retries</tabstop>
<tabstop>Errors</tabstop>
<tabstop>UAVTalkErrors</tabstop>
<tabstop>Resets</tabstop>
<tabstop>TXRate</tabstop>
<tabstop>RXRate</tabstop>
<tabstop>TelemPortConfig</tabstop>
<tabstop>TelemPortSpeed</tabstop>
<tabstop>FlexiPortConfig</tabstop>
<tabstop>FlexiPortSpeed</tabstop>
<tabstop>VCPConfig</tabstop>
<tabstop>VCPSpeed</tabstop>
<tabstop>MaxRFDatarate</tabstop>
<tabstop>MaxRFTxPower</tabstop> <tabstop>MaxRFTxPower</tabstop>
<tabstop>SendTimeout</tabstop>
<tabstop>MinPacketSize</tabstop>
<tabstop>FrequencyCalibration</tabstop>
<tabstop>Frequency</tabstop>
<tabstop>ScanSpectrum</tabstop>
<tabstop>AESKey</tabstop>
<tabstop>AESKeyRandom</tabstop>
<tabstop>AESEnable</tabstop>
<tabstop>graphicsView_Spectrum</tabstop>
<tabstop>Apply</tabstop> <tabstop>Apply</tabstop>
<tabstop>Save</tabstop> <tabstop>Save</tabstop>
</tabstops> </tabstops>

View File

@ -886,10 +886,9 @@ QVariant UAVObjectField::getValue(quint32 index)
{ {
quint8 tmpenum; quint8 tmpenum;
memcpy(&tmpenum, &data[offset + numBytesPerElement*index], numBytesPerElement); memcpy(&tmpenum, &data[offset + numBytesPerElement*index], numBytesPerElement);
// Q_ASSERT((tmpenum < options.length()) && (tmpenum >= 0)); // catch bad enum settings
if(tmpenum >= options.length()) { if(tmpenum >= options.length()) {
qDebug() << "Invalid value for" << name; qDebug() << "Invalid value for" << name;
return QVariant( QString("Bad Value") ); tmpenum = 0;
} }
return QVariant( options[tmpenum] ); return QVariant( options[tmpenum] );
break; break;
@ -1015,7 +1014,10 @@ void UAVObjectField::setValue(const QVariant& value, quint32 index)
case ENUM: case ENUM:
{ {
qint8 tmpenum = options.indexOf( value.toString() ); qint8 tmpenum = options.indexOf( value.toString() );
Q_ASSERT(tmpenum >= 0); // To catch any programming errors where we set invalid values // Default to 0 on invalid values.
if(tmpenum < 0) {
tmpenum = 0;
}
memcpy(&data[offset + numBytesPerElement*index], &tmpenum, numBytesPerElement); memcpy(&data[offset + numBytesPerElement*index], &tmpenum, numBytesPerElement);
break; break;
} }

View File

@ -457,11 +457,11 @@ void ConfigTaskWidget::forceShadowUpdates()
{ {
foreach (shadow * sh, oTw->shadowsList) foreach (shadow * sh, oTw->shadowsList)
{ {
disconnectWidgetUpdatesToSlot((QWidget*)sh->widget,SLOT(widgetsContentsChanged())); disconnectWidgetUpdatesToSlot((QWidget*)sh->widget, SLOT(widgetsContentsChanged()));
checkWidgetsLimits(sh->widget,oTw->field,oTw->index,sh->isLimited,getVariantFromWidget(oTw->widget,oTw->scale),sh->scale); checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale);
setWidgetFromVariant(sh->widget,getVariantFromWidget(oTw->widget,oTw->scale),sh->scale); setWidgetFromVariant(sh->widget, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale);
emit widgetContentsChanged((QWidget*)sh->widget); emit widgetContentsChanged((QWidget*)sh->widget);
connectWidgetUpdatesToSlot((QWidget*)sh->widget,SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot((QWidget*)sh->widget, SLOT(widgetsContentsChanged()));
} }
} }
@ -480,7 +480,7 @@ void ConfigTaskWidget::widgetsContentsChanged()
if(oTw->widget==(QWidget*)sender()) if(oTw->widget==(QWidget*)sender())
{ {
scale=oTw->scale; scale=oTw->scale;
checkWidgetsLimits((QWidget*)sender(),oTw->field,oTw->index,oTw->isLimited,getVariantFromWidget((QWidget*)sender(),oTw->scale),oTw->scale); checkWidgetsLimits((QWidget*)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget*)sender(), oTw->scale, oTw->getUnits()), oTw->scale);
} }
else else
{ {
@ -489,25 +489,25 @@ void ConfigTaskWidget::widgetsContentsChanged()
if(sh->widget==(QWidget*)sender()) if(sh->widget==(QWidget*)sender())
{ {
scale=sh->scale; scale=sh->scale;
checkWidgetsLimits((QWidget*)sender(),oTw->field,oTw->index,sh->isLimited,getVariantFromWidget((QWidget*)sender(),scale),scale); checkWidgetsLimits((QWidget*)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), scale);
} }
} }
} }
if(oTw->widget!=(QWidget *)sender()) if(oTw->widget!=(QWidget *)sender())
{ {
disconnectWidgetUpdatesToSlot((QWidget*)oTw->widget,SLOT(widgetsContentsChanged())); disconnectWidgetUpdatesToSlot((QWidget*)oTw->widget, SLOT(widgetsContentsChanged()));
checkWidgetsLimits(oTw->widget,oTw->field,oTw->index,oTw->isLimited,getVariantFromWidget((QWidget*)sender(),scale),oTw->scale); checkWidgetsLimits(oTw->widget, oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), oTw->scale);
setWidgetFromVariant(oTw->widget,getVariantFromWidget((QWidget*)sender(),scale),oTw->scale); setWidgetFromVariant(oTw->widget, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), oTw->scale);
emit widgetContentsChanged((QWidget*)oTw->widget); emit widgetContentsChanged((QWidget*)oTw->widget);
connectWidgetUpdatesToSlot((QWidget*)oTw->widget,SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot((QWidget*)oTw->widget, SLOT(widgetsContentsChanged()));
} }
foreach (shadow * sh, oTw->shadowsList) foreach (shadow * sh, oTw->shadowsList)
{ {
if(sh->widget!=(QWidget*)sender()) if(sh->widget!=(QWidget*)sender())
{ {
disconnectWidgetUpdatesToSlot((QWidget*)sh->widget,SLOT(widgetsContentsChanged())); disconnectWidgetUpdatesToSlot((QWidget*)sh->widget,SLOT(widgetsContentsChanged()));
checkWidgetsLimits(sh->widget,oTw->field,oTw->index,sh->isLimited,getVariantFromWidget((QWidget*)sender(),scale),sh->scale); checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), sh->scale);
setWidgetFromVariant(sh->widget,getVariantFromWidget((QWidget*)sender(),scale),sh->scale); setWidgetFromVariant(sh->widget, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), sh->scale);
emit widgetContentsChanged((QWidget*)sh->widget); emit widgetContentsChanged((QWidget*)sh->widget);
connectWidgetUpdatesToSlot((QWidget*)sh->widget,SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot((QWidget*)sh->widget,SLOT(widgetsContentsChanged()));
} }
@ -1034,7 +1034,7 @@ bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * fiel
{ {
if(!widget || !field) if(!widget || !field)
return false; return false;
QVariant ret=getVariantFromWidget(widget,scale); QVariant ret = getVariantFromWidget(widget, scale, field->getUnits());
if(ret.isValid()) if(ret.isValid())
{ {
field->setValue(ret,index); field->setValue(ret,index);
@ -1051,7 +1051,7 @@ bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * fiel
* @param scale scale to be used on the assignement * @param scale scale to be used on the assignement
* @return returns the value of the widget times the scale * @return returns the value of the widget times the scale
*/ */
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget * widget,double scale) QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, QString units)
{ {
if(QComboBox * cb=qobject_cast<QComboBox *>(widget)) if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{ {
@ -1075,7 +1075,13 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget * widget,double scale)
} }
else if(QLineEdit * cb=qobject_cast<QLineEdit *>(widget)) else if(QLineEdit * cb=qobject_cast<QLineEdit *>(widget))
{ {
return (QString)cb->displayText(); QString value = (QString)cb->displayText();
if(units == "hex") {
bool ok;
return value.toUInt(&ok, 16);
} else {
return value;
}
} }
else else
return QVariant(); return QVariant();
@ -1083,13 +1089,14 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget * widget,double scale)
/** /**
* Sets a widget from a variant * Sets a widget from a variant
* @param widget pointer for the widget to set * @param widget pointer for the widget to set
* @param scale scale to be used on the assignement
* @param value value to be used on the assignement * @param value value to be used on the assignement
* @param scale scale to be used on the assignement
* @param units the units for the value
* @return returns true if the assignement was successfull * @return returns true if the assignement was successfull
*/ */
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale) bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units)
{ {
if(QComboBox * cb=qobject_cast<QComboBox *>(widget)) if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{ {
cb->setCurrentIndex(cb->findText(value.toString())); cb->setCurrentIndex(cb->findText(value.toString()));
return true; return true;
@ -1125,15 +1132,33 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou
} }
else if(QLineEdit * cb=qobject_cast<QLineEdit *>(widget)) else if(QLineEdit * cb=qobject_cast<QLineEdit *>(widget))
{ {
if(scale==0) if ((scale== 0) || (scale == 1)) {
cb->setText(value.toString()); if(units == "hex") {
else cb->setText(QString::number(value.toUInt(), 16).toUpper());
} else {
cb->setText(value.toString());
}
} else {
cb->setText(QString::number((value.toDouble()/scale))); cb->setText(QString::number((value.toDouble()/scale)));
}
return true; return true;
} }
else else
return false; return false;
} }
/**
* Sets a widget from a variant
* @param widget pointer for the widget to set
* @param value value to be used on the assignement
* @param scale scale to be used on the assignement
* @return returns true if the assignement was successfull
*/
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale)
{
return setWidgetFromVariant(widget, value, scale, QString(""));
}
/** /**
* Sets a widget from a UAVObject field * Sets a widget from a UAVObject field
* @param widget pointer to the widget to set * @param widget pointer to the widget to set
@ -1154,7 +1179,7 @@ bool ConfigTaskWidget::setWidgetFromField(QWidget * widget,UAVObjectField * fiel
} }
QVariant var=field->getValue(index); QVariant var=field->getValue(index);
checkWidgetsLimits(widget,field,index,hasLimits,var,scale); checkWidgetsLimits(widget,field,index,hasLimits,var,scale);
bool ret=setWidgetFromVariant(widget,var,scale); bool ret = setWidgetFromVariant(widget, var, scale, field->getUnits());
if(ret) if(ret)
return true; return true;
else else

View File

@ -68,6 +68,12 @@ public:
double scale; double scale;
bool isLimited; bool isLimited;
QList<shadow *> shadowsList; QList<shadow *> shadowsList;
QString getUnits() const {
if (field) {
return field->getUnits();
}
return QString("");
}
}; };
struct temphelper struct temphelper
@ -181,8 +187,9 @@ private:
bool dirty; bool dirty;
bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale); bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale);
bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits); bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits);
QVariant getVariantFromWidget(QWidget *widget, double scale); QVariant getVariantFromWidget(QWidget *widget, double scale, QString units);
bool setWidgetFromVariant(QWidget *widget,QVariant value,double scale); bool setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units);
bool setWidgetFromVariant(QWidget *widget, QVariant value, double scale);
void connectWidgetUpdatesToSlot(QWidget *widget, const char *function); void connectWidgetUpdatesToSlot(QWidget *widget, const char *function);
void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function); void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function);
void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale); void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale);

View File

@ -17,6 +17,8 @@
<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="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="RadioPort" units="function" type="enum" elements="1" options="Disabled,Telemetry" defaultvalue="Disabled"/>
<field name="MaxRFPower" units="mW" type="enum" elements="1" options="1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="100"/>
<field name="DefaultFrequency" units="Hz" type="uint32" elements="1" defaultvalue="433000000"/>
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/> <field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
<field name="GPSSpeed" 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"/>

View File

@ -1,20 +1,19 @@
<xml> <xml>
<object name="OPLinkSettings" singleinstance="true" settings="true"> <object name="OPLinkSettings" singleinstance="true" settings="true">
<description>OPLink configurations options.</description> <description>OPLink configurations options.</description>
<field name="PairID" units="" type="uint32" elements="1" defaultvalue="0"/> <field name="Bindings" units="hex" type="uint32" elements="8" defaultvalue="0"/>
<field name="Coordinator" units="binary" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/> <field name="RemoteMainPort" units="" type="enum" elements="8" options="Disabled,Serial,PPM" defaultvalue="Telemetry"/>
<field name="UAVTalk" units="binary" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/> <field name="RemoteFlexiPort" units="" type="enum" elements="8" options="Disabled,Serial,PPM" defaultvalue="Disabled"/>
<field name="PPM" units="" type="enum" elements="1" options="Disabled,Input,Output" defaultvalue="Disabled"/> <field name="RemoteVCPPort" units="" type="enum" elements="8" options="Disabled,Serial" defaultvalue="Disabled"/>
<field name="InputConnection" units="function" type="enum" elements="1" options="HID,VCP,Telemetry,Flexi" defaultvalue="HID"/> <field name="ComSpeed" units="bps" type="enum" elements="8" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="38400"/>
<field name="OutputConnection" units="function" type="enum" elements="1" options="RemoteHID,RemoteVCP,RemoteTelemetry,RemoteFlexi,Telemetry,Flexi" defaultvalue="RemoteTelemetry"/> <field name="MainPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM" defaultvalue="Telemetry"/>
<field name="ComSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="38400"/> <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="MaxRFPower" units="mW" type="enum" elements="1" options="1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="100"/> <field name="MaxRFPower" units="mW" type="enum" elements="1" options="1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="100"/>
<field name="SendTimeout" units="ms" type="uint16" elements="1" defaultvalue="50"/> <field name="MinFrequency" units="Hz" type="uint32" elements="1" defaultvalue="430000000"/>
<field name="MinPacketSize" units="bytes" type="uint8" elements="1" defaultvalue="50"/> <field name="MaxFrequency" units="Hz" type="uint32" elements="1" defaultvalue="440000000"/>
<field name="FrequencyCalibration" units="" type="uint8" elements="1" defaultvalue="127"/> <field name="InitFrequency" units="Hz" type="uint32" elements="1" defaultvalue="433000000"/>
<field name="MinFrequency" units="" type="uint32" elements="1" defaultvalue="432000000"/> <field name="ChannelSpacing" units="Hz" type="uint32" elements="1" defaultvalue="75000"/>
<field name="MaxFrequency" units="" type="uint32" elements="1" defaultvalue="436000000"/>
<field name="AESKey" units="" type="uint8" elements="32" defaultvalue="0123456789abcdef0123456789abcdef"/>
<access gcs="readwrite" flight="readwrite"/> <access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/> <telemetrygcs acked="true" updatemode="onchange" period="0"/>

View File

@ -2,10 +2,11 @@
<object name="OPLinkStatus" singleinstance="true" settings="false"> <object name="OPLinkStatus" singleinstance="true" settings="false">
<description>OPLink device status.</description> <description>OPLink device status.</description>
<field name="Description" units="" type="uint8" elements="40"/> <field name="Description" units="" type="uint8" elements="40"/>
<field name="CPUSerial" units="" type="uint8" elements="12" /> <field name="CPUSerial" units="hex" type="uint8" elements="12" />
<field name="BoardRevision" units="" type="uint16" elements="1"/> <field name="BoardRevision" units="" type="uint16" elements="1"/>
<field name="BoardType" units="" type="uint8" elements="1"/> <field name="BoardType" units="" type="uint8" elements="1"/>
<field name="DeviceID" units="" type="uint32" elements="1" defaultvalue="0"/> <field name="DeviceID" units="hex" type="uint32" elements="1" defaultvalue="0"/>
<field name="HeapRemaining" units="bytes" type="uint16" elements="1"/>
<field name="RxGood" units="%" type="uint8" elements="1" defaultvalue="0"/> <field name="RxGood" units="%" type="uint8" elements="1" defaultvalue="0"/>
<field name="RxCorrected" units="%" type="uint8" elements="1" defaultvalue="0"/> <field name="RxCorrected" units="%" type="uint8" elements="1" defaultvalue="0"/>
<field name="RxErrors" units="%" type="uint8" elements="1" defaultvalue="0"/> <field name="RxErrors" units="%" type="uint8" elements="1" defaultvalue="0"/>
@ -18,14 +19,13 @@
<field name="Resets" units="" type="uint8" elements="1" defaultvalue="0"/> <field name="Resets" units="" type="uint8" elements="1" defaultvalue="0"/>
<field name="Timeouts" units="" type="uint8" elements="1" defaultvalue="0"/> <field name="Timeouts" units="" type="uint8" elements="1" defaultvalue="0"/>
<field name="RSSI" units="dBm" type="int8" elements="1" defaultvalue="0"/> <field name="RSSI" units="dBm" type="int8" elements="1" defaultvalue="0"/>
<field name="AFCCorrection" units="Hz" type="int8" elements="1" defaultvalue="0"/>
<field name="LinkQuality" units="" type="uint8" elements="1" defaultvalue="0"/> <field name="LinkQuality" units="" type="uint8" elements="1" defaultvalue="0"/>
<field name="TXRate" units="Bps" type="uint16" elements="1" defaultvalue="0"/> <field name="TXRate" units="Bps" type="uint16" elements="1" defaultvalue="0"/>
<field name="RXRate" units="Bps" type="uint16" elements="1" defaultvalue="0"/> <field name="RXRate" units="Bps" type="uint16" elements="1" defaultvalue="0"/>
<field name="TXSeq" units="" 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="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="Disconnected,Connecting,Connected" defaultvalue="Disconnected"/>
<field name="PairIDs" units="" type="uint32" elements="4" defaultvalue="0"/> <field name="PairIDs" units="hex" type="uint32" elements="4" defaultvalue="0"/>
<field name="PairSignalStrengths" units="dBm" type="int8" elements="4" defaultvalue="-127"/> <field name="PairSignalStrengths" units="dBm" type="int8" elements="4" defaultvalue="-127"/>
<access gcs="readonly" flight="readwrite"/> <access gcs="readonly" flight="readwrite"/>