1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-17 02:52:12 +01:00

Merge branch 'rel-13.06.02'

Conflicts:
	WHATSNEW.txt
This commit is contained in:
Brian Webb 2013-07-05 19:02:39 -07:00
commit fb5a24b1cc
49 changed files with 2938 additions and 3739 deletions

View File

@ -1,3 +1,10 @@
--- RELEASE-13.06.02 ---
Refactoring of OPLink radio driver. Auto-configuration was removed, and a
one-way link was added, including a ppm-only mode that is intended to be used
when only a PPM link is desired. PPM-only mode configures the modem as a
one-way link running at 9600 bps (air datarate) and only sends PPM packets.
--- RELEASE-13.06.01 --- Italian Stallion Release ---
It applies the following changes to previously not released to public RELEASE-13.06

View File

@ -1,111 +0,0 @@
/**
******************************************************************************
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
* @{
*
* @file packet_handler.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief A packet handler for handeling radio packet transmission.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef __PACKET_HANDLER_H__
#define __PACKET_HANDLER_H__
#include <uavobjectmanager.h>
#include <gcsreceiver.h>
#include <oplinksettings.h>
#include <pios_rfm22b_rcvr.h>
// Public defines / macros
#define PHPacketSize(p) ((uint8_t *)(p->data) + p->header.data_size - (uint8_t *)p)
#define PHPacketSizeECC(p) ((uint8_t *)(p->data) + p->header.data_size + RS_ECC_NPARITY - (uint8_t *)p)
// Public types
typedef enum {
PACKET_TYPE_NONE = 0,
PACKET_TYPE_STATUS, // broadcasts status of this modem
PACKET_TYPE_CON_REQUEST, // request a connection to another modem
PACKET_TYPE_DATA, // data packet (packet contains user data)
PACKET_TYPE_DUPLICATE_DATA, // a duplicate data packet
PACKET_TYPE_PPM, // PPM relay values
PACKET_TYPE_ACK, // Acknowlege the receipt of a packet
PACKET_TYPE_NACK, // Acknowlege the receipt of an uncorrectable packet
} PHPacketType;
typedef struct {
uint32_t destination_id;
portTickType prev_tx_time;
uint16_t seq_num;
uint8_t type;
uint8_t data_size;
} PHPacketHeader;
#define PH_MAX_DATA (PIOS_PH_MAX_PACKET - sizeof(PHPacketHeader) - RS_ECC_NPARITY)
#define PH_PACKET_SIZE(p) ((p)->data + (p)->header.data_size - (uint8_t *)(p) + RS_ECC_NPARITY)
typedef struct {
PHPacketHeader header;
uint8_t data[PH_MAX_DATA + RS_ECC_NPARITY];
} PHPacket, *PHPacketHandle;
#define PH_ACK_NACK_DATA_SIZE(p) ((uint8_t *)((p)->ecc) - (uint8_t *)(((PHPacketHandle)(p))->data))
typedef struct {
PHPacketHeader header;
uint8_t ecc[RS_ECC_NPARITY];
} PHAckNackPacket, *PHAckNackPacketHandle;
#define PH_PPM_DATA_SIZE(p) ((uint8_t *)((p)->ecc) - (uint8_t *)(((PHPacketHandle)(p))->data))
typedef struct {
PHPacketHeader header;
int16_t channels[PIOS_RFM22B_RCVR_MAX_CHANNELS];
uint8_t ecc[RS_ECC_NPARITY];
} PHPpmPacket, *PHPpmPacketHandle;
#define PH_STATUS_DATA_SIZE(p) ((uint8_t *)((p)->ecc) - (uint8_t *)(((PHPacketHandle)(p))->data))
typedef struct {
PHPacketHeader header;
uint32_t source_id;
uint8_t link_quality;
int8_t received_rssi;
uint8_t ecc[RS_ECC_NPARITY];
} PHStatusPacket, *PHStatusPacketHandle;
#define PH_CONNECTION_DATA_SIZE(p) ((uint8_t *)((p)->ecc) - (uint8_t *)(((PHPacketHandle)(p))->data))
typedef struct {
PHPacketHeader header;
uint32_t source_id;
uint32_t min_frequency;
uint32_t max_frequency;
uint32_t channel_spacing;
portTickType status_rx_time;
OPLinkSettingsMainPortOptions main_port;
OPLinkSettingsFlexiPortOptions flexi_port;
OPLinkSettingsVCPPortOptions vcp_port;
OPLinkSettingsComSpeedOptions com_speed;
uint8_t ecc[RS_ECC_NPARITY];
} PHConnectionPacket, *PHConnectionPacketHandle;
#endif // __PACKET_HANDLER_H__
/**
* @}
* @}
*/

View File

@ -38,10 +38,12 @@
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <pios.h>
#include <uavobjectmanager.h>
#include <openpilot.h>
#include <oplinkstatus.h>
#include <oplinksettings.h>
#include <taskinfo.h>
#include <pios_rfm22b.h>
@ -95,22 +97,6 @@ int32_t OPLinkModInitialize(void)
{
// Must registers objects here for system thread because ObjectManager started in OpenPilotInit
// Initialize out status object.
OPLinkStatusInitialize();
OPLinkStatusData oplinkStatus;
OPLinkStatusGet(&oplinkStatus);
// Get our hardware information.
const struct pios_board_info *bdinfo = &pios_board_info_blob;
oplinkStatus.BoardType = bdinfo->board_type;
PIOS_BL_HELPER_FLASH_Read_Description(oplinkStatus.Description, OPLINKSTATUS_DESCRIPTION_NUMELEM);
PIOS_SYS_SerialNumberGetBinary(oplinkStatus.CPUSerial);
oplinkStatus.BoardRevision = bdinfo->board_rev;
// Update the object
OPLinkStatusSet(&oplinkStatus);
// Call the module start function.
OPLinkModStart();

View File

@ -7,7 +7,7 @@
* @{
*
* @file RadioComBridge.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012-2013.
* @brief Bridges selected Com Port to the COM VCP emulated serial port
* @see The GNU Public License (GPL) Version 3
*
@ -32,11 +32,10 @@
#include <openpilot.h>
#include <radiocombridge.h>
#include <packet_handler.h>
#include <gcsreceiver.h>
#include <oplinkstatus.h>
#include <objectpersistence.h>
#include <oplinksettings.h>
#include <oplinkreceiver.h>
#include <uavtalk_priv.h>
#include <pios_rfm22b.h>
#include <ecc.h>
@ -46,23 +45,17 @@
#include <stdbool.h>
// External functions
void PIOS_InitUartMainPort();
void PIOS_InitUartFlexiPort();
void PIOS_InitPPMMainPort(bool input);
void PIOS_InitPPMFlexiPort(bool input);
// ****************
// Private constants
#define STACK_SIZE_BYTES 150
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
#define MAX_RETRIES 2
#define RETRY_TIMEOUT_MS 20
#define EVENT_QUEUE_SIZE 10
#define MAX_PORT_DELAY 200
#define EV_SEND_ACK 0x20
#define EV_SEND_NACK 0x30
#define STACK_SIZE_BYTES 150
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
#define MAX_RETRIES 2
#define RETRY_TIMEOUT_MS 20
#define EVENT_QUEUE_SIZE 10
#define MAX_PORT_DELAY 200
#define SERIAL_RX_BUF_LEN 100
#define PPM_INPUT_TIMEOUT 100
// ****************
// Private types
@ -73,26 +66,28 @@ typedef struct {
xTaskHandle telemetryRxTaskHandle;
xTaskHandle radioTxTaskHandle;
xTaskHandle radioRxTaskHandle;
xTaskHandle PPMInputTaskHandle;
xTaskHandle serialRxTaskHandle;
// The UAVTalk connection on the com side.
UAVTalkConnection outUAVTalkCon;
UAVTalkConnection inUAVTalkCon;
UAVTalkConnection telemUAVTalkCon;
UAVTalkConnection radioUAVTalkCon;
// Queue handles.
xQueueHandle gcsEventQueue;
xQueueHandle uavtalkEventQueue;
xQueueHandle radioEventQueue;
// The raw serial Rx buffer
uint8_t serialRxBuf[SERIAL_RX_BUF_LEN];
// Error statistics.
uint32_t comTxErrors;
uint32_t comTxRetries;
uint32_t UAVTalkErrors;
uint32_t droppedPackets;
uint32_t comTxErrors;
uint32_t comTxRetries;
uint32_t UAVTalkErrors;
uint32_t droppedPackets;
// Should we parse UAVTalk?
bool parseUAVTalk;
// We can only configure the hardware once.
bool configured;
bool parseUAVTalk;
// The current configured uart speed
OPLinkSettingsComSpeedOptions comSpeed;
@ -103,15 +98,15 @@ typedef struct {
static void telemetryTxTask(void *parameters);
static void telemetryRxTask(void *parameters);
static void serialRxTask(void *parameters);
static void radioTxTask(void *parameters);
static void radioRxTask(void *parameters);
static void PPMInputTask(void *parameters);
static int32_t UAVTalkSendHandler(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 queueEvent(xQueueHandle queue, void *obj, uint16_t instId, UAVObjEventType type);
static void configureComCallback(OPLinkSettingsRemoteMainPortOptions main_port, OPLinkSettingsRemoteFlexiPortOptions flexi_port,
OPLinkSettingsRemoteVCPPortOptions vcp_port, OPLinkSettingsComSpeedOptions com_speed);
static void updateSettings(OPLinkSettingsData *oplinkSettings);
static void ProcessTelemetryStream(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle, uint8_t rxbyte);
static void ProcessRadioStream(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle, uint8_t rxbyte);
static void objectPersistenceUpdatedCb(UAVObjEvent *objEv);
// ****************
// Private variables
@ -119,7 +114,7 @@ static void updateSettings(OPLinkSettingsData *oplinkSettings);
static RadioComBridgeData *data;
/**
* Start the module
* @brief Start the module
*
* @return -1 if initialisation failed, 0 on success
*/
@ -129,27 +124,12 @@ static int32_t RadioComBridgeStart(void)
// Get the settings.
OPLinkSettingsData oplinkSettings;
OPLinkSettingsGet(&oplinkSettings);
bool is_coordinator = (oplinkSettings.Coordinator == OPLINKSETTINGS_COORDINATOR_TRUE);
// Set the baudrates, etc.
bool is_coordinator = PIOS_RFM22B_IsCoordinator(pios_rfm22b_id);
if (is_coordinator) {
// Set the frequency range.
PIOS_RFM22B_SetFrequencyRange(pios_rfm22b_id, oplinkSettings.MinFrequency, oplinkSettings.MaxFrequency, oplinkSettings.ChannelSpacing);
// Set the com baud rates.
updateSettings(&oplinkSettings);
// Reinitilize the modem.
PIOS_RFM22B_Reinit(pios_rfm22b_id);
// We will not parse/send UAVTalk if any ports are configured as Serial (except for over the USB HID port).
data->parseUAVTalk = ((oplinkSettings.MainPort != OPLINKSETTINGS_MAINPORT_SERIAL) &&
(oplinkSettings.FlexiPort != OPLINKSETTINGS_FLEXIPORT_SERIAL) &&
(oplinkSettings.VCPPort != OPLINKSETTINGS_VCPPORT_SERIAL));
} else {
// Configure the com port configuration callback on the remote modem.
PIOS_RFM22B_SetComConfigCallback(pios_rfm22b_id, &configureComCallback);
}
// We will not parse/send UAVTalk if any ports are configured as Serial (except for over the USB HID port).
data->parseUAVTalk = ((oplinkSettings.MainPort != OPLINKSETTINGS_MAINPORT_SERIAL) &&
(oplinkSettings.FlexiPort != OPLINKSETTINGS_FLEXIPORT_SERIAL) &&
(oplinkSettings.VCPPort != OPLINKSETTINGS_VCPPORT_SERIAL));
// Set the maximum radio RF power.
switch (oplinkSettings.MaxRFPower) {
@ -182,12 +162,34 @@ static int32_t RadioComBridgeStart(void)
break;
}
// Set the initial frequency.
PIOS_RFM22B_SetInitialFrequency(pios_rfm22b_id, oplinkSettings.InitFrequency);
// Configure our UAVObjects for updates.
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);
if (is_coordinator) {
UAVObjConnectQueue(UAVObjGetByID(OPLINKRECEIVER_OBJID), data->radioEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
} else {
UAVObjConnectQueue(UAVObjGetByID(OPLINKRECEIVER_OBJID), data->uavtalkEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
}
// Configure the UAVObject callbacks
ObjectPersistenceConnectCallback(&objectPersistenceUpdatedCb);
// Start the primary tasks for receiving/sending UAVTalk packets from the GCS.
xTaskCreate(telemetryTxTask, (signed char *)"telemetryTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryTxTaskHandle));
xTaskCreate(telemetryRxTask, (signed char *)"telemetryRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryRxTaskHandle));
if (PIOS_PPM_RECEIVER != 0) {
xTaskCreate(PPMInputTask, (signed char *)"PPMInputTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->PPMInputTaskHandle));
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_PPMINPUT);
#endif
}
if (!data->parseUAVTalk) {
// If the user wants raw serial communication, we need to spawn another thread to handle it.
xTaskCreate(serialRxTask, (signed char *)"serialRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->serialRxTaskHandle));
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_SERIALRX);
#endif
}
xTaskCreate(radioTxTask, (signed char *)"radioTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioTxTaskHandle));
xTaskCreate(radioRxTask, (signed char *)"radioRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioRxTaskHandle));
@ -205,7 +207,7 @@ static int32_t RadioComBridgeStart(void)
}
/**
* Initialise the module
* @brief Initialise the module
*
* @return -1 if initialisation failed on success
*/
@ -220,27 +222,21 @@ static int32_t RadioComBridgeInitialize(void)
// Initialize the UAVObjects that we use
OPLinkStatusInitialize();
ObjectPersistenceInitialize();
OPLinkReceiverInitialize();
// Initialise UAVTalk
data->outUAVTalkCon = UAVTalkInitialize(&UAVTalkSendHandler);
data->inUAVTalkCon = UAVTalkInitialize(&RadioSendHandler);
data->telemUAVTalkCon = UAVTalkInitialize(&UAVTalkSendHandler);
data->radioUAVTalkCon = UAVTalkInitialize(&RadioSendHandler);
// Initialize the queues.
data->uavtalkEventQueue = xQueueCreate(EVENT_QUEUE_SIZE, sizeof(UAVObjEvent));
// Configure our UAVObjects for updates.
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);
#if defined(PIOS_INCLUDE_RFM22B_GCSRECEIVER)
UAVObjConnectQueue(UAVObjGetByID(GCSRECEIVER_OBJID), data->uavtalkEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
#endif
data->radioEventQueue = xQueueCreate(EVENT_QUEUE_SIZE, sizeof(UAVObjEvent));
// Initialize the statistics.
data->comTxErrors = 0;
data->comTxRetries = 0;
data->UAVTalkErrors = 0;
data->parseUAVTalk = true;
data->configured = false;
data->comSpeed = OPLINKSETTINGS_COMSPEED_9600;
PIOS_COM_RADIO = PIOS_COM_RFM22B;
@ -249,7 +245,7 @@ static int32_t RadioComBridgeInitialize(void)
MODULE_INITCALL(RadioComBridgeInitialize, RadioComBridgeStart);
/**
* Telemetry transmit task, regular priority
* @brief Telemetry transmit task, regular priority
*
* @param[in] parameters The task parameters
*/
@ -269,29 +265,7 @@ static void telemetryTxTask(__attribute__((unused)) void *parameters)
uint32_t retries = 0;
int32_t success = -1;
while (retries < MAX_RETRIES && success == -1) {
success = UAVTalkSendObject(data->outUAVTalkCon, ev.obj, 0, 0, RETRY_TIMEOUT_MS) == 0;
if (!success) {
++retries;
}
}
data->comTxRetries += retries;
} else if (ev.event == EV_SEND_ACK) {
// Send the ACK
uint32_t retries = 0;
int32_t success = -1;
while (retries < MAX_RETRIES && success == -1) {
success = UAVTalkSendAck(data->outUAVTalkCon, ev.obj, ev.instId) == 0;
if (!success) {
++retries;
}
}
data->comTxRetries += retries;
} else if (ev.event == EV_SEND_NACK) {
// Send the NACK
uint32_t retries = 0;
int32_t success = -1;
while (retries < MAX_RETRIES && success == -1) {
success = UAVTalkSendNack(data->outUAVTalkCon, UAVObjGetID(ev.obj)) == 0;
success = UAVTalkSendObject(data->telemUAVTalkCon, ev.obj, 0, 0, RETRY_TIMEOUT_MS) == 0;
if (!success) {
++retries;
}
@ -303,7 +277,7 @@ static void telemetryTxTask(__attribute__((unused)) void *parameters)
}
/**
* Radio tx task. Receive data packets from the com port and send to the radio.
* @brief Radio tx task. Receive data packets from the com port and send to the radio.
*
* @param[in] parameters The task parameters
*/
@ -315,23 +289,29 @@ static void radioTxTask(__attribute__((unused)) void *parameters)
PIOS_WDG_UpdateFlag(PIOS_WDG_RADIOTX);
#endif
// Wait until the com port is available.
if (data->parseUAVTalk || !PIOS_COM_TELEMETRY) {
vTaskDelay(5);
continue;
}
// Process the radio event queue, sending UAVObjects over the radio link as necessary.
UAVObjEvent ev;
// Read from the com port.
uint8_t serial_data[1];
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(PIOS_COM_TELEMETRY, serial_data, sizeof(serial_data), MAX_PORT_DELAY);
if (bytes_to_process > 0) {
PIOS_COM_SendBufferNonBlocking(PIOS_COM_RADIO, serial_data, bytes_to_process);
// Wait for queue message
if (xQueueReceive(data->radioEventQueue, &ev, MAX_PORT_DELAY) == pdTRUE) {
if ((ev.event == EV_UPDATED) || (ev.event == EV_UPDATE_REQ)) {
// Send update (with retries)
uint32_t retries = 0;
int32_t success = -1;
while (retries < MAX_RETRIES && success == -1) {
success = UAVTalkSendObject(data->radioUAVTalkCon, ev.obj, 0, 0, RETRY_TIMEOUT_MS) == 0;
if (!success) {
++retries;
}
}
data->comTxRetries += retries;
}
}
}
}
/**
* Radio rx task. Receive data packets from the radio and pass them on.
* @brief Radio rx task. Receive data packets from the radio and pass them on.
*
* @param[in] parameters The task parameters
*/
@ -342,25 +322,28 @@ static void radioRxTask(__attribute__((unused)) void *parameters)
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORX);
#endif
uint8_t serial_data[1];
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, serial_data, sizeof(serial_data), MAX_PORT_DELAY);
if (bytes_to_process > 0) {
// Either pass the data through the UAVTalk parser, or just send it to the radio (if we're doing raw comms).
if (data->parseUAVTalk) {
for (uint8_t i = 0; i < bytes_to_process; i++) {
if (UAVTalkRelayInputStream(data->outUAVTalkCon, serial_data[i]) == UAVTALK_STATE_ERROR) {
data->UAVTalkErrors++;
if (PIOS_COM_RADIO) {
uint8_t serial_data[1];
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, serial_data, sizeof(serial_data), MAX_PORT_DELAY);
if (bytes_to_process > 0) {
if (data->parseUAVTalk) {
// Pass the data through the UAVTalk parser.
for (uint8_t i = 0; i < bytes_to_process; i++) {
ProcessRadioStream(data->radioUAVTalkCon, data->telemUAVTalkCon, serial_data[i]);
}
} else if (PIOS_COM_TELEMETRY) {
// Send the data straight to the telemetry port.
PIOS_COM_SendBufferNonBlocking(PIOS_COM_TELEMETRY, serial_data, bytes_to_process);
}
} else if (PIOS_COM_TELEMETRY) {
PIOS_COM_SendBufferNonBlocking(PIOS_COM_TELEMETRY, serial_data, bytes_to_process);
}
} else {
vTaskDelay(5);
}
}
}
/**
* Receive telemetry from the USB/COM port.
* @brief Receive telemetry from the USB/COM port.
*
* @param[in] parameters The task parameters
*/
@ -383,7 +366,7 @@ static void telemetryRxTask(__attribute__((unused)) void *parameters)
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(inputPort, serial_data, sizeof(serial_data), MAX_PORT_DELAY);
if (bytes_to_process > 0) {
for (uint8_t i = 0; i < bytes_to_process; i++) {
ProcessInputStream(data->inUAVTalkCon, serial_data[i]);
ProcessTelemetryStream(data->telemUAVTalkCon, data->radioUAVTalkCon, serial_data[i]);
}
}
} else {
@ -393,7 +376,67 @@ static void telemetryRxTask(__attribute__((unused)) void *parameters)
}
/**
* Transmit data buffer to the com port.
* @brief Reads the PPM input device and sends out OPLinkReceiver objects.
*
* @param[in] parameters The task parameters (unused)
*/
static void PPMInputTask(__attribute__((unused)) void *parameters)
{
xSemaphoreHandle sem = PIOS_RCVR_GetSemaphore(PIOS_PPM_RECEIVER, 1);
int16_t channels[RFM22B_PPM_NUM_CHANNELS];
while (1) {
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_PPMINPUT);
#endif
// Wait for the receiver semaphore.
if (xSemaphoreTake(sem, PPM_INPUT_TIMEOUT) == pdTRUE) {
// Read the receiver inputs.
for (uint8_t i = 0; i < OPLINKRECEIVER_CHANNEL_NUMELEM; ++i) {
channels[i] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i + 1);
}
} else {
// Failsafe
for (uint8_t i = 0; i < OPLINKRECEIVER_CHANNEL_NUMELEM; ++i) {
channels[i] = PIOS_RCVR_INVALID;
}
}
// Pass the channel values to the radio device.
PIOS_RFM22B_PPMSet(pios_rfm22b_id, channels);
}
}
/**
* @brief Receive raw serial data from the USB/COM port.
*
* @param[in] parameters The task parameters
*/
static void serialRxTask(__attribute__((unused)) void *parameters)
{
// Task loop
while (1) {
uint32_t inputPort = PIOS_COM_TELEMETRY;
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_SERIALRX);
#endif
if (inputPort && PIOS_COM_RADIO) {
// Receive some data.
uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(inputPort, data->serialRxBuf, sizeof(data->serialRxBuf), MAX_PORT_DELAY);
// Send the data over the radio link.
if (bytes_to_process > 0) {
PIOS_COM_SendBufferNonBlocking(PIOS_COM_RADIO, data->serialRxBuf, bytes_to_process);
}
} else {
vTaskDelay(5);
}
}
}
/**
* @brief Transmit data buffer to the com port.
*
* @param[in] buf Data buffer to send
* @param[in] length Length of buffer
@ -427,6 +470,9 @@ static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length)
*/
static int32_t RadioSendHandler(uint8_t *buf, int32_t length)
{
if (!data->parseUAVTalk) {
return length;
}
uint32_t outputPort = PIOS_COM_RADIO;
// Don't send any data unless the radio port is available.
@ -439,272 +485,117 @@ static int32_t RadioSendHandler(uint8_t *buf, int32_t length)
}
/**
* Process a byte of data received
* @brief Process a byte of data received on the telemetry stream
*
* @param[in] connectionHandle The UAVTalk connection handle
* @param[in] inConnectionHandle The UAVTalk connection handle on the telemetry port
* @param[in] outConnectionHandle The UAVTalk connection handle on the radio port.
* @param[in] rxbyte The received byte.
*/
static void ProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte)
static void ProcessTelemetryStream(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle, uint8_t rxbyte)
{
// Keep reading until we receive a completed packet.
UAVTalkRxState state = UAVTalkRelayInputStream(connectionHandle, rxbyte);
UAVTalkConnectionData *connection = (UAVTalkConnectionData *)(connectionHandle);
UAVTalkInputProcessor *iproc = &(connection->iproc);
UAVTalkRxState state = UAVTalkProcessInputStream(inConnectionHandle, rxbyte);
if (state == UAVTALK_STATE_COMPLETE) {
// Is this a local UAVObject?
// We only generate GcsReceiver ojects, we don't consume them.
if ((iproc->obj != NULL) && (iproc->objId != GCSRECEIVER_OBJID)) {
// We treat the ObjectPersistence object differently
if (iproc->objId == OBJECTPERSISTENCE_OBJID) {
// Unpack object, if the instance does not exist it will be created!
UAVObjUnpack(iproc->obj, iproc->instId, connection->rxBuffer);
// Get the ObjectPersistence object.
ObjectPersistenceData obj_per;
ObjectPersistenceGet(&obj_per);
// Is this concerning or setting object?
if (obj_per.ObjectID == OPLINKSETTINGS_OBJID) {
// Queue up the ACK.
queueEvent(data->uavtalkEventQueue, (void *)iproc->obj, iproc->instId, EV_SEND_ACK);
// Is this a save, load, or delete?
bool success = true;
switch (obj_per.Operation) {
case OBJECTPERSISTENCE_OPERATION_LOAD:
{
#if defined(PIOS_INCLUDE_FLASH_LOGFS_SETTINGS)
// Load the settings.
void *obj = UAVObjGetByID(obj_per.ObjectID);
if (obj == 0) {
success = false;
} else {
// Load selected instance
success = (UAVObjLoad(obj, obj_per.InstanceID) == 0);
}
#endif
break;
}
case OBJECTPERSISTENCE_OPERATION_SAVE:
{
#if defined(PIOS_INCLUDE_FLASH_LOGFS_SETTINGS)
void *obj = UAVObjGetByID(obj_per.ObjectID);
if (obj == 0) {
success = false;
} else {
// Save selected instance
success = UAVObjSave(obj, obj_per.InstanceID) == 0;
}
#endif
break;
}
case OBJECTPERSISTENCE_OPERATION_DELETE:
{
#if defined(PIOS_INCLUDE_FLASH_LOGFS_SETTINGS)
void *obj = UAVObjGetByID(obj_per.ObjectID);
if (obj == 0) {
success = false;
} else {
// Save selected instance
success = UAVObjDelete(obj, obj_per.InstanceID) == 0;
}
#endif
break;
}
default:
break;
}
if (success == true) {
obj_per.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED;
ObjectPersistenceSet(&obj_per);
}
}
} else {
switch (iproc->type) {
case UAVTALK_TYPE_OBJ:
// Unpack object, if the instance does not exist it will be created!
UAVObjUnpack(iproc->obj, iproc->instId, connection->rxBuffer);
break;
case UAVTALK_TYPE_OBJ_REQ:
// Queue up an object send request.
queueEvent(data->uavtalkEventQueue, (void *)iproc->obj, iproc->instId, EV_UPDATE_REQ);
break;
case UAVTALK_TYPE_OBJ_ACK:
if (UAVObjUnpack(iproc->obj, iproc->instId, connection->rxBuffer) == 0) {
// Queue up an ACK
queueEvent(data->uavtalkEventQueue, (void *)iproc->obj, iproc->instId, EV_SEND_ACK);
}
break;
}
}
}
} else if (state == UAVTALK_STATE_ERROR) {
if (state == UAVTALK_STATE_ERROR) {
data->UAVTalkErrors++;
} else if (state == UAVTALK_STATE_COMPLETE) {
UAVTalkRelayPacket(inConnectionHandle, outConnectionHandle);
}
}
// Send a NACK if required.
if ((iproc->obj) && (iproc->type == UAVTALK_TYPE_OBJ_ACK)) {
// Queue up a NACK
queueEvent(data->uavtalkEventQueue, iproc->obj, iproc->instId, EV_SEND_NACK);
/**
* @brief Process a byte of data received on the radio data stream.
*
* @param[in] inConnectionHandle The UAVTalk connection handle on the radio port.
* @param[in] outConnectionHandle The UAVTalk connection handle on the telemetry port.
* @param[in] rxbyte The received byte.
*/
static void ProcessRadioStream(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle, uint8_t rxbyte)
{
// Keep reading until we receive a completed packet.
UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(inConnectionHandle, rxbyte);
if (state == UAVTALK_STATE_ERROR) {
data->UAVTalkErrors++;
} else if (state == UAVTALK_STATE_COMPLETE) {
// We only want to unpack certain objects from the remote modem.
uint32_t objId = UAVTalkGetPacketObjId(inConnectionHandle);
switch (objId) {
case OPLINKSTATUS_OBJID:
case OPLINKSETTINGS_OBJID:
break;
case OPLINKRECEIVER_OBJID:
UAVTalkReceiveObject(inConnectionHandle);
break;
default:
UAVTalkRelayPacket(inConnectionHandle, outConnectionHandle);
break;
}
}
}
/**
* Queue and event into an event queue.
*
* @param[in] queue The event queue
* @param[in] obj The data pointer
* @param[in] type The event type
* @brief Callback that is called when the ObjectPersistence UAVObject is changed.
* @param[in] objEv The event that precipitated the callback.
*/
static void queueEvent(xQueueHandle queue, void *obj, uint16_t instId, UAVObjEventType type)
static void objectPersistenceUpdatedCb(__attribute__((unused)) UAVObjEvent *objEv)
{
UAVObjEvent ev;
// Get the ObjectPersistence object.
ObjectPersistenceData obj_per;
ev.obj = (UAVObjHandle)obj;
ev.instId = instId;
ev.event = type;
xQueueSend(queue, &ev, portMAX_DELAY);
}
ObjectPersistenceGet(&obj_per);
/**
* Configure the output port based on a configuration event from the remote coordinator.
*
* @param[in] com_port The com port to configure
* @param[in] com_speed The com port speed
*/
static void configureComCallback(OPLinkSettingsRemoteMainPortOptions main_port, OPLinkSettingsRemoteFlexiPortOptions flexi_port,
OPLinkSettingsRemoteVCPPortOptions vcp_port, OPLinkSettingsComSpeedOptions com_speed)
{
// Update the com baud rate
data->comSpeed = com_speed;
// Get the settings.
OPLinkSettingsData oplinkSettings;
OPLinkSettingsGet(&oplinkSettings);
switch (main_port) {
case OPLINKSETTINGS_REMOTEMAINPORT_DISABLED:
oplinkSettings.MainPort = OPLINKSETTINGS_MAINPORT_DISABLED;
break;
case OPLINKSETTINGS_REMOTEMAINPORT_SERIAL:
oplinkSettings.MainPort = OPLINKSETTINGS_MAINPORT_SERIAL;
break;
case OPLINKSETTINGS_REMOTEMAINPORT_PPM:
oplinkSettings.MainPort = OPLINKSETTINGS_MAINPORT_PPM;
break;
}
switch (flexi_port) {
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;
}
switch (vcp_port) {
case OPLINKSETTINGS_REMOTEVCPPORT_DISABLED:
oplinkSettings.VCPPort = OPLINKSETTINGS_VCPPORT_DISABLED;
break;
case OPLINKSETTINGS_REMOTEVCPPORT_SERIAL:
oplinkSettings.VCPPort = OPLINKSETTINGS_VCPPORT_SERIAL;
break;
}
// We will not parse/send UAVTalk if any ports are configured as Serial (except for over the USB HID port).
data->parseUAVTalk = ((oplinkSettings.MainPort != OPLINKSETTINGS_MAINPORT_SERIAL) &&
(oplinkSettings.FlexiPort != OPLINKSETTINGS_FLEXIPORT_SERIAL) &&
(oplinkSettings.VCPPort != OPLINKSETTINGS_VCPPORT_SERIAL));
// Update the OPLinkSettings object.
OPLinkSettingsSet(&oplinkSettings);
// Perform the update.
updateSettings(&oplinkSettings);
}
/**
* Update the oplink settings.
*/
static void updateSettings(OPLinkSettingsData *oplinkSettings)
{
// We can only configure the hardware once.
if (data->configured) {
return;
}
data->configured = true;
// Configure the main port
bool is_coordinator = PIOS_RFM22B_IsCoordinator(pios_rfm22b_id);
switch (oplinkSettings->MainPort) {
case OPLINKSETTINGS_MAINPORT_TELEMETRY:
case OPLINKSETTINGS_MAINPORT_SERIAL:
/* Configure the main port for uart serial */
PIOS_InitUartMainPort();
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_MAIN;
break;
case OPLINKSETTINGS_MAINPORT_PPM:
PIOS_InitPPMMainPort(is_coordinator);
break;
case OPLINKSETTINGS_MAINPORT_DISABLED:
break;
}
// Configure the flexi port
switch (oplinkSettings->FlexiPort) {
case OPLINKSETTINGS_FLEXIPORT_TELEMETRY:
case OPLINKSETTINGS_FLEXIPORT_SERIAL:
/* Configure the flexi port as uart serial */
PIOS_InitUartFlexiPort();
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_FLEXI;
break;
case OPLINKSETTINGS_FLEXIPORT_PPM:
PIOS_InitPPMFlexiPort(is_coordinator);
break;
case OPLINKSETTINGS_FLEXIPORT_DISABLED:
break;
}
// Configure the USB VCP port
switch (oplinkSettings->VCPPort) {
case OPLINKSETTINGS_VCPPORT_SERIAL:
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_USB_VCP;
break;
case OPLINKSETTINGS_VCPPORT_DISABLED:
break;
}
// Update the com baud rate.
uint32_t comBaud = 9600;
switch (data->comSpeed) {
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_TELEMETRY) {
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, comBaud);
// Is this concerning or setting object?
if (obj_per.ObjectID == OPLINKSETTINGS_OBJID) {
// Is this a save, load, or delete?
bool success = false;
switch (obj_per.Operation) {
case OBJECTPERSISTENCE_OPERATION_LOAD:
{
#if defined(PIOS_INCLUDE_FLASH_LOGFS_SETTINGS)
// Load the settings.
void *obj = UAVObjGetByID(obj_per.ObjectID);
if (obj == 0) {
success = false;
} else {
// Load selected instance
success = (UAVObjLoad(obj, obj_per.InstanceID) == 0);
}
#endif
break;
}
case OBJECTPERSISTENCE_OPERATION_SAVE:
{
#if defined(PIOS_INCLUDE_FLASH_LOGFS_SETTINGS)
void *obj = UAVObjGetByID(obj_per.ObjectID);
if (obj == 0) {
success = false;
} else {
// Save selected instance
success = UAVObjSave(obj, obj_per.InstanceID) == 0;
}
#endif
break;
}
case OBJECTPERSISTENCE_OPERATION_DELETE:
{
#if defined(PIOS_INCLUDE_FLASH_LOGFS_SETTINGS)
void *obj = UAVObjGetByID(obj_per.ObjectID);
if (obj == 0) {
success = false;
} else {
// Save selected instance
success = UAVObjDelete(obj, obj_per.InstanceID) == 0;
}
#endif
break;
}
default:
break;
}
if (success == true) {
obj_per.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED;
ObjectPersistenceSet(&obj_per);
}
}
}

View File

@ -54,6 +54,9 @@
#include <taskinfo.h>
#include <hwsettings.h>
#include <pios_flashfs.h>
#if defined(PIOS_INCLUDE_RFM22B)
#include <oplinkstatus.h>
#endif
// Flight Libraries
#include <sanitycheck.h>
@ -80,7 +83,7 @@
#if defined(PIOS_SYSTEM_STACK_SIZE)
#define STACK_SIZE_BYTES PIOS_SYSTEM_STACK_SIZE
#else
#define STACK_SIZE_BYTES 924
#define STACK_SIZE_BYTES 1024
#endif
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
@ -249,6 +252,54 @@ static void systemTask(__attribute__((unused)) void *parameters)
UAVObjEvent ev;
int delayTime = SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2);
#if defined(PIOS_INCLUDE_RFM22B)
// Update the OPLinkStatus UAVO
OPLinkStatusData oplinkStatus;
OPLinkStatusGet(&oplinkStatus);
// Get the other device stats.
PIOS_RFM2B_GetPairStats(pios_rfm22b_id, oplinkStatus.PairIDs, oplinkStatus.PairSignalStrengths, OPLINKSTATUS_PAIRIDS_NUMELEM);
// Get the stats from the radio device
struct rfm22b_stats radio_stats;
PIOS_RFM22B_GetStats(pios_rfm22b_id, &radio_stats);
// Update the OPLInk status
static bool first_time = true;
static uint16_t prev_tx_count = 0;
static uint16_t prev_rx_count = 0;
oplinkStatus.HeapRemaining = xPortGetFreeHeapSize();
oplinkStatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id);
oplinkStatus.RxGood = radio_stats.rx_good;
oplinkStatus.RxCorrected = radio_stats.rx_corrected;
oplinkStatus.RxErrors = radio_stats.rx_error;
oplinkStatus.RxMissed = radio_stats.rx_missed;
oplinkStatus.RxFailure = radio_stats.rx_failure;
oplinkStatus.TxDropped = radio_stats.tx_dropped;
oplinkStatus.TxResent = radio_stats.tx_resent;
oplinkStatus.TxFailure = radio_stats.tx_failure;
oplinkStatus.Resets = radio_stats.resets;
oplinkStatus.Timeouts = radio_stats.timeouts;
oplinkStatus.RSSI = radio_stats.rssi;
oplinkStatus.LinkQuality = radio_stats.link_quality;
if (first_time) {
first_time = false;
} else {
uint16_t tx_count = radio_stats.tx_byte_count;
uint16_t rx_count = radio_stats.rx_byte_count;
uint16_t tx_bytes = (tx_count < prev_tx_count) ? (0xffff - prev_tx_count + tx_count) : (tx_count - prev_tx_count);
uint16_t rx_bytes = (rx_count < prev_rx_count) ? (0xffff - prev_rx_count + rx_count) : (rx_count - prev_rx_count);
oplinkStatus.TXRate = (uint16_t)((float)(tx_bytes * 1000) / SYSTEM_UPDATE_PERIOD_MS);
oplinkStatus.RXRate = (uint16_t)((float)(rx_bytes * 1000) / SYSTEM_UPDATE_PERIOD_MS);
prev_tx_count = tx_count;
prev_rx_count = rx_count;
}
oplinkStatus.TXSeq = radio_stats.tx_seq;
oplinkStatus.RXSeq = radio_stats.rx_seq;
oplinkStatus.LinkState = radio_stats.link_state;
OPLinkStatusSet(&oplinkStatus);
#endif /* if defined(PIOS_INCLUDE_RFM22B) */
if (xQueueReceive(objectPersistenceQueue, &ev, delayTime) == pdTRUE) {
// If object persistence is updated call the callback
objectUpdatedCb(&ev);

View File

@ -44,6 +44,7 @@
#define STACK_SIZE_BYTES PIOS_TELEM_STACK_SIZE
#define TASK_PRIORITY_RX (tskIDLE_PRIORITY + 2)
#define TASK_PRIORITY_TX (tskIDLE_PRIORITY + 2)
#define TASK_PRIORITY_RADRX (tskIDLE_PRIORITY + 2)
#define TASK_PRIORITY_TXPRI (tskIDLE_PRIORITY + 2)
#define REQ_TIMEOUT_MS 250
#define MAX_RETRIES 2
@ -66,14 +67,23 @@ static void telemetryTxPriTask(void *parameters);
static xTaskHandle telemetryTxTaskHandle;
static xTaskHandle telemetryRxTaskHandle;
#ifdef PIOS_INCLUDE_RFM22B
static xTaskHandle radioRxTaskHandle;
#endif
static uint32_t txErrors;
static uint32_t txRetries;
static uint32_t timeOfLastObjectUpdate;
static UAVTalkConnection uavTalkCon;
#ifdef PIOS_INCLUDE_RFM22B
static UAVTalkConnection radioUavTalkCon;
#endif
// Private functions
static void telemetryTxTask(void *parameters);
static void telemetryRxTask(void *parameters);
#ifdef PIOS_INCLUDE_RFM22B
static void radioRxTask(void *parameters);
#endif
static int32_t transmitData(uint8_t *data, int32_t length);
static void registerObject(UAVObjHandle obj);
static void updateObject(UAVObjHandle obj, int32_t eventType);
@ -82,7 +92,7 @@ static void processObjEvent(UAVObjEvent *ev);
static void updateTelemetryStats();
static void gcsTelemetryStatsUpdated();
static void updateSettings();
static uint32_t getComPort();
static uint32_t getComPort(bool input);
/**
* Initialise the telemetry module
@ -103,6 +113,11 @@ int32_t TelemetryStart(void)
xTaskCreate(telemetryRxTask, (signed char *)"TelRx", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_TELEMETRYRX, telemetryRxTaskHandle);
#ifdef PIOS_INCLUDE_RFM22B
xTaskCreate(radioRxTask, (signed char *)"RadioRx", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY_RADRX, &radioRxTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_RADIORX, radioRxTaskHandle);
#endif
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
xTaskCreate(telemetryTxPriTask, (signed char *)"TelPriTx", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY_TXPRI, &telemetryTxPriTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_TELEMETRYTXPRI, telemetryTxPriTaskHandle);
@ -137,10 +152,13 @@ int32_t TelemetryInitialize(void)
// Initialise UAVTalk
uavTalkCon = UAVTalkInitialize(&transmitData);
#ifdef PIOS_INCLUDE_RFM22B
radioUavTalkCon = UAVTalkInitialize(&transmitData);
#endif
// Create periodic event that will be used to update the telemetry stats
txErrors = 0;
txRetries = 0;
txErrors = 0;
txRetries = 0;
UAVObjEvent ev;
memset(&ev, 0, sizeof(UAVObjEvent));
EventPeriodicQueueCreate(&ev, priorityQueue, STATS_UPDATE_PERIOD_MS);
@ -342,13 +360,13 @@ static void telemetryTxPriTask(__attribute__((unused)) void *parameters)
#endif
/**
* Telemetry transmit task. Processes queue events and periodic updates.
* Telemetry receive task. Processes queue events and periodic updates.
*/
static void telemetryRxTask(__attribute__((unused)) void *parameters)
{
// Task loop
while (1) {
uint32_t inputPort = getComPort();
uint32_t inputPort = getComPort(true);
if (inputPort) {
// Block until data are available
@ -367,6 +385,32 @@ static void telemetryRxTask(__attribute__((unused)) void *parameters)
}
}
#ifdef PIOS_INCLUDE_RFM22B
/**
* Radio telemetry receive task. Processes queue events and periodic updates.
*/
static void radioRxTask(__attribute__((unused)) void *parameters)
{
// Task loop
while (1) {
if (telemetryPort) {
// Block until data are available
uint8_t serial_data[1];
uint16_t bytes_to_process;
bytes_to_process = PIOS_COM_ReceiveBuffer(telemetryPort, serial_data, sizeof(serial_data), 500);
if (bytes_to_process > 0) {
for (uint8_t i = 0; i < bytes_to_process; i++) {
UAVTalkProcessInputStream(radioUavTalkCon, serial_data[i]);
}
}
} else {
vTaskDelay(5);
}
}
}
#endif /* PIOS_INCLUDE_RFM22B */
/**
* Transmit data buffer to the modem or USB port.
* \param[in] data Data buffer to send
@ -376,7 +420,7 @@ static void telemetryRxTask(__attribute__((unused)) void *parameters)
*/
static int32_t transmitData(uint8_t *data, int32_t length)
{
uint32_t outputPort = getComPort();
uint32_t outputPort = getComPort(false);
if (outputPort) {
return PIOS_COM_SendBuffer(outputPort, data, length);
@ -434,6 +478,10 @@ static void updateTelemetryStats()
// Get stats
UAVTalkGetStats(uavTalkCon, &utalkStats);
#ifdef PIOS_INCLUDE_RFM22B
UAVTalkAddStats(radioUavTalkCon, &utalkStats);
UAVTalkResetStats(radioUavTalkCon);
#endif
UAVTalkResetStats(uavTalkCon);
// Get object data
@ -553,15 +601,19 @@ static void updateSettings()
/**
* Determine input/output com port as highest priority available
* @param[in] input Returns the approproate input com port if true, else the appropriate output com port
*/
static uint32_t getComPort()
static uint32_t getComPort(bool input)
{
#ifndef PIOS_INCLUDE_RFM22B
input = false;
#endif
#if defined(PIOS_INCLUDE_USB)
if (PIOS_COM_Available(PIOS_COM_TELEM_USB)) {
return PIOS_COM_TELEM_USB;
} else
#endif /* PIOS_INCLUDE_USB */
if (PIOS_COM_Available(telemetryPort)) {
if (!input && PIOS_COM_Available(telemetryPort)) {
return telemetryPort;
} else {
return 0;

View File

@ -0,0 +1,194 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_OPLinkRCVR OPLink Receiver Input Functions
* @brief Code to read the channels within the OPLinkReceiver UAVObject
* @{
*
* @file pios_opinkrcvr.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
* @brief GCS Input functions (STM32 dependent)
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <pios.h>
#ifdef PIOS_INCLUDE_OPLINKRCVR
#include <uavobjectmanager.h>
#include <oplinkreceiver.h>
#include <pios_oplinkrcvr_priv.h>
static OPLinkReceiverData oplinkreceiverdata;
/* Provide a RCVR driver */
static int32_t PIOS_OPLinkRCVR_Get(uint32_t rcvr_id, uint8_t channel);
static void PIOS_oplinkrcvr_Supervisor(uint32_t ppm_id);
const struct pios_rcvr_driver pios_oplinkrcvr_rcvr_driver = {
.read = PIOS_OPLinkRCVR_Get,
};
/* Local Variables */
enum pios_oplinkrcvr_dev_magic {
PIOS_OPLINKRCVR_DEV_MAGIC = 0x07ab9e2544cf5029,
};
struct pios_oplinkrcvr_dev {
enum pios_oplinkrcvr_dev_magic magic;
uint8_t supv_timer;
bool Fresh;
};
static struct pios_oplinkrcvr_dev *global_oplinkrcvr_dev;
static bool PIOS_oplinkrcvr_validate(struct pios_oplinkrcvr_dev *oplinkrcvr_dev)
{
return oplinkrcvr_dev->magic == PIOS_OPLINKRCVR_DEV_MAGIC;
}
#if defined(PIOS_INCLUDE_FREERTOS)
static struct pios_oplinkrcvr_dev *PIOS_oplinkrcvr_alloc(void)
{
struct pios_oplinkrcvr_dev *oplinkrcvr_dev;
oplinkrcvr_dev = (struct pios_oplinkrcvr_dev *)pvPortMalloc(sizeof(*oplinkrcvr_dev));
if (!oplinkrcvr_dev) {
return NULL;
}
oplinkrcvr_dev->magic = PIOS_OPLINKRCVR_DEV_MAGIC;
oplinkrcvr_dev->Fresh = false;
oplinkrcvr_dev->supv_timer = 0;
/* The update callback cannot receive the device pointer, so set it in a global */
global_oplinkrcvr_dev = oplinkrcvr_dev;
return oplinkrcvr_dev;
}
#else
static struct pios_oplinkrcvr_dev pios_oplinkrcvr_devs[PIOS_OPLINKRCVR_MAX_DEVS];
static uint8_t pios_oplinkrcvr_num_devs;
static struct pios_oplinkrcvr_dev *PIOS_oplinkrcvr_alloc(void)
{
struct pios_oplinkrcvr_dev *oplinkrcvr_dev;
if (pios_oplinkrcvr_num_devs >= PIOS_OPLINKRCVR_MAX_DEVS) {
return NULL;
}
oplinkrcvr_dev = &pios_oplinkrcvr_devs[pios_oplinkrcvr_num_devs++];
oplinkrcvr_dev->magic = PIOS_OPLINKRCVR_DEV_MAGIC;
oplinkrcvr_dev->Fresh = false;
oplinkrcvr_dev->supv_timer = 0;
global_oplinkrcvr_dev = oplinkrcvr_dev;
return oplinkrcvr_dev;
}
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
static void oplinkreceiver_updated(UAVObjEvent *ev)
{
struct pios_oplinkrcvr_dev *oplinkrcvr_dev = global_oplinkrcvr_dev;
if (ev->obj == OPLinkReceiverHandle()) {
OPLinkReceiverGet(&oplinkreceiverdata);
oplinkrcvr_dev->Fresh = true;
}
}
extern int32_t PIOS_OPLinkRCVR_Init(__attribute__((unused)) uint32_t *oplinkrcvr_id)
{
struct pios_oplinkrcvr_dev *oplinkrcvr_dev;
/* Allocate the device structure */
oplinkrcvr_dev = (struct pios_oplinkrcvr_dev *)PIOS_oplinkrcvr_alloc();
if (!oplinkrcvr_dev) {
return -1;
}
for (uint8_t i = 0; i < OPLINKRECEIVER_CHANNEL_NUMELEM; i++) {
/* Flush channels */
oplinkreceiverdata.Channel[i] = PIOS_RCVR_TIMEOUT;
}
/* Register uavobj callback */
OPLinkReceiverConnectCallback(oplinkreceiver_updated);
/* Register the failsafe timer callback. */
if (!PIOS_RTC_RegisterTickCallback(PIOS_oplinkrcvr_Supervisor, (uint32_t)oplinkrcvr_dev)) {
PIOS_DEBUG_Assert(0);
}
return 0;
}
/**
* Get the value of an input channel
* \param[in] channel Number of the channel desired (zero based)
* \output PIOS_RCVR_INVALID channel not available
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
* \output >=0 channel value
*/
static int32_t PIOS_OPLinkRCVR_Get(__attribute__((unused)) uint32_t rcvr_id, uint8_t channel)
{
if (channel >= OPLINKRECEIVER_CHANNEL_NUMELEM) {
/* channel is out of range */
return PIOS_RCVR_INVALID;
}
return oplinkreceiverdata.Channel[channel];
}
static void PIOS_oplinkrcvr_Supervisor(uint32_t oplinkrcvr_id)
{
/* Recover our device context */
struct pios_oplinkrcvr_dev *oplinkrcvr_dev = (struct pios_oplinkrcvr_dev *)oplinkrcvr_id;
if (!PIOS_oplinkrcvr_validate(oplinkrcvr_dev)) {
/* Invalid device specified */
return;
}
/*
* RTC runs at 625Hz.
*/
if (++(oplinkrcvr_dev->supv_timer) < (PIOS_OPLINK_RCVR_TIMEOUT_MS * 1000 / 625)) {
return;
}
oplinkrcvr_dev->supv_timer = 0;
if (!oplinkrcvr_dev->Fresh) {
for (int32_t i = 0; i < OPLINKRECEIVER_CHANNEL_NUMELEM; i++) {
oplinkreceiverdata.Channel[i] = PIOS_RCVR_TIMEOUT;
}
}
oplinkrcvr_dev->Fresh = false;
}
#endif /* PIOS_INCLUDE_OPLINKRCVR */
/**
* @}
* @}
*/

View File

@ -113,6 +113,38 @@ int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel)
return rcvr_dev->driver->read(rcvr_dev->lower_id, channel);
}
/**
* @brief Get a semaphore that signals when a new sample is available.
* @param[in] rcvr_id driver to read from
* @param[in] channel channel to read
* @returns The semaphore, or NULL if not supported.
*/
xSemaphoreHandle PIOS_RCVR_GetSemaphore(uint32_t rcvr_id, uint8_t channel)
{
// Publicly facing API uses channel 1 for first channel
if (channel == 0) {
return NULL;
} else {
channel--;
}
if (rcvr_id == 0) {
return NULL;
}
struct pios_rcvr_dev *rcvr_dev = (struct pios_rcvr_dev *)rcvr_id;
if (!PIOS_RCVR_validate(rcvr_dev)) {
/* Undefined RCVR port for this board (see pios_board.c) */
PIOS_Assert(0);
}
if (rcvr_dev->driver->get_semaphore) {
return rcvr_dev->driver->get_semaphore(rcvr_dev->lower_id, channel);
}
return NULL;
}
#endif /* PIOS_INCLUDE_RCVR */
/**

View File

@ -34,15 +34,22 @@
// This module uses the RFM22B's internal packet handling hardware to
// encapsulate our own packet data.
//
// The RFM22B internal hardware packet handler configuration is as follows ..
// The RFM22B internal hardware packet handler configuration is as follows:
//
// 4-byte (32-bit) preamble .. alternating 0's & 1's
// 6-byte (32-bit) preamble .. alternating 0's & 1's
// 4-byte (32-bit) sync
// 1-byte packet length (number of data bytes to follow)
// 0 to 255 user data bytes
// 4 byte ECC
//
// Our own packet data will also contain it's own header and 32-bit CRC
// as a single 16-bit CRC is not sufficient for wireless comms.
// OR in PPM only mode:
//
// 6-byte (32-bit) preamble .. alternating 0's & 1's
// 4-byte (32-bit) sync
// 1-byte packet length (number of data bytes to follow)
// 1 byte valid bitmask
// 8 PPM values (0-255)
// 1 byte CRC
//
// *****************************************************************
@ -51,12 +58,8 @@
#ifdef PIOS_INCLUDE_RFM22B
#include <pios_spi_priv.h>
#include <packet_handler.h>
#if defined(PIOS_INCLUDE_GCSRCVR)
#include <gcsreceiver.h>
#endif
#include <pios_rfm22b_priv.h>
#include <pios_ppm_out_priv.h>
#include <pios_ppm_out.h>
#include <ecc.h>
/* Local Defines */
@ -66,32 +69,24 @@
#define EVENT_QUEUE_SIZE 5
#define RFM22B_DEFAULT_RX_DATARATE RFM22_datarate_9600
#define RFM22B_DEFAULT_TX_POWER RFM22_tx_pwr_txpow_0
#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
// The maximum amount of time since the last message received to consider the connection broken.
#define DISCONNECT_TIMEOUT_MS 1000 // ms
#define RFM22B_LINK_QUALITY_THRESHOLD 20
#define RFM22B_DEFAULT_MIN_CHANNEL 0
#define RFM22B_DEFAULT_MAX_CHANNEL 250
#define RFM22B_DEFAULT_CHANNEL_SET 24
#define RFM22B_PPM_ONLY_DATARATE RFM22_datarate_9600
// The maximum amount of time without activity before initiating a reset.
#define PIOS_RFM22B_SUPERVISOR_TIMEOUT 100 // ms
// The time between updates for sending stats the radio link.
#define RADIOSTATS_UPDATE_PERIOD_MS 250
// The number of stats updates that a modem can miss before it's considered disconnected
#define MAX_RADIOSTATS_MISS_COUNT 3
// The time between PPM updates
#define PPM_UPDATE_PERIOD_MS 30
#define PIOS_RFM22B_SUPERVISOR_TIMEOUT 150 // ms
// this is too adjust the RF module so that it is on frequency
#define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default
#define TX_PREAMBLE_NIBBLES 12 // 7 to 511 (number of nibbles)
#define RX_PREAMBLE_NIBBLES 6 // 5 to 31 (number of nibbles)
#define SYNC_BYTES 4
#define HEADER_BYTES 4
#define LENGTH_BYTES 1
// the size of the rf modules internal FIFO buffers
#define FIFO_SIZE 64
@ -155,24 +150,19 @@ static const uint8_t OUT_FF[64] = {
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF
};
// The randomized channel list.
static const uint8_t channel_list[] = { 68, 34, 2, 184, 166, 94, 204, 18, 47, 118, 239, 176, 5, 213, 218, 186, 104, 160, 199, 209, 231, 197, 92, 191, 88, 129, 40, 19, 93, 200, 156, 14, 247, 182, 193, 194, 208, 210, 248, 76, 244, 48, 179, 105, 25, 74, 155, 203, 39, 97, 195, 81, 83, 180, 134, 172, 235, 132, 198, 119, 207, 154, 0, 61, 140, 171, 245, 26, 95, 3, 22, 62, 169, 55, 127, 144, 45, 33, 170, 91, 158, 167, 63, 201, 41, 21, 190, 51, 103, 49, 189, 205, 240, 89, 181, 149, 6, 157, 249, 230, 115, 72, 163, 17, 29, 99, 28, 117, 219, 73, 78, 53, 69, 216, 161, 124, 110, 242, 214, 145, 13, 11, 220, 113, 138, 58, 54, 162, 237, 37, 152, 187, 232, 77, 126, 85, 38, 238, 173, 23, 188, 100, 131, 226, 31, 9, 114, 106, 221, 42, 233, 139, 4, 241, 96, 211, 8, 98, 121, 147, 24, 217, 27, 87, 122, 125, 135, 148, 178, 71, 206, 57, 141, 35, 30, 246, 159, 16, 32, 15, 229, 20, 12, 223, 150, 101, 79, 56, 102, 111, 174, 236, 137, 143, 52, 225, 64, 224, 112, 168, 243, 130, 108, 202, 123, 146, 228, 75, 46, 153, 7, 192, 175, 151, 222, 59, 82, 90, 1, 65, 109, 44, 165, 84, 43, 36, 128, 196, 67, 80, 136, 86, 70, 234, 66, 185, 10, 164, 177, 116, 50, 107, 183, 215, 212, 60, 227, 133, 120, 142 };
/* Local function forwared declarations */
static void pios_rfm22_task(void *parameters);
static bool pios_rfm22_readStatus(struct pios_rfm22b_dev *rfm22b_dev);
static void pios_rfm22_setDatarate(struct pios_rfm22b_dev *rfm22b_dev, enum rfm22b_datarate datarate, bool data_whitening);
static void pios_rfm22_setDatarate(struct pios_rfm22b_dev *rfm22b_dev);
static void rfm22_rxFailure(struct pios_rfm22b_dev *rfm22b_dev);
static void pios_rfm22_inject_event(struct pios_rfm22b_dev *rfm22b_dev, enum pios_radio_event event, bool inISR);
static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event rfm22_receiveStatus(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event rfm22_receiveAck(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event rfm22_receiveNack(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event rfm22_sendAck(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event rfm22_sendNack(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event rfm22_requestConnection(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event radio_setRxMode(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event radio_rxData(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *rfm22b_dev, PHPacketHandle p, uint16_t rx_len);
static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *rfm22b_dev, uint8_t *p, uint16_t rx_len);
static enum pios_radio_event radio_txStart(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event radio_txData(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event rfm22_txFailure(struct pios_rfm22b_dev *rfm22b_dev);
@ -181,17 +171,19 @@ static void rfm22_process_event(struct pios_rfm22b_dev *rfm22b_dev, enum pios_ra
static enum pios_radio_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev);
static enum pios_radio_event rfm22_fatal_error(struct pios_rfm22b_dev *rfm22b_dev);
static void rfm22_sendStatus(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 rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint32_t min_frequency, uint32_t max_frequency, uint32_t step_size);
static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint8_t init_chan);
static bool rfm22_setFreqHopChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t channel);
static void rfm22_updatePairStatus(struct pios_rfm22b_dev *radio_dev);
static void rfm22_calculateLinkQuality(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 bool rfm22_isCoordinator(struct pios_rfm22b_dev *rfm22b_dev);
static uint32_t rfm22_destinationID(struct pios_rfm22b_dev *rfm22b_dev);
static bool rfm22_timeToSend(struct pios_rfm22b_dev *rfm22b_dev);
static void rfm22_synchronizeClock(struct pios_rfm22b_dev *rfm22b_dev);
static portTickType rfm22_coordinatorTime(struct pios_rfm22b_dev *rfm22b_dev, portTickType ticks);
static uint8_t rfm22_calcChannel(struct pios_rfm22b_dev *rfm22b_dev);
static uint8_t rfm22_calcChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t index);
static uint8_t rfm22_calcChannelFromClock(struct pios_rfm22b_dev *rfm22b_dev);
static bool rfm22_changeChannel(struct pios_rfm22b_dev *rfm22b_dev);
static void rfm22_clearLEDs();
@ -212,79 +204,41 @@ static uint8_t rfm22_read(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr);
/* The state transition table */
static const struct pios_rfm22b_transition rfm22b_transitions[RADIO_STATE_NUM_STATES] = {
// Initialization thread
[RADIO_STATE_UNINITIALIZED] = {
[RADIO_STATE_UNINITIALIZED] = {
.entry_fn = 0,
.next_state = {
.next_state = {
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
},
},
[RADIO_STATE_INITIALIZING] = {
[RADIO_STATE_INITIALIZING] = {
.entry_fn = rfm22_init,
.next_state = {
.next_state = {
[RADIO_EVENT_INITIALIZED] = RADIO_STATE_RX_MODE,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_REQUESTING_CONNECTION] = {
.entry_fn = rfm22_requestConnection,
.next_state = {
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR
},
},
[RADIO_STATE_ACCEPTING_CONNECTION] = {
.entry_fn = rfm22_acceptConnection,
.next_state = {
[RADIO_EVENT_DEFAULT] = RADIO_STATE_SENDING_ACK,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_RX_MODE] = {
[RADIO_STATE_RX_MODE] = {
.entry_fn = radio_setRxMode,
.next_state = {
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
[RADIO_EVENT_ACK_TIMEOUT] = RADIO_STATE_RECEIVING_NACK,
.next_state = {
[RADIO_EVENT_INT_RECEIVED] = RADIO_STATE_RX_DATA,
[RADIO_EVENT_FAILURE] = RADIO_STATE_RX_FAILURE,
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
[RADIO_EVENT_RX_MODE] = RADIO_STATE_RX_MODE,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_RX_DATA] = {
[RADIO_STATE_RX_DATA] = {
.entry_fn = radio_rxData,
.next_state = {
[RADIO_EVENT_INT_RECEIVED] = RADIO_STATE_RX_DATA,
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
[RADIO_EVENT_ACK_TIMEOUT] = RADIO_STATE_RECEIVING_NACK,
[RADIO_EVENT_RX_COMPLETE] = RADIO_STATE_SENDING_ACK,
[RADIO_EVENT_RX_MODE] = RADIO_STATE_RX_MODE,
[RADIO_EVENT_STATUS_RECEIVED] = RADIO_STATE_RECEIVING_STATUS,
[RADIO_EVENT_CONNECTION_REQUESTED] = RADIO_STATE_ACCEPTING_CONNECTION,
[RADIO_EVENT_PACKET_ACKED] = RADIO_STATE_RECEIVING_ACK,
[RADIO_EVENT_PACKET_NACKED] = RADIO_STATE_RECEIVING_NACK,
[RADIO_EVENT_FAILURE] = RADIO_STATE_RX_FAILURE,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_RECEIVING_ACK] = {
.entry_fn = rfm22_receiveAck,
.next_state = {
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
.next_state = {
[RADIO_EVENT_INT_RECEIVED] = RADIO_STATE_RX_DATA,
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
[RADIO_EVENT_RX_COMPLETE] = RADIO_STATE_TX_START,
[RADIO_EVENT_RX_MODE] = RADIO_STATE_RX_MODE,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
@ -292,30 +246,9 @@ static const struct pios_rfm22b_transition rfm22b_transitions[RADIO_STATE_NUM_ST
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_RECEIVING_NACK] = {
.entry_fn = rfm22_receiveNack,
.next_state = {
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_RECEIVING_STATUS] = {
.entry_fn = rfm22_receiveStatus,
.next_state = {
[RADIO_EVENT_RX_COMPLETE] = RADIO_STATE_TX_START,
[RADIO_EVENT_REQUEST_CONNECTION] = RADIO_STATE_REQUESTING_CONNECTION,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_TX_START] = {
[RADIO_STATE_TX_START] = {
.entry_fn = radio_txStart,
.next_state = {
.next_state = {
[RADIO_EVENT_INT_RECEIVED] = RADIO_STATE_TX_DATA,
[RADIO_EVENT_RX_MODE] = RADIO_STATE_RX_MODE,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
@ -324,21 +257,20 @@ static const struct pios_rfm22b_transition rfm22b_transitions[RADIO_STATE_NUM_ST
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_TX_DATA] = {
[RADIO_STATE_TX_DATA] = {
.entry_fn = radio_txData,
.next_state = {
.next_state = {
[RADIO_EVENT_INT_RECEIVED] = RADIO_STATE_TX_DATA,
[RADIO_EVENT_RX_MODE] = RADIO_STATE_RX_MODE,
[RADIO_EVENT_FAILURE] = RADIO_STATE_TX_FAILURE,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_TX_FAILURE] = {
[RADIO_STATE_TX_FAILURE] = {
.entry_fn = rfm22_txFailure,
.next_state = {
.next_state = {
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
@ -346,29 +278,9 @@ static const struct pios_rfm22b_transition rfm22b_transitions[RADIO_STATE_NUM_ST
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_SENDING_ACK] = {
.entry_fn = rfm22_sendAck,
.next_state = {
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_SENDING_NACK] = {
.entry_fn = rfm22_sendNack,
.next_state = {
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
[RADIO_EVENT_TIMEOUT] = RADIO_STATE_TIMEOUT,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_TIMEOUT] = {
[RADIO_STATE_TIMEOUT] = {
.entry_fn = rfm22_timeout,
.next_state = {
.next_state = {
[RADIO_EVENT_TX_START] = RADIO_STATE_TX_START,
[RADIO_EVENT_RX_MODE] = RADIO_STATE_RX_MODE,
[RADIO_EVENT_ERROR] = RADIO_STATE_ERROR,
@ -376,47 +288,60 @@ static const struct pios_rfm22b_transition rfm22b_transitions[RADIO_STATE_NUM_ST
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_ERROR] = {
[RADIO_STATE_ERROR] = {
.entry_fn = rfm22_error,
.next_state = {
.next_state = {
[RADIO_EVENT_INITIALIZE] = RADIO_STATE_INITIALIZING,
[RADIO_EVENT_FATAL_ERROR] = RADIO_STATE_FATAL_ERROR,
},
},
[RADIO_STATE_FATAL_ERROR] = {
[RADIO_STATE_FATAL_ERROR] = {
.entry_fn = rfm22_fatal_error,
.next_state = {},
.next_state = {},
},
};
// xtal 10 ppm, 434MHz
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, 1 };
static const uint32_t data_rate[] = {
9600, // 96 kbps, 433 HMz, 30 khz freq dev
19200, // 19.2 kbps, 433 MHz, 45 khz freq dev
32000, // 32 kbps, 433 MHz, 45 khz freq dev
57600, // 57.6 kbps, 433 MHz, 45 khz freq dev
64000, // 64 kbps, 433 MHz, 45 khz freq dev
100000, // 100 kbps, 433 MHz, 60 khz freq dev
128000, // 128 kbps, 433 MHz, 90 khz freq dev
192000, // 192 kbps, 433 MHz, 128 khz freq dev
256000, // 256 kbps, 433 MHz, 150 khz freq dev
};
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_1C[] = { 0x01, 0x05, 0x06, 0x95, 0x95, 0x81, 0x88, 0x8B, 0x8D }; // rfm22_if_filter_bandwidth
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, 0x0A, 0x02 }; // rfm22_afc_timing_control
static const uint8_t reg_1D[] = { 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40 }; // rfm22_afc_loop_gearshift_override
static const uint8_t reg_1E[] = { 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, 0x03 }; // rfm22_clk_recovery_gearshift_override
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, 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, 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, 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, 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, 0x6E, 0xFF, 0x74, 0xFF, 0xFF }; // rfm22_clk_recovery_timing_loop_gain0
static const uint8_t reg_1F[] = { 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03 }; // rfm22_clk_recovery_gearshift_override
static const uint8_t reg_20[] = { 0xA1, 0xD0, 0x7D, 0x68, 0x5E, 0x78, 0x5E, 0x3F, 0x2F }; // rfm22_clk_recovery_oversampling_ratio
static const uint8_t reg_21[] = { 0x20, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x02, 0x02 }; // rfm22_clk_recovery_offset2
static const uint8_t reg_22[] = { 0x4E, 0x9D, 0x06, 0x3A, 0x5D, 0x11, 0x5D, 0x0C, 0xBB }; // rfm22_clk_recovery_offset1
static const uint8_t reg_23[] = { 0xA5, 0x49, 0x25, 0x93, 0x86, 0x11, 0x86, 0x4A, 0x0D }; // rfm22_clk_recovery_offset0
static const uint8_t reg_24[] = { 0x00, 0x00, 0x01, 0x03, 0x03, 0x03, 0x03, 0x06, 0x07 }; // rfm22_clk_recovery_timing_loop_gain1
static const uint8_t reg_25[] = { 0x34, 0x88, 0x77, 0x29, 0xE2, 0x90, 0xE2, 0x1A, 0xFF }; // rfm22_clk_recovery_timing_loop_gain0
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_2A[] = { 0x1E, 0x24, 0x28, 0x3C, 0x3C, 0x50, 0x50, 0x50, 0x50 }; // rfm22_afc_limiter .. AFC_pull_in_range = <20>AFCLimiter[7:0] x (hbsel+1) x 625 Hz
static const uint8_t reg_58[] = { 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80 }; // rfm22_cpcuu
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_58[] = { 0x80, 0x80, 0x80, 0x80, 0x80, 0xC0, 0xC0, 0xC0, 0xED }; // rfm22_cpcuu
static const uint8_t reg_69[] = { 0x60, 0x60, 0x60, 0x60, 0x60, 0x60, 0x60, 0x60, 0x60 }; // rfm22_agc_override1
static const uint8_t reg_6E[] = { 0x4E, 0x9D, 0x08, 0x0E, 0x10, 0x19, 0x20, 0x31, 0x41 }; // rfm22_tx_data_rate1
static const uint8_t reg_6F[] = { 0xA5, 0x49, 0x31, 0xBF, 0x62, 0x9A, 0xC5, 0x27, 0x89 }; // rfm22_tx_data_rate0
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, 0x23 }; // rfm22_modulation_mode_control2
static const uint8_t reg_70[] = { 0x2C, 0x2C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C }; // rfm22_modulation_mode_control1
static const uint8_t reg_71[] = { 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, 0x2E, 0x33, 0x66, 0x9A, 0xCD }; // rfm22_frequency_deviation
static const uint8_t reg_72[] = { 0x30, 0x48, 0x48, 0x48, 0x48, 0x60, 0x90, 0xCD, 0x0F }; // rfm22_frequency_deviation
static const uint8_t packet_time[] = { 80, 40, 25, 15, 13, 10, 8, 6, 5 };
static const uint8_t packet_time_ppm[] = { 26, 25, 25, 15, 13, 10, 8, 6, 5 };
static const uint8_t num_channels[] = { 4, 4, 4, 6, 8, 8, 10, 12, 16 };
static struct pios_rfm22b_dev *g_rfm22b_dev = NULL;
@ -451,15 +376,18 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
rfm22b_dev->spi_id = spi_id;
// Initialize our configuration parameters
rfm22b_dev->send_ppm = false;
rfm22b_dev->datarate = RFM22B_DEFAULT_RX_DATARATE;
rfm22b_dev->tx_power = RFM22B_DEFAULT_TX_POWER;
rfm22b_dev->coordinator = false;
rfm22b_dev->coordinatorID = 0;
// Initialize the com callbacks.
rfm22b_dev->com_config_cb = NULL;
rfm22b_dev->rx_in_cb = NULL;
rfm22b_dev->tx_out_cb = NULL;
// Initialzie the PPM callback.
rfm22b_dev->ppm_callback = NULL;
// Initialize the stats.
rfm22b_dev->stats.packets_per_sec = 0;
rfm22b_dev->stats.rx_good = 0;
@ -476,18 +404,12 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
rfm22b_dev->stats.rx_seq = 0;
rfm22b_dev->stats.tx_failure = 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;
// Initialize the channels.
PIOS_RFM22B_SetChannelConfig(*rfm22b_id, RFM22B_DEFAULT_RX_DATARATE, RFM22B_DEFAULT_MIN_CHANNEL,
RFM22B_DEFAULT_MAX_CHANNEL, RFM22B_DEFAULT_CHANNEL_SET, false, false, false, false);
// Create the event queue
rfm22b_dev->eventQueue = xQueueCreate(EVENT_QUEUE_SIZE, sizeof(enum pios_radio_event));
rfm22b_dev->eventQueue = xQueueCreate(EVENT_QUEUE_SIZE, sizeof(enum pios_radio_event));
// Bind the configuration to the device instance
rfm22b_dev->cfg = *cfg;
@ -508,11 +430,6 @@ 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;
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.
PIOS_EXTI_Init(cfg->exti_cfg);
@ -581,19 +498,13 @@ uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id)
}
/**
* Returns true if the modem is configured as a coordinator.
* Are we connected to the remote modem?
*
* @param[in] rfm22b_id The RFM22B device index.
* @return True if the modem is configured as a coordinator.
* @param[in] rfm22b_dev The device structure
*/
bool PIOS_RFM22B_IsCoordinator(uint32_t rfm22b_id)
static bool rfm22_isConnected(struct pios_rfm22b_dev *rfm22b_dev)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (PIOS_RFM22B_Validate(rfm22b_dev)) {
return rfm22b_dev->coordinator;
}
return false;
return (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED) || (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTING);
}
/**
@ -629,85 +540,91 @@ void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr)
}
/**
* Sets the radio frequency range and initial frequency
* Sets the range and number of channels to use for the radio.
* The channels are 0 to 255 divided across the 430-440 MHz range.
* The number of channels configured will be spread across the selected channel range.
* The channel spacing is 10MHz / 250 = 40kHz
*
* @param[in] rfm22b_id The RFM22B device index.
* @param[in] min_freq The minimum frequency
* @param[in] max_freq The maximum frequency
* @param[in] step_size The channel step size
* @param[in] datarate The desired datarate.
* @param[in] min_chan The minimum channel.
* @param[in] max_chan The maximum channel.
* @param[in] chan_set The "seed" for selecting a channel sequence.
* @param[in] coordinator Is this modem an coordinator.
* @param[in] ppm_mode Should this modem send/receive ppm packets?
* @param[in] oneway Only the coordinator can send packets if true.
*/
void PIOS_RFM22B_SetFrequencyRange(uint32_t rfm22b_id, uint32_t min_freq, uint32_t max_freq, uint32_t step_size)
void PIOS_RFM22B_SetChannelConfig(uint32_t rfm22b_id, enum rfm22b_datarate datarate, uint8_t min_chan, uint8_t max_chan, uint8_t chan_set, bool coordinator, bool oneway, bool ppm_mode, bool ppm_only)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return;
}
rfm22b_dev->con_packet.min_frequency = min_freq;
rfm22b_dev->con_packet.max_frequency = max_freq;
rfm22b_dev->con_packet.channel_spacing = step_size;
ppm_mode = ppm_mode || ppm_only;
rfm22b_dev->coordinator = coordinator;
rfm22b_dev->ppm_send_mode = ppm_mode && coordinator;
rfm22b_dev->ppm_recv_mode = ppm_mode && !coordinator;
if (ppm_mode && (datarate <= RFM22B_PPM_ONLY_DATARATE)) {
ppm_only = true;
}
rfm22b_dev->ppm_only_mode = ppm_only;
if (ppm_only) {
rfm22b_dev->one_way_link = true;
datarate = RFM22B_PPM_ONLY_DATARATE;
rfm22b_dev->datarate = RFM22B_PPM_ONLY_DATARATE;
} else {
rfm22b_dev->one_way_link = oneway;
rfm22b_dev->datarate = datarate;
}
rfm22b_dev->packet_time = (ppm_mode ? packet_time_ppm[datarate] : packet_time[datarate]);
// Find the first N channels that meet the min/max criteria out of the random channel list.
uint8_t num_found = 0;
for (uint16_t i = 0; (i < RFM22B_NUM_CHANNELS) && (num_found < num_channels[datarate]); ++i) {
uint8_t idx = (i + chan_set) % RFM22B_NUM_CHANNELS;
uint8_t chan = channel_list[idx];
if ((chan >= min_chan) && (chan <= max_chan)) {
rfm22b_dev->channels[num_found++] = chan;
}
}
// Calculate the maximum packet length from the datarate.
float bytes_per_period = (float)data_rate[datarate] * (float)(rfm22b_dev->packet_time - 2) / 9000;
rfm22b_dev->max_packet_len = bytes_per_period - TX_PREAMBLE_NIBBLES / 2 - SYNC_BYTES - HEADER_BYTES - LENGTH_BYTES;
if (rfm22b_dev->max_packet_len > RFM22B_MAX_PACKET_LEN) {
rfm22b_dev->max_packet_len = RFM22B_MAX_PACKET_LEN;
}
}
/**
* Sets the initial radio frequency range
* Set a modem to be a coordinator or not.
*
* @param[in] rfm22b_id The RFM22B device index.
* @param[in] init_freq The initial frequency
* @param[in] rfm22b_id The RFM22B device index.
* @param[in] coordinator If true, this modem will be configured as a coordinator.
*/
void PIOS_RFM22B_SetInitialFrequency(uint32_t rfm22b_id, uint32_t init_freq)
extern 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;
if (PIOS_RFM22B_Validate(rfm22b_dev)) {
rfm22b_dev->coordinator = coordinator;
}
rfm22b_dev->init_frequency = init_freq;
}
/**
* Set the com port configuration callback (to receive com configuration over the air)
* Sets the device coordinator ID.
*
* @param[in] rfm22b_id The rfm22b device.
* @param[in] cb A pointer to the callback function
* @param[in] rfm22b_id The RFM22B device index.
* @param[in] coord_id The coordinator ID.
*/
void PIOS_RFM22B_SetComConfigCallback(uint32_t rfm22b_id, PIOS_RFM22B_ComConfigCallback cb)
void PIOS_RFM22B_SetCoordinatorID(uint32_t rfm22b_id, uint32_t coord_id)
{
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] bindingPairIDs The array of binding IDs.
* @param[in] mainPortSettings The array of main com port configurations.
* @param[in] flexiPortSettings The array of flexi com port configurations.
* @param[in] vcpPortSettings The array of VCP com port configurations.
* @param[in] comSpeeds The array of com port speeds.
*/
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;
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return;
}
// 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);
if (PIOS_RFM22B_Validate(rfm22b_dev)) {
rfm22b_dev->coordinatorID = coord_id;
}
}
@ -728,17 +645,7 @@ void PIOS_RFM22B_GetStats(uint32_t rfm22b_id, struct rfm22b_stats *stats)
// Calculate the current link quality
rfm22_calculateLinkQuality(rfm22b_dev);
// We are connected if our destination ID is in the pair stats.
if (rfm22b_dev->destination_id != 0xffffffff) {
for (uint8_t i = 0; i < OPLINKSTATUS_PAIRIDS_NUMELEM; ++i) {
if ((rfm22b_dev->pair_stats[i].pairID == rfm22b_dev->destination_id) &&
(rfm22b_dev->pair_stats[i].rssi > -127)) {
rfm22b_dev->stats.rssi = rfm22b_dev->pair_stats[i].rssi;
rfm22b_dev->stats.afc_correction = rfm22b_dev->pair_stats[i].afc_correction;
break;
}
}
}
// Return the stats.
*stats = rfm22b_dev->stats;
}
@ -780,7 +687,7 @@ bool PIOS_RFM22B_LinkStatus(uint32_t rfm22b_id)
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return false;
}
return rfm22_isConnected(rfm22b_dev) && (rfm22b_dev->stats.link_quality > RFM22B_LINK_QUALITY_THRESHOLD);
return rfm22b_dev->stats.link_quality > RFM22B_LINK_QUALITY_THRESHOLD;
}
/**
@ -790,18 +697,13 @@ bool PIOS_RFM22B_LinkStatus(uint32_t rfm22b_id)
* @param[in] p The packet to receive into.
* @return true if Rx mode was entered sucessfully.
*/
bool PIOS_RFM22B_ReceivePacket(uint32_t rfm22b_id, PHPacketHandle p)
bool PIOS_RFM22B_ReceivePacket(uint32_t rfm22b_id, uint8_t *p)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return false;
}
// Are we already in Rx mode?
if ((rfm22b_dev->rfm22b_state == RFM22B_STATE_RX_MODE) || (rfm22b_dev->rfm22b_state == RFM22B_STATE_RX_WAIT)) {
return false;
}
rfm22b_dev->rx_packet_handle = p;
// Claim the SPI bus.
@ -855,7 +757,7 @@ bool PIOS_RFM22B_ReceivePacket(uint32_t rfm22b_id, PHPacketHandle p)
* @param[in] p The packet to transmit.
* @return true if there if the packet was queued for transmission.
*/
bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, PHPacketHandle p)
bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, uint8_t *p, uint8_t len)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
@ -863,8 +765,9 @@ bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, PHPacketHandle p)
return false;
}
rfm22b_dev->tx_packet = p;
rfm22b_dev->packet_start_ticks = xTaskGetTickCount();
rfm22b_dev->tx_packet_handle = p;
rfm22b_dev->stats.tx_byte_count += len;
rfm22b_dev->packet_start_ticks = xTaskGetTickCount();
if (rfm22b_dev->packet_start_ticks == 0) {
rfm22b_dev->packet_start_ticks = 1;
}
@ -877,23 +780,23 @@ bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, PHPacketHandle p)
rfm22_write(rfm22b_dev, RFM22_interrupt_enable2, 0x00);
// set the tx power
rfm22b_dev->tx_power = 0x7;
rfm22_write(rfm22b_dev, RFM22_tx_power, RFM22_tx_pwr_lna_sw | rfm22b_dev->tx_power);
// TUNE mode
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon);
// Queue the data up for sending
rfm22b_dev->tx_data_wr = PH_PACKET_SIZE(rfm22b_dev->tx_packet);
rfm22b_dev->tx_data_wr = len;
RX_LED_OFF;
// Set the destination address in the transmit header.
// The destination address is the first 4 bytes of the message.
uint8_t *tx_buffer = (uint8_t *)(rfm22b_dev->tx_packet);
rfm22_write(rfm22b_dev, RFM22_transmit_header0, tx_buffer[0]);
rfm22_write(rfm22b_dev, RFM22_transmit_header1, tx_buffer[1]);
rfm22_write(rfm22b_dev, RFM22_transmit_header2, tx_buffer[2]);
rfm22_write(rfm22b_dev, RFM22_transmit_header3, tx_buffer[3]);
uint32_t id = rfm22_destinationID(rfm22b_dev);
rfm22_write(rfm22b_dev, RFM22_transmit_header0, id & 0xff);
rfm22_write(rfm22b_dev, RFM22_transmit_header1, (id >> 8) & 0xff);
rfm22_write(rfm22b_dev, RFM22_transmit_header2, (id >> 16) & 0xff);
rfm22_write(rfm22b_dev, RFM22_transmit_header3, (id >> 24) & 0xff);
// FIFO mode, GFSK modulation
uint8_t fd_bit = rfm22_read(rfm22b_dev, RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
@ -904,9 +807,10 @@ bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, PHPacketHandle p)
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, 0x00);
// Set the total number of data bytes we are going to transmit.
rfm22_write(rfm22b_dev, RFM22_transmit_packet_length, rfm22b_dev->tx_data_wr);
rfm22_write(rfm22b_dev, RFM22_transmit_packet_length, len);
// Add some data to the chips TX FIFO before enabling the transmitter
uint8_t *tx_buffer = rfm22b_dev->tx_packet_handle;
rfm22_assertCs(rfm22b_dev);
PIOS_SPI_TransferByte(rfm22b_dev->spi_id, RFM22_fifo_access | 0x80);
int bytes_to_write = (rfm22b_dev->tx_data_wr - rfm22b_dev->tx_data_rd);
@ -929,6 +833,10 @@ bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, PHPacketHandle p)
TX_LED_ON;
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
D1_LED_ON;
#endif
return true;
}
@ -951,11 +859,10 @@ pios_rfm22b_int_result PIOS_RFM22B_ProcessTx(uint32_t rfm22b_id)
return PIOS_RFM22B_INT_FAILURE;
}
// TX FIFO almost empty, it needs filling up
if (rfm22b_dev->status_regs.int_status_1.tx_fifo_almost_empty) {
// Add data to the TX FIFO buffer
uint8_t *tx_buffer = (uint8_t *)(rfm22b_dev->tx_packet);
uint8_t *tx_buffer = rfm22b_dev->tx_packet_handle;
uint16_t max_bytes = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1;
rfm22_claimBus(rfm22b_dev);
rfm22_assertCs(rfm22b_dev);
@ -971,7 +878,6 @@ pios_rfm22b_int_result PIOS_RFM22B_ProcessTx(uint32_t rfm22b_id)
} else if (rfm22b_dev->status_regs.int_status_1.packet_sent_interrupt) {
// Transition out of Tx mode.
rfm22b_dev->rfm22b_state = RFM22B_STATE_TRANSITION;
return PIOS_RFM22B_TX_COMPLETE;
}
@ -991,7 +897,7 @@ pios_rfm22b_int_result PIOS_RFM22B_ProcessRx(uint32_t rfm22b_id)
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return PIOS_RFM22B_INT_FAILURE;
}
uint8_t *rx_buffer = (uint8_t *)(rfm22b_dev->rx_packet_handle);
uint8_t *rx_buffer = rfm22b_dev->rx_packet_handle;
pios_rfm22b_int_result ret = PIOS_RFM22B_INT_SUCCESS;
// Read the device status registers
@ -1015,7 +921,14 @@ pios_rfm22b_int_result PIOS_RFM22B_ProcessRx(uint32_t rfm22b_id)
// read the total length of the packet data
uint32_t len = rfm22_read(rfm22b_dev, RFM22_received_packet_length);
// their must still be data in the RX FIFO we need to get
// The received packet is going to be larger than the receive buffer
if (len > rfm22b_dev->max_packet_len) {
rfm22_releaseBus(rfm22b_dev);
rfm22_rxFailure(rfm22b_dev);
return PIOS_RFM22B_INT_FAILURE;
}
// there must still be data in the RX FIFO we need to get
if (rfm22b_dev->rx_buffer_wr < len) {
int32_t bytes_to_read = len - rfm22b_dev->rx_buffer_wr;
// Fetch the data from the RX FIFO
@ -1026,6 +939,12 @@ pios_rfm22b_int_result PIOS_RFM22B_ProcessRx(uint32_t rfm22b_id)
rfm22_deassertCs(rfm22b_dev);
}
// Read the packet header (destination ID)
rfm22b_dev->rx_destination_id = rfm22_read(rfm22b_dev, RFM22_received_header0);
rfm22b_dev->rx_destination_id |= (rfm22_read(rfm22b_dev, RFM22_received_header1) << 8);
rfm22b_dev->rx_destination_id |= (rfm22_read(rfm22b_dev, RFM22_received_header2) << 16);
rfm22b_dev->rx_destination_id |= (rfm22_read(rfm22b_dev, RFM22_received_header3) << 24);
// Release the SPI bus.
rfm22_releaseBus(rfm22b_dev);
@ -1038,6 +957,9 @@ pios_rfm22b_int_result PIOS_RFM22B_ProcessRx(uint32_t rfm22b_id)
// Increment the total byte received count.
rfm22b_dev->stats.rx_byte_count += rfm22b_dev->rx_buffer_wr;
// Update the pair status with this packet.
rfm22_updatePairStatus(rfm22b_dev);
// We're finished with Rx mode
rfm22b_dev->rfm22b_state = RFM22B_STATE_TRANSITION;
@ -1059,6 +981,13 @@ pios_rfm22b_int_result PIOS_RFM22B_ProcessRx(uint32_t rfm22b_id)
return PIOS_RFM22B_INT_FAILURE;
}
// The received packet is going to be larger than the receive buffer
if ((rfm22b_dev->rx_buffer_wr + RX_FIFO_HI_WATERMARK) > rfm22b_dev->max_packet_len) {
rfm22_releaseBus(rfm22b_dev);
rfm22_rxFailure(rfm22b_dev);
return PIOS_RFM22B_INT_FAILURE;
}
// Fetch the data from the RX FIFO
rfm22_assertCs(rfm22b_dev);
PIOS_SPI_TransferByte(rfm22b_dev->spi_id, RFM22_fifo_access & 0x7F);
@ -1074,15 +1003,19 @@ pios_rfm22b_int_result PIOS_RFM22B_ProcessRx(uint32_t rfm22b_id)
} else if (rfm22b_dev->status_regs.int_status_2.valid_preamble_detected) {
// Valid preamble detected
RX_LED_ON;
// Sync word detected
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
D2_LED_ON;
#endif // PIOS_RFM22B_DEBUG_ON_TELEM
rfm22b_dev->packet_start_ticks = xTaskGetTickCount();
if (rfm22b_dev->packet_start_ticks == 0) {
rfm22b_dev->packet_start_ticks = 1;
}
// We detected the preamble, now wait for sync.
rfm22b_dev->rfm22b_state = RFM22B_STATE_RX_WAIT_SYNC;
} else if (rfm22b_dev->status_regs.int_status_2.sync_word_detected) {
// Sync word detected
// Claim the SPI bus.
rfm22_claimBus(rfm22b_dev);
@ -1112,16 +1045,62 @@ pios_rfm22b_int_result PIOS_RFM22B_ProcessRx(uint32_t rfm22b_id)
return PIOS_RFM22B_INT_FAILURE;
}
// Set the packet start time if necessary.
if ((rfm22b_dev->packet_start_ticks == 0) &&
((rfm22b_dev->rfm22b_state == RFM22B_STATE_RX_WAIT_SYNC) || (rfm22b_dev->rfm22b_state == RFM22B_STATE_RX_WAIT_SYNC))) {
rfm22b_dev->packet_start_ticks = xTaskGetTickCount();
if (rfm22b_dev->packet_start_ticks == 0) {
rfm22b_dev->packet_start_ticks = 1;
}
return ret;
}
/**
* Set the PPM packet received callback.
*
* @param[in] rfm22b_dev The RFM22B device ID.
* @param[in] cb The callback function pointer.
*/
void PIOS_RFM22B_SetPPMCallback(uint32_t rfm22b_id, PPMReceivedCallback cb)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return;
}
return ret;
rfm22b_dev->ppm_callback = cb;
}
/**
* Set the PPM values to be transmitted.
*
* @param[in] rfm22b_dev The RFM22B device ID.
* @param[in] channels The PPM channel values.
*/
extern void PIOS_RFM22B_PPMSet(uint32_t rfm22b_id, int16_t *channels)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return;
}
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
rfm22b_dev->ppm[i] = channels[i];
}
}
/**
* Fetch the PPM values that have been received.
*
* @param[in] rfm22b_dev The RFM22B device structure pointer.
* @param[out] channels The PPM channel values.
*/
extern void PIOS_RFM22B_PPMGet(uint32_t rfm22b_id, int16_t *channels)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return;
}
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
channels[i] = rfm22b_dev->ppm[i];
}
}
/**
@ -1151,9 +1130,7 @@ static void pios_rfm22_task(void *parameters)
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return;
}
portTickType lastEventTicks = xTaskGetTickCount();
portTickType lastStatusTicks = lastEventTicks;
portTickType lastPPMTicks = lastEventTicks;
portTickType lastEventTicks = xTaskGetTickCount();
while (1) {
#if defined(PIOS_INCLUDE_WDG) && defined(PIOS_WDG_RFM22B)
@ -1178,65 +1155,40 @@ static void pios_rfm22_task(void *parameters)
// Has it been too long since the last event?
portTickType curTicks = xTaskGetTickCount();
if (pios_rfm22_time_difference_ms(lastEventTicks, curTicks) > PIOS_RFM22B_SUPERVISOR_TIMEOUT) {
// Transsition through an error event.
rfm22_process_event(rfm22b_dev, RADIO_EVENT_ERROR);
// Clear the event queue.
enum pios_radio_event event;
while (xQueueReceive(rfm22b_dev->eventQueue, &event, 0) == pdTRUE) {
// Do nothing;
}
lastEventTicks = xTaskGetTickCount();
// Transsition through an error event.
rfm22_process_event(rfm22b_dev, RADIO_EVENT_ERROR);
}
}
// Change channels if necessary.
if (PIOS_RFM22B_InRxWait((uint32_t)rfm22b_dev)) {
rfm22_changeChannel(rfm22b_dev);
if (rfm22_changeChannel(rfm22b_dev)) {
rfm22_process_event(rfm22b_dev, RADIO_EVENT_RX_MODE);
}
portTickType curTicks = xTaskGetTickCount();
uint32_t last_rec_ms = (rfm22b_dev->rx_complete_ticks == 0) ? 0 : pios_rfm22_time_difference_ms(rfm22b_dev->rx_complete_ticks, curTicks);
// Have we been sending / receiving this packet too long?
if ((rfm22b_dev->packet_start_ticks > 0) &&
(pios_rfm22_time_difference_ms(rfm22b_dev->packet_start_ticks, curTicks) > (rfm22b_dev->max_packet_time * 3))) {
rfm22_process_event(rfm22b_dev, RADIO_EVENT_TIMEOUT);
} else if (last_rec_ms > DISCONNECT_TIMEOUT_MS) {
// Has it been too long since we received a packet
rfm22_process_event(rfm22b_dev, RADIO_EVENT_ERROR);
} else {
// Are we waiting for an ACK?
if (rfm22b_dev->prev_tx_packet) {
// Should we resend the packet?
if ((pios_rfm22_time_difference_ms(rfm22b_dev->tx_complete_ticks, curTicks) > rfm22b_dev->max_ack_delay) &&
PIOS_RFM22B_InRxWait((uint32_t)rfm22b_dev)) {
rfm22b_dev->tx_complete_ticks = curTicks;
rfm22_process_event(rfm22b_dev, RADIO_EVENT_ACK_TIMEOUT);
}
} else {
// Queue up a PPM packet if it's time.
if (pios_rfm22_time_difference_ms(lastPPMTicks, curTicks) > PPM_UPDATE_PERIOD_MS) {
rfm22_sendPPM(rfm22b_dev);
lastPPMTicks = curTicks;
}
// Queue up a status packet if it's time.
if (pios_rfm22_time_difference_ms(lastStatusTicks, curTicks) > RADIOSTATS_UPDATE_PERIOD_MS) {
rfm22_sendStatus(rfm22b_dev);
lastStatusTicks = curTicks;
}
}
if ((rfm22b_dev->packet_start_ticks > 0) &&
(pios_rfm22_time_difference_ms(rfm22b_dev->packet_start_ticks, curTicks) > (rfm22b_dev->packet_time * 3))) {
rfm22_process_event(rfm22b_dev, RADIO_EVENT_TIMEOUT);
}
// Send a packet if it's our time slice
// Start transmitting a packet if it's time.
bool time_to_send = rfm22_timeToSend(rfm22b_dev);
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
if (time_to_send) {
D4_LED_ON;
} else {
D4_LED_OFF;
}
#endif
#endif
if (time_to_send && PIOS_RFM22B_InRxWait((uint32_t)rfm22b_dev)) {
rfm22_process_event(rfm22b_dev, RADIO_EVENT_TX_START);
}
@ -1371,28 +1323,23 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
}
// Initialize the state
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_DISCONNECTED;
rfm22b_dev->destination_id = 0xffffffff;
rfm22b_dev->send_status = false;
rfm22b_dev->send_connection_request = false;
rfm22b_dev->send_ack_nack = false;
rfm22b_dev->resend_packet = false;
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_ENABLED;
// Initialize the packets.
rfm22b_dev->rx_packet_len = 0;
rfm22b_dev->tx_packet = NULL;
rfm22b_dev->prev_tx_packet = NULL;
rfm22b_dev->data_packet.header.data_size = 0;
rfm22b_dev->rx_packet_len = 0;
rfm22b_dev->rx_destination_id = 0;
rfm22b_dev->tx_packet_handle = NULL;
// Initialize the devide state
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;
rfm22b_dev->rfm22b_state = RFM22B_STATE_INITIALIZING;
rfm22b_dev->rx_buffer_wr = 0;
rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0;
rfm22b_dev->channel = 0;
rfm22b_dev->channel_index = 0;
rfm22b_dev->afc_correction_Hz = 0;
rfm22b_dev->packet_start_ticks = 0;
rfm22b_dev->tx_complete_ticks = 0;
rfm22b_dev->rfm22b_state = RFM22B_STATE_INITIALIZING;
rfm22b_dev->on_sync_channel = false;
// software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B)
rfm22_write_claim(rfm22b_dev, RFM22_op_and_func_ctrl1, RFM22_opfc1_swres);
@ -1522,13 +1469,14 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
RFM22_header_cntl1_hdch_1 |
RFM22_header_cntl1_hdch_2 |
RFM22_header_cntl1_hdch_3);
// Check all bit of all bytes of the header
rfm22_write(rfm22b_dev, RFM22_header_enable0, 0xff);
rfm22_write(rfm22b_dev, RFM22_header_enable1, 0xff);
rfm22_write(rfm22b_dev, RFM22_header_enable2, 0xff);
rfm22_write(rfm22b_dev, RFM22_header_enable3, 0xff);
// Set the ID to be checked
uint32_t id = rfm22b_dev->deviceID;
// Check all bit of all bytes of the header, unless we're an unbound modem.
uint8_t header_mask = (rfm22_destinationID(rfm22b_dev) == 0xffffffff) ? 0 : 0xff;
rfm22_write(rfm22b_dev, RFM22_header_enable0, header_mask);
rfm22_write(rfm22b_dev, RFM22_header_enable1, header_mask);
rfm22_write(rfm22b_dev, RFM22_header_enable2, header_mask);
rfm22_write(rfm22b_dev, RFM22_header_enable3, header_mask);
// The destination ID and receive ID should be the same.
uint32_t id = rfm22_destinationID(rfm22b_dev);
rfm22_write(rfm22b_dev, RFM22_check_header0, id & 0xff);
rfm22_write(rfm22b_dev, RFM22_check_header1, (id >> 8) & 0xff);
rfm22_write(rfm22b_dev, RFM22_check_header2, (id >> 16) & 0xff);
@ -1561,8 +1509,8 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
rfm22_releaseBus(rfm22b_dev);
// Initialize the frequency and datarate to te default.
rfm22_setNominalCarrierFrequency(rfm22b_dev, rfm22b_dev->init_frequency, rfm22b_dev->init_frequency, RFM22B_FREQUENCY_HOP_STEP_SIZE);
pios_rfm22_setDatarate(rfm22b_dev, RFM22B_DEFAULT_RX_DATARATE, true);
rfm22_setNominalCarrierFrequency(rfm22b_dev, 0);
pios_rfm22_setDatarate(rfm22b_dev);
return RADIO_EVENT_INITIALIZED;
}
@ -1580,15 +1528,10 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
* @param[in] datarate The air datarate.
* @param[in] data_whitening Is data whitening desired?
*/
static void pios_rfm22_setDatarate(struct pios_rfm22b_dev *rfm22b_dev, enum rfm22b_datarate datarate, bool data_whitening)
static void pios_rfm22_setDatarate(struct pios_rfm22b_dev *rfm22b_dev)
{
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.5f);
// 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;
rfm22b_dev->max_ack_delay = (uint16_t)((float)((sizeof(PHAckNackPacket) * 8 + TX_PREAMBLE_NIBBLES * 4) * 1000) / (float)(datarate_bps) + 0.5f) * 4 + 4 + random;
enum rfm22b_datarate datarate = rfm22b_dev->datarate;
bool data_whitening = true;
// Claim the SPI bus.
rfm22_claimBus(rfm22b_dev);
@ -1651,16 +1594,17 @@ static void pios_rfm22_setDatarate(struct pios_rfm22b_dev *rfm22b_dev, enum rfm2
}
/**
* Set the nominal carrier frequency and channel step size.
* Set the nominal carrier frequency, channel step size, and initial channel
*
* @param[in] rfm33b_dev The device structure pointer.
* @param[in] min_frequency The minimum frequenc to transmit on (in Hz).
* @param[in] max_frequency The maximum frequenc to transmit on (in Hz).
* @param[in] step_size The channel spacing (in Hz).
* @param[in] init_chan The initial channel to tune to.
*/
static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint32_t min_frequency, uint32_t max_frequency, uint32_t step_size)
static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint8_t init_chan)
{
uint32_t frequency_hz = min_frequency;
// Set the frequency channels to start at 430MHz
uint32_t frequency_hz = RFM22B_NOMINAL_CARRIER_FREQUENCY;
// The step size is 10MHz / 250 channels = 40khz, and the step size is specified in 10khz increments.
uint8_t freq_hop_step_size = 4;
// holds the hbsel (1 or 2)
uint8_t hbsel;
@ -1681,22 +1625,15 @@ static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev,
// Claim the SPI bus.
rfm22_claimBus(rfm22b_dev);
// Calculate the number of frequency hopping channels.
rfm22b_dev->num_channels = (step_size == 0) ? 1 : (uint16_t)((max_frequency - min_frequency) / step_size);
// initialize the frequency hopping step size (specified in 10khz increments).
uint32_t freq_hop_step_size = step_size / 10000;
if (freq_hop_step_size > 255) {
freq_hop_step_size = 255;
}
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_step_size, (uint8_t)freq_hop_step_size);
// Setthe frequency hopping step size.
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_step_size, freq_hop_step_size);
// 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)
rfm22b_dev->frequency_hop_channel = 0;
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_channel_select, 0);
rfm22b_dev->channel = init_chan;
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_channel_select, init_chan);
// no frequency offset
rfm22_write(rfm22b_dev, RFM22_frequency_offset1, 0);
@ -1720,13 +1657,13 @@ static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev,
static bool rfm22_setFreqHopChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t channel)
{
// set the frequency hopping channel
if (rfm22b_dev->frequency_hop_channel == channel) {
if (rfm22b_dev->channel == channel) {
return false;
}
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
D3_LED_TOGGLE;
#endif // PIOS_RFM22B_DEBUG_ON_TELEM
rfm22b_dev->frequency_hop_channel = channel;
rfm22b_dev->channel = channel;
rfm22_write_claim(rfm22b_dev, RFM22_frequency_hopping_channel_select, channel);
return true;
}
@ -1777,10 +1714,6 @@ static void rfm22_rxFailure(struct pios_rfm22b_dev *rfm22b_dev)
rfm22b_dev->rx_buffer_wr = 0;
rfm22b_dev->packet_start_ticks = 0;
rfm22b_dev->rfm22b_state = RFM22B_STATE_TRANSITION;
rfm22b_dev->rx_complete_ticks = xTaskGetTickCount();
if (rfm22b_dev->rx_complete_ticks == 0) {
rfm22b_dev->rx_complete_ticks = 1;
}
}
@ -1796,100 +1729,84 @@ static void rfm22_rxFailure(struct pios_rfm22b_dev *rfm22b_dev)
*/
static enum pios_radio_event radio_txStart(struct pios_rfm22b_dev *radio_dev)
{
PHPacketHandle p = NULL;
uint8_t *p = radio_dev->tx_packet;
uint8_t len = 0;
uint8_t max_data_len = radio_dev->max_packet_len - (radio_dev->ppm_only_mode ? 0 : RS_ECC_NPARITY);
// Don't send if it's not our turn, or if we're receiving a packet.
if (!rfm22_timeToSend(radio_dev) || !PIOS_RFM22B_InRxWait((uint32_t)radio_dev)) {
return RADIO_EVENT_RX_MODE;
}
#ifdef PIOS_PPM_RECEIVER
// Send a PPM packet?
if (radio_dev->send_ppm) {
p = (PHPacketHandle) & (radio_dev->ppm_packet);
radio_dev->send_ppm = false;
}
#endif
// Send an ACK/NACK?
if (!p && radio_dev->send_ack_nack) {
p = (PHPacketHandle) & (radio_dev->ack_nack_packet);
radio_dev->send_ack_nack = false;
}
// Resend a packet?
if (!p && radio_dev->resend_packet) {
p = radio_dev->prev_tx_packet;
radio_dev->prev_tx_packet = NULL;
radio_dev->resend_packet = false;
}
// Don't send another packet if we're waiting for an ACK.
if (!p && radio_dev->prev_tx_packet) {
// Don't send anything if we're bound to a coordinator and not yet connected.
if (!rfm22_isCoordinator(radio_dev) && !rfm22_isConnected(radio_dev)) {
return RADIO_EVENT_RX_MODE;
}
// Send a connection request?
if (!p && radio_dev->send_connection_request) {
p = (PHPacketHandle) & (radio_dev->con_packet);
radio_dev->send_connection_request = false;
// Should we append PPM data to the packet?
if (radio_dev->ppm_send_mode) {
len = RFM22B_PPM_NUM_CHANNELS + (radio_dev->ppm_only_mode ? 2 : 1);
// Ensure we can fit the PPM data in the packet.
if (max_data_len < len) {
return RADIO_EVENT_RX_MODE;
}
// The first byte is a bitmask of valid channels.
p[0] = 0;
// Read the PPM input.
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
int32_t val = radio_dev->ppm[i];
if ((val == PIOS_RCVR_INVALID) || (val == PIOS_RCVR_TIMEOUT)) {
p[i + 1] = 0;
} else {
p[0] |= 1 << i;
p[i + 1] = (val < 1000) ? 0 : ((val >= 1900) ? 255 : (uint8_t)(256 * (val - 1000) / 900));
}
}
// The last byte is a CRC.
if (radio_dev->ppm_only_mode) {
uint8_t crc = 0;
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS + 1; ++i) {
crc = PIOS_CRC_updateByte(crc, p[i]);
}
p[RFM22B_PPM_NUM_CHANNELS + 1] = crc;
}
}
// Try to get some data to send
if (!p) {
// Append data from the com interface if applicable.
if (!radio_dev->ppm_only_mode && radio_dev->tx_out_cb) {
// Try to get some data to send
bool need_yield = false;
p = &radio_dev->data_packet;
p->header.type = PACKET_TYPE_DATA;
p->header.destination_id = radio_dev->destination_id;
if (radio_dev->tx_out_cb && (p->header.data_size == 0)) {
p->header.data_size = (radio_dev->tx_out_cb)(radio_dev->tx_out_context, p->data, PH_MAX_DATA, NULL, &need_yield);
}
// Don't send any data until we're connected.
if (!rfm22_isConnected(radio_dev)) {
p->header.data_size = 0;
}
if (p->header.data_size == 0) {
p = NULL;
}
len += (radio_dev->tx_out_cb)(radio_dev->tx_out_context, p + len, max_data_len - len, NULL, &need_yield);
}
// Send status?
if (!p && radio_dev->send_status) {
p = (PHPacketHandle) & (radio_dev->status_packet);
radio_dev->send_status = false;
}
if (!p) {
// Always send a packet on the sync channel if this modem is a coordinator.
if ((len == 0) && ((radio_dev->channel_index != 0) || !rfm22_isCoordinator(radio_dev))) {
return RADIO_EVENT_RX_MODE;
}
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
D1_LED_ON;
#endif
// Add the packet sequence number.
p->header.seq_num = radio_dev->stats.tx_seq++;
// Pass the time of the previous transmitted packet to use for synchronizing the clocks.
p->header.prev_tx_time = radio_dev->tx_complete_ticks;
// Change the channel if necessary, but not when ACKing the connection request message.
if ((p->header.type != PACKET_TYPE_ACK) || (radio_dev->rx_packet.header.type != PACKET_TYPE_CON_REQUEST)) {
rfm22_changeChannel(radio_dev);
}
// Increment the packet sequence number.
radio_dev->stats.tx_seq++;
// Add the error correcting code.
encode_data((unsigned char *)p, PHPacketSize(p), (unsigned char *)p);
if (!radio_dev->ppm_only_mode) {
if (len != 0) {
encode_data((unsigned char *)p, len, (unsigned char *)p);
}
len += RS_ECC_NPARITY;
}
// Transmit the packet.
PIOS_RFM22B_TransmitPacket((uint32_t)radio_dev, p);
PIOS_RFM22B_TransmitPacket((uint32_t)radio_dev, p, len);
return RADIO_EVENT_NUM_EVENTS;
}
/**
* Receive packet data.
* Transmit packet data.
*
* @param[in] rfm22b_dev The device structure
* @return enum pios_radio_event The next event to inject
@ -1901,25 +1818,11 @@ static enum pios_radio_event radio_txData(struct pios_rfm22b_dev *radio_dev)
// Is the transmition complete
if (res == PIOS_RFM22B_TX_COMPLETE) {
radio_dev->stats.tx_byte_count += PH_PACKET_SIZE(radio_dev->tx_packet);
radio_dev->tx_complete_ticks = xTaskGetTickCount();
radio_dev->tx_complete_ticks = xTaskGetTickCount();
// Is this an ACK?
bool is_ack = (radio_dev->tx_packet->header.type == PACKET_TYPE_ACK);
ret_event = RADIO_EVENT_RX_MODE;
if (is_ack) {
// If this is an ACK for a connection request message we need to
// configure this modem from the connection request message.
if (radio_dev->rx_packet.header.type == PACKET_TYPE_CON_REQUEST) {
rfm22_setConnectionParameters(radio_dev);
}
} else if ((radio_dev->tx_packet->header.type != PACKET_TYPE_NACK) &&
(radio_dev->tx_packet->header.type != PACKET_TYPE_PPM) &&
(radio_dev->tx_packet->header.type != PACKET_TYPE_STATUS)) {
// We need to wait for an ACK if this packet it not an ACK, NACK, PPM, or status packet.
radio_dev->prev_tx_packet = radio_dev->tx_packet;
}
radio_dev->tx_packet = 0;
radio_dev->tx_packet_handle = 0;
radio_dev->tx_data_wr = radio_dev->tx_data_rd = 0;
// Start a new transaction
radio_dev->packet_start_ticks = 0;
@ -1940,7 +1843,7 @@ static enum pios_radio_event radio_txData(struct pios_rfm22b_dev *radio_dev)
*/
static enum pios_radio_event radio_setRxMode(struct pios_rfm22b_dev *rfm22b_dev)
{
if (!PIOS_RFM22B_ReceivePacket((uint32_t)rfm22b_dev, &(rfm22b_dev->rx_packet))) {
if (!PIOS_RFM22B_ReceivePacket((uint32_t)rfm22b_dev, rfm22b_dev->rx_packet)) {
return RADIO_EVENT_NUM_EVENTS;
}
rfm22b_dev->packet_start_ticks = 0;
@ -1957,19 +1860,69 @@ static enum pios_radio_event radio_setRxMode(struct pios_rfm22b_dev *rfm22b_dev)
* @param[in] rc_len The number of bytes received.
* @return enum pios_radio_event The next event to inject
*/
static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *radio_dev, PHPacketHandle p, uint16_t rx_len)
static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *radio_dev, uint8_t *p, uint16_t rx_len)
{
portTickType curTicks = xTaskGetTickCount();
// Attempt to correct any errors in the packet.
decode_data((unsigned char *)p, rx_len);
bool good_packet = check_syndrome() == 0;
bool good_packet = true;
bool corrected_packet = false;
// We have an error. Try to correct it.
if (!good_packet && (correct_errors_erasures((unsigned char *)p, rx_len, 0, 0) != 0)) {
// We corrected it
corrected_packet = true;
uint8_t data_len = rx_len;
// We don't rsencode ppm only packets.
if (!radio_dev->ppm_only_mode) {
data_len -= RS_ECC_NPARITY;
// Attempt to correct any errors in the packet.
if (data_len > 0) {
decode_data((unsigned char *)p, rx_len);
good_packet = check_syndrome() == 0;
// We have an error. Try to correct it.
if (!good_packet && (correct_errors_erasures((unsigned char *)p, rx_len, 0, 0) != 0)) {
// We corrected it
corrected_packet = true;
}
}
}
// Should we pull PPM data off of the head of the packet?
if ((good_packet || corrected_packet) && radio_dev->ppm_recv_mode) {
uint8_t ppm_len = RFM22B_PPM_NUM_CHANNELS + (radio_dev->ppm_only_mode ? 2 : 1);
// Ensure the packet it long enough
if (data_len < ppm_len) {
good_packet = false;
}
// Verify the CRC if this is a PPM only packet.
if ((good_packet || corrected_packet) && radio_dev->ppm_only_mode) {
uint8_t crc = 0;
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS + 1; ++i) {
crc = PIOS_CRC_updateByte(crc, p[i]);
}
if (p[RFM22B_PPM_NUM_CHANNELS + 1] != crc) {
good_packet = false;
corrected_packet = false;
}
}
if (good_packet || corrected_packet) {
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
// Is this a valid channel?
if (p[0] & (1 << i)) {
uint32_t val = p[i + 1];
radio_dev->ppm[i] = (uint16_t)(1000 + val * 900 / 256);
} else {
radio_dev->ppm[i] = PIOS_RCVR_INVALID;
}
}
p += RFM22B_PPM_NUM_CHANNELS + 1;
data_len -= RFM22B_PPM_NUM_CHANNELS + 1;
// Call the PPM received callback if it's available.
if (radio_dev->ppm_callback) {
radio_dev->ppm_callback(radio_dev->ppm);
}
}
}
// Set the packet status
@ -1985,101 +1938,22 @@ static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *radio_d
enum pios_radio_event ret_event = RADIO_EVENT_RX_COMPLETE;
if (good_packet || corrected_packet) {
switch (p->header.type) {
case PACKET_TYPE_STATUS:
ret_event = RADIO_EVENT_STATUS_RECEIVED;
break;
case PACKET_TYPE_CON_REQUEST:
ret_event = RADIO_EVENT_CONNECTION_REQUESTED;
break;
case PACKET_TYPE_DATA:
{
// Send the data to the com port
bool rx_need_yield;
if (radio_dev->rx_in_cb) {
(radio_dev->rx_in_cb)(radio_dev->rx_in_context, p->data, p->header.data_size, NULL, &rx_need_yield);
}
break;
}
case PACKET_TYPE_DUPLICATE_DATA:
break;
case PACKET_TYPE_ACK:
ret_event = RADIO_EVENT_PACKET_ACKED;
break;
case PACKET_TYPE_NACK:
ret_event = RADIO_EVENT_PACKET_NACKED;
break;
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)p;
#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;
radio_dev->ppm_fresh = true;
for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) {
radio_dev->ppm_channel[i] = ppmp->channels[i];
}
#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;
}
default:
break;
// Send the data to the com port
bool rx_need_yield;
if (radio_dev->rx_in_cb && (data_len > 0) && !radio_dev->ppm_only_mode) {
(radio_dev->rx_in_cb)(radio_dev->rx_in_context, p, data_len, NULL, &rx_need_yield);
}
uint16_t seq_num = radio_dev->rx_packet.header.seq_num;
if (rfm22_isConnected(radio_dev)) {
// Adjust the clock syncronization if this is the remote modem.
// The coordinator sends the time that the previous packet was finised transmitting,
// which should match the time that the last packet was received.
uint16_t prev_seq_num = radio_dev->stats.rx_seq;
if (seq_num == (prev_seq_num + 1)) {
portTickType local_rx_time = radio_dev->rx_complete_ticks;
portTickType remote_tx_time = radio_dev->rx_packet.header.prev_tx_time;
portTickType time_delta = remote_tx_time - local_rx_time;
portTickType time_delta_delta = (time_delta > radio_dev->time_delta) ? (time_delta - radio_dev->time_delta) : (radio_dev->time_delta - time_delta);
if (time_delta_delta <= 2) {
radio_dev->time_delta = remote_tx_time - local_rx_time;
}
} else if (seq_num > prev_seq_num) {
// Add any missed packets into the stats.
uint16_t missed_packets = seq_num - prev_seq_num - 1;
radio_dev->stats.rx_missed += missed_packets;
}
// We only synchronize the clock on packets from our coordinator on the sync channel.
if (!rfm22_isCoordinator(radio_dev) && (radio_dev->rx_destination_id == rfm22_destinationID(radio_dev)) && (radio_dev->channel_index == 0)) {
rfm22_synchronizeClock(radio_dev);
radio_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_CONNECTED;
radio_dev->on_sync_channel = false;
}
// Update the sequence number
radio_dev->stats.rx_seq = seq_num;
} else {
ret_event = RADIO_EVENT_RX_COMPLETE;
}
// Log the time that the packet was received.
radio_dev->rx_complete_ticks = curTicks;
if (radio_dev->rx_complete_ticks == 0) {
radio_dev->rx_complete_ticks = 1;
}
return ret_event;
}
@ -2122,210 +1996,19 @@ static enum pios_radio_event radio_rxData(struct pios_rfm22b_dev *radio_dev)
}
/*****************************************************************************
* Packet Transmition Functions
* Link Statistics Functions
*****************************************************************************/
/**
* Send a radio status message.
*
* @param[in] rfm22b_dev The device structure
*/
static void rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev)
{
// Don't send if a status is already queued or if we're the coordinator and not connected.
if (rfm22b_dev->send_status || (rfm22b_dev->coordinator && !rfm22_isConnected(rfm22b_dev))) {
return;
}
// Update the link quality metric.
rfm22_calculateLinkQuality(rfm22b_dev);
// Queue the status message
if (rfm22_isConnected(rfm22b_dev)) {
rfm22b_dev->status_packet.header.destination_id = rfm22b_dev->destination_id;
} else if (rfm22b_dev->coordinator) {
return;
} else {
rfm22b_dev->status_packet.header.destination_id = 0xffffffff; // Broadcast
}
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.source_id = rfm22b_dev->deviceID;
rfm22b_dev->status_packet.link_quality = rfm22b_dev->stats.link_quality;
rfm22b_dev->status_packet.received_rssi = rfm22b_dev->rssi_dBm;
rfm22b_dev->send_status = true;
}
/**
* Send a PPM packet.
*
* @param[in] rfm22b_dev The device structure
*/
static void rfm22_sendPPM(__attribute__((unused)) struct pios_rfm22b_dev *rfm22b_dev)
{
#ifdef PIOS_PPM_RECEIVER
// Only send PPM if we're connected
if (!rfm22_isConnected(rfm22b_dev)) {
return;
}
// Just return if the PPM receiver is not configured.
if (PIOS_PPM_RECEIVER == 0) {
return;
}
// See if we have any valid channels.
bool valid_input_detected = false;
for (uint8_t i = 0; i < PIOS_PPM_NUM_INPUTS; ++i) {
rfm22b_dev->ppm_packet.channels[i] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i + 1);
if ((rfm22b_dev->ppm_packet.channels[i] != PIOS_RCVR_INVALID) && (rfm22b_dev->ppm_packet.channels[i] != PIOS_RCVR_TIMEOUT)) {
valid_input_detected = true;
}
}
// Send the PPM packet if it's valid
if (valid_input_detected) {
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 /* ifdef PIOS_PPM_RECEIVER */
}
/**
* Send an ACK to a received packet.
* Update the modem pair status.
*
* @param[in] rfm22b_dev The device structure
* @return enum pios_radio_event The next event to inject
*/
static enum pios_radio_event rfm22_sendAck(struct pios_rfm22b_dev *rfm22b_dev)
static void rfm22_updatePairStatus(struct pios_rfm22b_dev *radio_dev)
{
// We don't ACK PPM or status packets.
if ((rfm22b_dev->rx_packet.header.type != PACKET_TYPE_PPM) && (rfm22b_dev->rx_packet.header.type != PACKET_TYPE_STATUS)) {
PHAckNackPacketHandle aph = (PHAckNackPacketHandle)(&(rfm22b_dev->ack_nack_packet));
aph->header.destination_id = rfm22b_dev->destination_id;
aph->header.type = PACKET_TYPE_ACK;
aph->header.data_size = PH_ACK_NACK_DATA_SIZE(aph);
rfm22b_dev->send_ack_nack = true;
}
return RADIO_EVENT_TX_START;
}
/**
* Send an NACK to a received packet.
*
* @param[in] rfm22b_dev The device structure
* @return enum pios_radio_event The next event to inject
*/
static enum pios_radio_event rfm22_sendNack(struct pios_rfm22b_dev *rfm22b_dev)
{
PHAckNackPacketHandle aph = (PHAckNackPacketHandle)(&(rfm22b_dev->ack_nack_packet));
// We don't NACK PPM or status packets.
if ((rfm22b_dev->rx_packet.header.type != PACKET_TYPE_PPM) && (rfm22b_dev->rx_packet.header.type != PACKET_TYPE_STATUS)) {
aph->header.destination_id = rfm22b_dev->destination_id;
aph->header.type = PACKET_TYPE_NACK;
aph->header.data_size = PH_ACK_NACK_DATA_SIZE(aph);
rfm22b_dev->send_ack_nack = true;
}
return RADIO_EVENT_TX_START;
}
/**
* Send a connection request message.
*
* @param[in] rfm22b_dev The device structure
* @return enum pios_radio_event The next event to inject
*/
static enum pios_radio_event rfm22_requestConnection(struct pios_rfm22b_dev *rfm22b_dev)
{
PHConnectionPacketHandle cph = &(rfm22b_dev->con_packet);
// Set our connection state to requesting connection.
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_CONNECTING;
// 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.type = PACKET_TYPE_CON_REQUEST;
cph->header.data_size = PH_CONNECTION_DATA_SIZE(&(rfm22b_dev->con_packet));
cph->source_id = rfm22b_dev->deviceID;
cph->status_rx_time = rfm22b_dev->rx_complete_ticks;
cph->main_port = rfm22b_dev->bindings[rfm22b_dev->cur_binding].main_port;
cph->flexi_port = rfm22b_dev->bindings[rfm22b_dev->cur_binding].flexi_port;
cph->vcp_port = rfm22b_dev->bindings[rfm22b_dev->cur_binding].vcp_port;
cph->com_speed = rfm22b_dev->bindings[rfm22b_dev->cur_binding].com_speed;
rfm22b_dev->send_connection_request = true;
rfm22b_dev->prev_tx_packet = NULL;
return RADIO_EVENT_TX_START;
}
/*****************************************************************************
* Packet Receipt Functions
*****************************************************************************/
/**
* Receive an ACK.
*
* @param[in] rfm22b_dev The device structure
* @return enum pios_radio_event The next event to inject
*/
static enum pios_radio_event rfm22_receiveAck(struct pios_rfm22b_dev *rfm22b_dev)
{
PHPacketHandle prev = rfm22b_dev->prev_tx_packet;
// Clear the previous TX packet.
rfm22b_dev->prev_tx_packet = NULL;
// Was this a connection request?
switch (prev->header.type) {
case PACKET_TYPE_CON_REQUEST:
rfm22_setConnectionParameters(rfm22b_dev);
break;
case PACKET_TYPE_DATA:
rfm22b_dev->data_packet.header.data_size = 0;
break;
}
// Should we try to start another TX?
return RADIO_EVENT_TX_START;
}
/**
* Receive an MACK.
*
* @param[in] rfm22b_dev The device structure
* @return enum pios_radio_event The next event to inject
*/
static enum pios_radio_event rfm22_receiveNack(struct pios_rfm22b_dev *rfm22b_dev)
{
// Resend the previous TX packet.
rfm22b_dev->tx_packet = rfm22b_dev->prev_tx_packet;
rfm22b_dev->prev_tx_packet = NULL;
// Increment the reset packet counter if we're connected.
if (rfm22_isConnected(rfm22b_dev)) {
rfm22b_add_rx_status(rfm22b_dev, RADIO_RESENT_TX_PACKET);
}
return RADIO_EVENT_TX_START;
}
/**
* Receive a status packet
*
* @param[in] rfm22b_dev The device structure
* @return enum pios_radio_event The next event to inject
*/
static enum pios_radio_event rfm22_receiveStatus(struct pios_rfm22b_dev *radio_dev)
{
PHStatusPacketHandle status = (PHStatusPacketHandle) & (radio_dev->rx_packet);
int8_t rssi = radio_dev->rssi_dBm;
int8_t afc = radio_dev->afc_correction_Hz;
uint32_t id = status->source_id;
enum pios_radio_event ret_event = RADIO_EVENT_RX_COMPLETE;
int8_t rssi = radio_dev->rssi_dBm;
int8_t afc = radio_dev->afc_correction_Hz;
uint32_t id = radio_dev->rx_destination_id;
// Have we seen this device recently?
bool found = false;
@ -2338,7 +2021,7 @@ static enum pios_radio_event rfm22_receiveStatus(struct pios_rfm22b_dev *radio_d
}
}
// If we have seen it, update the RSSI and reset the last contact couter
// If we have seen it, update the RSSI and reset the last contact counter
if (found) {
radio_dev->pair_stats[id_idx].rssi = rssi;
radio_dev->pair_stats[id_idx].afc_correction = afc;
@ -2358,26 +2041,8 @@ static enum pios_radio_event rfm22_receiveStatus(struct pios_rfm22b_dev *radio_d
radio_dev->pair_stats[min_idx].afc_correction = afc;
radio_dev->pair_stats[min_idx].lastContact = 0;
}
// Send a connection request message if we're not connected, and this is a status message from a modem that we're bound to.
if (radio_dev->coordinator && !rfm22_isConnected(radio_dev)) {
for (uint8_t i = 0; i < OPLINKSETTINGS_BINDINGS_NUMELEM; ++i) {
if (radio_dev->bindings[i].pairID == id) {
radio_dev->cur_binding = i;
ret_event = RADIO_EVENT_REQUEST_CONNECTION;
break;
}
}
}
return ret_event;
}
/*****************************************************************************
* Link Statistics Functions
*****************************************************************************/
/**
* Calculate the link quality from the packet receipt, tranmittion statistics.
*
@ -2438,87 +2103,30 @@ static void rfm22b_add_rx_status(struct pios_rfm22b_dev *rfm22b_dev, enum pios_r
*****************************************************************************/
/**
* Are we connected to the remote modem?
* Are we a coordinator modem?
*
* @param[in] rfm22b_dev The device structure
*/
static bool rfm22_isConnected(struct pios_rfm22b_dev *rfm22b_dev)
static bool rfm22_isCoordinator(struct pios_rfm22b_dev *rfm22b_dev)
{
return rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED;
return rfm22b_dev->coordinator;
}
/**
* Set the connection parameters from a connection request message.
* Returns the destination ID to send packets to.
*
* @param[in] rfm22b_dev The device structure
* @param[in] rfm22b_id The RFM22B device index.
* @return The destination ID
*/
static void rfm22_setConnectionParameters(struct pios_rfm22b_dev *rfm22b_dev)
uint32_t rfm22_destinationID(struct pios_rfm22b_dev *rfm22b_dev)
{
PHConnectionPacketHandle cph = &(rfm22b_dev->con_packet);
// Set our connection state to connected
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_CONNECTED;
// Call the com port configuration function
if (rfm22b_dev->com_config_cb) {
rfm22b_dev->com_config_cb(cph->main_port, cph->flexi_port, cph->vcp_port, cph->com_speed);
if (rfm22_isCoordinator(rfm22b_dev)) {
return rfm22b_dev->deviceID;
} else if (rfm22b_dev->coordinatorID) {
return rfm22b_dev->coordinatorID;
} else {
return 0xffffffff;
}
// Configure this modem min an max frequency.
rfm22_setNominalCarrierFrequency(rfm22b_dev, cph->min_frequency, cph->max_frequency, cph->channel_spacing);
// Configure the modem datarate.
rfm22b_dev->datarate = RFM22_datarate_64000;
switch (cph->com_speed) {
case OPLINKSETTINGS_COMSPEED_2400:
rfm22b_dev->datarate = RFM22_datarate_8000;
break;
case OPLINKSETTINGS_COMSPEED_4800:
rfm22b_dev->datarate = RFM22_datarate_8000;
break;
case OPLINKSETTINGS_COMSPEED_9600:
rfm22b_dev->datarate = RFM22_datarate_16000;
break;
case OPLINKSETTINGS_COMSPEED_19200:
rfm22b_dev->datarate = RFM22_datarate_32000;
break;
case OPLINKSETTINGS_COMSPEED_38400:
rfm22b_dev->datarate = RFM22_datarate_57600;
break;
case OPLINKSETTINGS_COMSPEED_57600:
rfm22b_dev->datarate = RFM22_datarate_128000;
break;
case OPLINKSETTINGS_COMSPEED_115200:
rfm22b_dev->datarate = RFM22_datarate_192000;
break;
}
pios_rfm22_setDatarate(rfm22b_dev, rfm22b_dev->datarate, true);
}
/**
* Accept a connection request.
*
* @param[in] rfm22b_dev The device structure
* @return enum pios_radio_event The next event to inject
*/
static enum pios_radio_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm22b_dev)
{
// Copy the connection packet
PHConnectionPacketHandle cph = (PHConnectionPacketHandle)(&(rfm22b_dev->rx_packet));
PHConnectionPacketHandle lcph = (PHConnectionPacketHandle)(&(rfm22b_dev->con_packet));
memcpy((uint8_t *)lcph, (uint8_t *)cph, PH_PACKET_SIZE((PHPacketHandle)cph));
// Set the destination ID to the source of the connection request message.
rfm22b_dev->destination_id = cph->source_id;
// The remote modem sets the time delta between the two modems using the differene between the clock
// on the local modem when it sent the status packet and the time on the coordinator modem when it was received.
portTickType local_tx_time = rfm22b_dev->tx_complete_ticks;
portTickType remote_rx_time = cph->status_rx_time;
rfm22b_dev->time_delta = remote_rx_time - local_tx_time;
return RADIO_EVENT_DEFAULT;
}
@ -2526,6 +2134,27 @@ static enum pios_radio_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm2
* Frequency Hopping Functions
*****************************************************************************/
/**
* Synchronize the clock after a packet receive from our coordinator on the syncronization channel.
* This function should be called when a packet is received on the synchronization channel.
*
* @param[in] rfm22b_dev The device structure
*/
static void rfm22_synchronizeClock(struct pios_rfm22b_dev *rfm22b_dev)
{
portTickType start_time = rfm22b_dev->packet_start_ticks;
// This packet was transmitted on channel 0, calculate the time delta that will force us to transmit on channel 0 at the time this packet started.
uint8_t num_chan = num_channels[rfm22b_dev->datarate];
uint16_t frequency_hop_cycle_time = rfm22b_dev->packet_time * num_chan;
uint16_t time_delta = start_time % frequency_hop_cycle_time;
// Calculate the adjustment for the preamble
uint8_t offset = (uint8_t)ceil(35000.0F / data_rate[rfm22b_dev->datarate]);
rfm22b_dev->time_delta = frequency_hop_cycle_time - time_delta + offset;
}
/**
* Return the extimated current clock ticks count on the coordinator modem.
* This is the master clock used for all synchronization.
@ -2534,7 +2163,7 @@ static enum pios_radio_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm2
*/
static portTickType rfm22_coordinatorTime(struct pios_rfm22b_dev *rfm22b_dev, portTickType ticks)
{
if (rfm22b_dev->coordinator) {
if (rfm22_isCoordinator(rfm22b_dev)) {
return ticks;
}
return ticks + rfm22b_dev->time_delta;
@ -2547,11 +2176,66 @@ static portTickType rfm22_coordinatorTime(struct pios_rfm22b_dev *rfm22b_dev, po
*/
static bool rfm22_timeToSend(struct pios_rfm22b_dev *rfm22b_dev)
{
portTickType time = rfm22_coordinatorTime(rfm22b_dev, xTaskGetTickCount());
portTickType time = rfm22_coordinatorTime(rfm22b_dev, xTaskGetTickCount());
bool is_coordinator = rfm22_isCoordinator(rfm22b_dev);
// Divide time into 8ms blocks. Coordinator sends in first 1 ms, and remote send in 4th.
// Channel changes occurs in the 7th.
return (rfm22b_dev->coordinator) ? ((time & 0x7) == 0) : ((time & 0x7) == 3);
// If this is a one-way link, only the coordinator can send.
uint8_t packet_period = rfm22b_dev->packet_time;
if (rfm22b_dev->one_way_link) {
if (is_coordinator) {
return ((time - 1) % (packet_period)) == 0;
} else {
return false;
}
}
if (!is_coordinator) {
time += packet_period - 1;
} else {
time -= 1;
}
return (time % (packet_period * 2)) == 0;
}
/**
* Calculate the nth channel index.
*
* @param[in] rfm22b_dev The device structure
* @param[in] index The channel index to calculate
*/
static uint8_t rfm22_calcChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t index)
{
// Make sure we don't index outside of the range.
uint8_t num_chan = num_channels[rfm22b_dev->datarate];
uint8_t idx = index % num_chan;
// Are we switching to a new channel?
if (idx != rfm22b_dev->channel_index) {
// If the on_sync_channel flag is set, it means that we were on the sync channel, but no packet was received, so transition to a non-connected state.
if (!rfm22_isCoordinator(rfm22b_dev) && (rfm22b_dev->channel_index == 0) && rfm22b_dev->on_sync_channel) {
rfm22b_dev->on_sync_channel = false;
// Set the link state to disconnected.
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED) {
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_DISCONNECTED;
// Set the PPM outputs to INVALID
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
rfm22b_dev->ppm[i] = PIOS_RCVR_INVALID;
}
}
// Stay on the sync channel.
idx = 0;
} else if (idx == 0) {
// If we're switching to the sync channel, set a flag that can be used to detect if a packet was received.
rfm22b_dev->on_sync_channel = true;
}
rfm22b_dev->channel_index = idx;
}
return rfm22b_dev->channels[idx];
}
/**
@ -2559,14 +2243,15 @@ static bool rfm22_timeToSend(struct pios_rfm22b_dev *rfm22b_dev)
*
* @param[in] rfm22b_dev The device structure
*/
static uint8_t rfm22_calcChannel(struct pios_rfm22b_dev *rfm22b_dev)
static uint8_t rfm22_calcChannelFromClock(struct pios_rfm22b_dev *rfm22b_dev)
{
portTickType time = rfm22_coordinatorTime(rfm22b_dev, xTaskGetTickCount());
// Divide time into 8ms blocks. Coordinator sends in first 2 ms, and remote send in 5th and 6th ms.
// Channel changes occur in the last 2 ms.
uint8_t n = (((time + 2) >> 3) & 0xff);
uint8_t num_chan = num_channels[rfm22b_dev->datarate];
uint8_t n = (time / rfm22b_dev->packet_time) % num_chan;
return PIOS_CRC_updateByte(0, n) % rfm22b_dev->num_channels;
return rfm22_calcChannel(rfm22b_dev, n);
}
/**
@ -2576,10 +2261,12 @@ static uint8_t rfm22_calcChannel(struct pios_rfm22b_dev *rfm22b_dev)
*/
static bool rfm22_changeChannel(struct pios_rfm22b_dev *rfm22b_dev)
{
if (rfm22_isConnected(rfm22b_dev)) {
return rfm22_setFreqHopChannel(rfm22b_dev, rfm22_calcChannel(rfm22b_dev));
// A disconnected non-coordinator modem should sit on the sync channel until connected.
if (!rfm22_isCoordinator(rfm22b_dev) && !rfm22_isConnected(rfm22b_dev)) {
return rfm22_setFreqHopChannel(rfm22b_dev, rfm22_calcChannel(rfm22b_dev, 0));
} else {
return rfm22_setFreqHopChannel(rfm22b_dev, rfm22_calcChannelFromClock(rfm22b_dev));
}
return false;
}
@ -2612,7 +2299,7 @@ static enum pios_radio_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev)
rfm22b_dev->stats.timeouts++;
rfm22b_dev->packet_start_ticks = 0;
// Release the Tx packet if it's set.
if (rfm22b_dev->tx_packet != 0) {
if (rfm22b_dev->tx_packet_handle != 0) {
rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0;
}
rfm22b_dev->rfm22b_state = RFM22B_STATE_TRANSITION;

View File

@ -55,37 +55,12 @@ const struct pios_com_driver pios_rfm22b_com_driver = {
/**
* Changes the baud rate of the RFM22B peripheral without re-initialising.
*
* @param[in] rfm22b_id RFM22B name (GPS, TELEM, AUX)
* @param[in] rfm22b_id The defice ID
* @param[in] baud Requested baud rate
*/
static void PIOS_RFM22B_COM_ChangeBaud(uint32_t rfm22b_id, uint32_t baud)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return;
}
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
enum rfm22b_datarate datarate = RFM22_datarate_64000;
if (baud <= 1024) {
datarate = RFM22_datarate_500;
} else if (baud <= 2048) {
datarate = RFM22_datarate_1000;
} else if (baud <= 4096) {
datarate = RFM22_datarate_8000;
} else if (baud <= 9600) {
datarate = RFM22_datarate_16000;
} else if (baud <= 19200) {
datarate = RFM22_datarate_32000;
} else if (baud <= 38400) {
datarate = RFM22_datarate_57600;
} else if (baud <= 57600) {
datarate = RFM22_datarate_128000;
} else if (baud <= 115200) {
datarate = RFM22_datarate_192000;
}
rfm22b_dev->datarate = datarate;
}
static void PIOS_RFM22B_COM_ChangeBaud(__attribute__((unused)) uint32_t rfm22b_id,
__attribute__((unused)) uint32_t baud)
{}
/**
* Start a receive from the COM device
@ -103,14 +78,10 @@ static void PIOS_RFM22B_COM_RxStart(__attribute__((unused)) uint32_t rfm22b_id,
* @param[in] rfm22b_dev The device ID.
* @param[in] tx_bytes_available The number of bytes available to transmit
*/
static void PIOS_RFM22B_COM_TxStart(uint32_t rfm22b_id, __attribute__((unused)) uint16_t tx_bytes_avail)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
static void PIOS_RFM22B_COM_TxStart(__attribute__((unused)) uint32_t rfm22b_id,
__attribute__((unused)) uint16_t tx_bytes_avail)
{}
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return;
}
}
/**
* Register the callback to pass received data to

View File

@ -1,128 +0,0 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_RFM22B_RCVR RFM22B Receiver Input Functions
* @brief Code to output the PPM signal from the RFM22B
* @{
*
* @file pios_rfm22b_rcvr.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief Implements a receiver interface to the RFM22B device
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "pios.h"
#ifdef PIOS_INCLUDE_RFM22B_RCVR
#include "pios_rfm22b_priv.h"
/* Provide a RCVR driver */
static int32_t PIOS_RFM22B_RCVR_Get(uint32_t rcvr_id, uint8_t channel);
static void PIOS_RFM22B_RCVR_Supervisor(uint32_t rcvr_id);
const struct pios_rcvr_driver pios_rfm22b_rcvr_driver = {
.read = PIOS_RFM22B_RCVR_Get,
};
/**
* Initialize the receiver.
*
* @param[in] rfm22b_dev The receiver ID.
* @return < 0 on failure.
*/
int32_t PIOS_RFM22B_RCVR_Init(uint32_t rcvr_id)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rcvr_id;
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return -1;
}
// Initialize
for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) {
rfm22b_dev->ppm_channel[i] = PIOS_RCVR_TIMEOUT;
}
rfm22b_dev->ppm_supv_timer = 0;
// Register the failsafe timer callback.
if (!PIOS_RTC_RegisterTickCallback(PIOS_RFM22B_RCVR_Supervisor, rcvr_id)) {
PIOS_DEBUG_Assert(0);
}
return 0;
}
/**
* Get a channel from the receiver.
*
* @param[in] rcvr_id The receiver ID.
* @return The channel value, or -1 on failure.
*/
static int32_t PIOS_RFM22B_RCVR_Get(uint32_t rcvr_id, uint8_t channel)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rcvr_id;
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return -1;
}
if (channel >= GCSRECEIVER_CHANNEL_NUMELEM) {
/* channel is out of range */
return -1;
}
return rfm22b_dev->ppm_channel[channel];
}
/**
* The supervisor function that ensures that the data is current.
*
* @param[in] rcvr_id The receiver ID.
*/
static void PIOS_RFM22B_RCVR_Supervisor(uint32_t rcvr_id)
{
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rcvr_id;
if (!PIOS_RFM22B_Validate(rfm22b_dev)) {
return;
}
// RTC runs at 625Hz.
if (++(rfm22b_dev->ppm_supv_timer) < (PIOS_RFM22B_RCVR_TIMEOUT_MS * 625 / 1000)) {
return;
}
rfm22b_dev->ppm_supv_timer = 0;
// Have we received fresh values since the last update?
if (!rfm22b_dev->ppm_fresh) {
for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) {
rfm22b_dev->ppm_channel[i] = PIOS_RCVR_TIMEOUT;
}
}
rfm22b_dev->ppm_fresh = false;
}
#endif /* PIOS_INCLUDE_RFM22B_RCVR */
/**
* @}
* @}
*/

View File

@ -0,0 +1,45 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_OPLinkRCVR OPLink Receiver Functions
* @brief PIOS interface to read from OPLink receiver port
* @{
*
* @file pios_oplinkrcvr_priv.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
* @brief OPLINK receiver private functions
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_OPLINKRCVR_PRIV_H
#define PIOS_OPLINKRCVR_PRIV_H
#include <pios.h>
extern const struct pios_rcvr_driver pios_oplinkrcvr_rcvr_driver;
extern int32_t PIOS_OPLinkRCVR_Init(uint32_t *oplinkrcvr_id);
#endif /* PIOS_OPLINKRCVR_PRIV_H */
/**
* @}
* @}
*/

View File

@ -2,12 +2,13 @@
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS RFM22B Receiver Input Functions
* @addtogroup PIOS_PPM PPM Functions
* @brief PIOS interface to write to ppm port
* @{
*
* @file pios_rfm22b_rcvr.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief RFM22B Receiver Input functions header.
* @file pios_ppm_out_priv.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
* @brief ppm private structures.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
@ -27,14 +28,14 @@
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_RFM22B_RCVR_H
#ifndef PIOS_PPM_OUT_H
#define PIOS_PPM_OUT_H
#define PIOS_RFM22B_RCVR_MAX_CHANNELS 12
extern void PIOS_PPM_OUT_Set(uint32_t ppm_out_id, uint8_t servo, uint16_t position);
extern const struct pios_rcvr_driver pios_rfm22b_rcvr_driver;
#endif /* PIOS_PPM_H */
extern int32_t PIOS_RFM22B_RCVR_Init(uint32_t rcvr_id);
#define PIOS_RFM22B_RCVR_H
#endif /* PIOS_RFM22B_RCVR_H */
/**
* @}
* @}
*/

View File

@ -39,7 +39,6 @@ struct pios_ppm_out_cfg {
};
extern int32_t PIOS_PPM_Out_Init(uint32_t *ppm_out_id, const struct pios_ppm_out_cfg *cfg);
extern void PIOS_PPM_OUT_Set(uint32_t ppm_out_id, uint8_t servo, uint16_t position);
#endif /* PIOS_PPM_PRIV_H */

View File

@ -31,9 +31,6 @@
#ifndef PIOS_PPM_PRIV_H
#define PIOS_PPM_PRIV_H
#include <pios.h>
#include <pios_stm32.h>
struct pios_ppm_cfg {
TIM_ICInitTypeDef tim_ic_init;
const struct pios_tim_channel *channels;

View File

@ -34,10 +34,12 @@
struct pios_rcvr_driver {
void (*init)(uint32_t id);
int32_t (*read)(uint32_t id, uint8_t channel);
xSemaphoreHandle (*get_semaphore)(uint32_t id, uint8_t channel);
};
/* Public Functions */
extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel);
extern xSemaphoreHandle PIOS_RCVR_GetSemaphore(uint32_t rcvr_id, uint8_t channel);
/*! Define error codes for PIOS_RCVR_Get */
enum PIOS_RCVR_errors {

View File

@ -31,11 +31,12 @@
#ifndef PIOS_RFM22B_H
#define PIOS_RFM22B_H
#include <packet_handler.h>
#include <uavobjectmanager.h>
#include <oplinksettings.h>
/* Constant definitions */
enum gpio_direction { GPIO0_TX_GPIO1_RX, GPIO0_RX_GPIO1_TX };
#define RFM22B_PPM_NUM_CHANNELS 8
/* Global Types */
struct pios_rfm22b_cfg {
@ -45,6 +46,7 @@ struct pios_rfm22b_cfg {
uint8_t slave_num;
enum gpio_direction gpio_direction;
};
typedef void (*PPMReceivedCallback)(const int16_t *channels);
enum rfm22b_tx_power {
RFM22_tx_pwr_txpow_0 = 0x00, // +1dBm .. 1.25mW
@ -58,21 +60,15 @@ enum rfm22b_tx_power {
};
enum rfm22b_datarate {
RFM22_datarate_500 = 0,
RFM22_datarate_1000 = 1,
RFM22_datarate_2000 = 2,
RFM22_datarate_4000 = 3,
RFM22_datarate_8000 = 4,
RFM22_datarate_9600 = 5,
RFM22_datarate_16000 = 6,
RFM22_datarate_19200 = 7,
RFM22_datarate_24000 = 8,
RFM22_datarate_32000 = 9,
RFM22_datarate_57600 = 10,
RFM22_datarate_64000 = 11,
RFM22_datarate_128000 = 12,
RFM22_datarate_192000 = 13,
RFM22_datarate_256000 = 14,
RFM22_datarate_9600 = 0,
RFM22_datarate_19200 = 1,
RFM22_datarate_32000 = 2,
RFM22_datarate_57600 = 3,
RFM22_datarate_64000 = 4,
RFM22_datarate_100000 = 5,
RFM22_datarate_128000 = 6,
RFM22_datarate_192000 = 7,
RFM22_datarate_256000 = 8,
};
typedef enum {
@ -104,30 +100,24 @@ struct rfm22b_stats {
uint8_t link_state;
};
/* Callback function prototypes */
typedef void (*PIOS_RFM22B_ComConfigCallback)(OPLinkSettingsRemoteMainPortOptions main_port, OPLinkSettingsRemoteFlexiPortOptions flexi_port,
OPLinkSettingsRemoteVCPPortOptions vcp_port, OPLinkSettingsComSpeedOptions com_speed);
/* 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 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_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_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 void PIOS_RFM22B_SetChannelConfig(uint32_t rfm22b_id, enum rfm22b_datarate datarate, uint8_t min_chan, uint8_t max_chan, uint8_t chan_set, bool coordinator, bool oneway, bool ppm_mode, bool ppm_only);
extern void PIOS_RFM22B_SetCoordinatorID(uint32_t rfm22b_id, uint32_t coord_id);
extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id);
extern bool PIOS_RFM22B_IsCoordinator(uint32_t rfb22b_id);
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 bool PIOS_RFM22B_InRxWait(uint32_t rfb22b_id);
extern bool PIOS_RFM22B_LinkStatus(uint32_t rfm22b_id);
extern bool PIOS_RFM22B_ReceivePacket(uint32_t rfm22b_id, PHPacketHandle p);
extern bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, PHPacketHandle p);
extern bool PIOS_RFM22B_ReceivePacket(uint32_t rfm22b_id, uint8_t *p);
extern bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, uint8_t *p, uint8_t len);
extern pios_rfm22b_int_result PIOS_RFM22B_ProcessTx(uint32_t rfm22b_id);
extern pios_rfm22b_int_result PIOS_RFM22B_ProcessRx(uint32_t rfm22b_id);
extern void PIOS_RFM22B_SetPPMCallback(uint32_t rfm22b_id, PPMReceivedCallback cb);
extern void PIOS_RFM22B_PPMSet(uint32_t rfm22b_id, int16_t *channels);
extern void PIOS_RFM22B_PPMGet(uint32_t rfm22b_id, int16_t *channels);
/* Global Variables */
extern const struct pios_com_driver pios_rfm22b_com_driver;

View File

@ -36,7 +36,11 @@
#include <uavobjectmanager.h>
#include <oplinkstatus.h>
#include "pios_rfm22b.h"
#include "pios_rfm22b_rcvr.h"
// ************************************
#define RFM22B_MAX_PACKET_LEN 64
#define RFM22B_NUM_CHANNELS 250
// ************************************
@ -46,11 +50,6 @@
// ************************************
#define RFM22_MIN_CARRIER_FREQUENCY_HZ 240000000ul
#define RFM22_MAX_CARRIER_FREQUENCY_HZ 930000000ul
// ************************************
#define BIT0 (1u << 0)
#define BIT1 (1u << 1)
#define BIT2 (1u << 2)
@ -534,19 +533,12 @@ enum pios_rfm22b_dev_magic {
enum pios_radio_state {
RADIO_STATE_UNINITIALIZED,
RADIO_STATE_INITIALIZING,
RADIO_STATE_REQUESTING_CONNECTION,
RADIO_STATE_ACCEPTING_CONNECTION,
RADIO_STATE_RX_MODE,
RADIO_STATE_RX_DATA,
RADIO_STATE_RX_FAILURE,
RADIO_STATE_RECEIVING_STATUS,
RADIO_STATE_TX_START,
RADIO_STATE_TX_DATA,
RADIO_STATE_TX_FAILURE,
RADIO_STATE_SENDING_ACK,
RADIO_STATE_SENDING_NACK,
RADIO_STATE_RECEIVING_ACK,
RADIO_STATE_RECEIVING_NACK,
RADIO_STATE_TIMEOUT,
RADIO_STATE_ERROR,
RADIO_STATE_FATAL_ERROR,
@ -559,16 +551,9 @@ enum pios_radio_event {
RADIO_EVENT_INT_RECEIVED,
RADIO_EVENT_INITIALIZE,
RADIO_EVENT_INITIALIZED,
RADIO_EVENT_REQUEST_CONNECTION,
RADIO_EVENT_CONNECTION_REQUESTED,
RADIO_EVENT_PACKET_ACKED,
RADIO_EVENT_PACKET_NACKED,
RADIO_EVENT_ACK_TIMEOUT,
RADIO_EVENT_RX_MODE,
RADIO_EVENT_RX_COMPLETE,
RADIO_EVENT_STATUS_RECEIVED,
RADIO_EVENT_TX_START,
RADIO_EVENT_FAILURE,
RADIO_EVENT_TIMEOUT,
RADIO_EVENT_ERROR,
RADIO_EVENT_FATAL_ERROR,
@ -603,14 +588,6 @@ typedef struct {
uint8_t lastContact;
} rfm22b_pair_stats;
typedef struct {
uint32_t pairID;
OPLinkSettingsRemoteMainPortOptions main_port;
OPLinkSettingsRemoteFlexiPortOptions flexi_port;
OPLinkSettingsRemoteVCPPortOptions vcp_port;
OPLinkSettingsComSpeedOptions com_speed;
} rfm22b_binding;
enum pios_rfm22b_chip_power_state {
RFM22B_IDLE_STATE = 0x00,
RFM22B_RX_STATE = 0x01,
@ -683,27 +660,22 @@ typedef struct {
rfm22b_int_status_2 int_status_2;
} rfm22b_device_status;
struct pios_rfm22b_dev {
enum pios_rfm22b_dev_magic magic;
struct pios_rfm22b_cfg cfg;
// The SPI bus information
uint32_t spi_id;
uint32_t slave_num;
uint32_t spi_id;
uint32_t slave_num;
// Should this modem ack as a coordinator.
bool coordinator;
// The device ID
uint32_t deviceID;
uint32_t deviceID;
// The 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?
bool coordinator;
// The coodinator ID (0 if this modem is a coordinator).
uint32_t coordinatorID;
// The task handle
xTaskHandle taskHandle;
@ -714,9 +686,6 @@ struct pios_rfm22b_dev {
// ISR pending semaphore
xSemaphoreHandle isrPending;
// The com configuration callback
PIOS_RFM22B_ComConfigCallback com_config_cb;
// The COM callback functions.
pios_com_callback rx_in_cb;
uint32_t rx_in_context;
@ -755,11 +724,9 @@ struct pios_rfm22b_dev {
int8_t rssi_dBm;
// The tx data packet
PHPacket data_packet;
uint8_t tx_packet[RFM22B_MAX_PACKET_LEN];
// The current tx packet
PHPacketHandle tx_packet;
// The previous tx packet (waiting for an ACK)
PHPacketHandle prev_tx_packet;
uint8_t *tx_packet_handle;
// The tx data read index
uint16_t tx_data_rd;
// The tx data write index
@ -768,65 +735,52 @@ struct pios_rfm22b_dev {
uint16_t tx_seq;
// The rx data packet
PHPacket rx_packet;
uint8_t rx_packet[RFM22B_MAX_PACKET_LEN];
// The rx data packet
PHPacketHandle rx_packet_handle;
uint8_t *rx_packet_handle;
// The receive buffer write index
uint16_t rx_buffer_wr;
// The receive buffer write index
uint16_t rx_packet_len;
// The status packet
PHStatusPacket status_packet;
// The PPM buffer
int16_t ppm[RFM22B_PPM_NUM_CHANNELS];
// The PPM packet received callback.
PPMReceivedCallback ppm_callback;
// The ACK/NACK packet
PHAckNackPacket ack_nack_packet;
// The id that the packet was received from
uint32_t rx_destination_id;
// The maximum packet length (including header, etc.)
uint8_t max_packet_len;
// The packet transmit time in ms.
uint8_t packet_time;
// Do all packets originate from the coordinator modem?
bool one_way_link;
// Should this modem send PPM data?
bool ppm_send_mode;
// Should this modem receive PPM data?
bool ppm_recv_mode;
// Are we sending / receiving only PPM data?
bool ppm_only_mode;
#ifdef PIOS_PPM_RECEIVER
// The PPM packet
PHPpmPacket ppm_packet;
#endif
// The connection packet.
PHConnectionPacket con_packet;
// Send flags
bool send_status;
bool send_ppm;
bool send_connection_request;
bool send_ack_nack;
bool resend_packet;
// The initial frequency
uint32_t init_frequency;
// The channel list
uint8_t channels[RFM22B_NUM_CHANNELS];
// The number of frequency hopping channels.
uint16_t num_channels;
uint8_t num_channels;
// The frequency hopping step size
float frequency_step_size;
// current frequency hop channel
uint8_t frequency_hop_channel;
uint8_t channel;
// current frequency hop channel index
uint8_t channel_index;
// afc correction reading (in Hz)
int8_t afc_correction_Hz;
// The packet timers.
portTickType packet_start_ticks;
portTickType tx_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;
#ifdef PIOS_INCLUDE_RFM22B_RCVR
// The PPM channel values
uint16_t ppm_channel[PIOS_RFM22B_RCVR_MAX_CHANNELS];
uint32_t ppm_supv_timer;
bool ppm_fresh;
#endif
bool on_sync_channel;
};

View File

@ -241,10 +241,6 @@
#include <pios_sbus.h>
#endif
#ifdef PIOS_INCLUDE_GCSRCVR
/* only priv header */
#endif
/* PIOS abstract receiver interface */
#ifdef PIOS_INCLUDE_RCVR
#include <pios_rcvr.h>
@ -300,9 +296,6 @@
#ifdef PIOS_INCLUDE_RFM22B_COM
#include <pios_rfm22b_com.h>
#endif
#ifdef PIOS_INCLUDE_RFM22B_RCVR
#include <pios_rfm22b_rcvr.h>
#endif
#endif /* PIOS_INCLUDE_RFM22B */
/* PIOS misc peripherals */

View File

@ -32,14 +32,19 @@
#ifdef PIOS_INCLUDE_PPM
#include "pios_ppm_priv.h"
#include <pios_stm32.h>
#include "pios_ppm_priv.h"
/* Provide a RCVR driver */
static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel);
static xSemaphoreHandle PIOS_PPM_Get_Semaphore(uint32_t rcvr_id, uint8_t channel);
const struct pios_rcvr_driver pios_ppm_rcvr_driver = {
.read = PIOS_PPM_Get,
.read = PIOS_PPM_Get,
#if defined(PIOS_INCLUDE_FREERTOS)
.get_semaphore = PIOS_PPM_Get_Semaphore
#endif
};
#define PIOS_PPM_IN_MIN_NUM_CHANNELS 4
@ -76,6 +81,10 @@ struct pios_ppm_dev {
uint8_t supv_timer;
bool Tracking;
bool Fresh;
#ifdef PIOS_INCLUDE_FREERTOS
xSemaphoreHandle new_sample_semaphores[PIOS_PPM_IN_MIN_NUM_CHANNELS];
#endif /* PIOS_INCLUDE_FREERTOS */
};
static bool PIOS_PPM_validate(struct pios_ppm_dev *ppm_dev)
@ -93,6 +102,11 @@ static struct pios_ppm_dev *PIOS_PPM_alloc(void)
return NULL;
}
// Initialize the semaphores to 0.
for (uint8_t i = 0; i < PIOS_PPM_IN_MIN_NUM_CHANNELS; ++i) {
ppm_dev->new_sample_semaphores[i] = 0;
}
ppm_dev->magic = PIOS_PPM_DEV_MAGIC;
return ppm_dev;
}
@ -199,6 +213,28 @@ out_fail:
return -1;
}
#if defined(PIOS_INCLUDE_FREERTOS)
static xSemaphoreHandle PIOS_PPM_Get_Semaphore(uint32_t rcvr_id, uint8_t channel)
{
struct pios_ppm_dev *ppm_dev = (struct pios_ppm_dev *)rcvr_id;
if (!PIOS_PPM_validate(ppm_dev)) {
/* Invalid device specified */
return 0;
}
if (channel >= PIOS_PPM_IN_MAX_NUM_CHANNELS) {
/* Channel out of range */
return 0;
}
if (ppm_dev->new_sample_semaphores[channel] == 0) {
vSemaphoreCreateBinary(ppm_dev->new_sample_semaphores[channel]);
}
return ppm_dev->new_sample_semaphores[channel];
}
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
/**
* Get the value of an input channel
* \param[in] channel Number of the channel desired (zero based)
@ -296,6 +332,15 @@ static void PIOS_PPM_tim_edge_cb(__attribute__((unused)) uint32_t tim_id,
i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT;
}
#if defined(PIOS_INCLUDE_FREERTOS)
/* Signal that a new sample is ready on this channel. */
if (ppm_dev->new_sample_semaphores[chan_idx] != 0) {
signed portBASE_TYPE pxHigherPriorityTaskWoken = pdFALSE;
if (xSemaphoreGiveFromISR(ppm_dev->new_sample_semaphores[chan_idx], &pxHigherPriorityTaskWoken) == pdTRUE) {
portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); /* FIXME: is this the right place for this? */
}
}
#endif /* USE_FREERTOS */
}
ppm_dev->Fresh = TRUE;

View File

@ -36,9 +36,13 @@
/* Provide a RCVR driver */
static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel);
static xSemaphoreHandle PIOS_PPM_Get_Semaphore(uint32_t rcvr_id, uint8_t channel);
const struct pios_rcvr_driver pios_ppm_rcvr_driver = {
.read = PIOS_PPM_Get,
.read = PIOS_PPM_Get,
#if defined(PIOS_INCLUDE_FREERTOS)
.get_semaphore = PIOS_PPM_Get_Semaphore
#endif
};
#define PIOS_PPM_IN_MIN_NUM_CHANNELS 4
@ -72,6 +76,10 @@ struct pios_ppm_dev {
uint8_t supv_timer;
bool Tracking;
bool Fresh;
#ifdef PIOS_INCLUDE_FREERTOS
xSemaphoreHandle new_sample_semaphores[PIOS_PPM_IN_MIN_NUM_CHANNELS];
#endif /* PIOS_INCLUDE_FREERTOS */
};
static bool PIOS_PPM_validate(struct pios_ppm_dev *ppm_dev)
@ -89,6 +97,11 @@ static struct pios_ppm_dev *PIOS_PPM_alloc(void)
return NULL;
}
// Initialize the semaphores to 0.
for (uint8_t i = 0; i < PIOS_PPM_IN_MIN_NUM_CHANNELS; ++i) {
ppm_dev->new_sample_semaphores[i] = 0;
}
ppm_dev->magic = PIOS_PPM_DEV_MAGIC;
return ppm_dev;
}
@ -194,6 +207,28 @@ out_fail:
return -1;
}
#if defined(PIOS_INCLUDE_FREERTOS)
static xSemaphoreHandle PIOS_PPM_Get_Semaphore(uint32_t rcvr_id, uint8_t channel)
{
struct pios_ppm_dev *ppm_dev = (struct pios_ppm_dev *)rcvr_id;
if (!PIOS_PPM_validate(ppm_dev)) {
/* Invalid device specified */
return 0;
}
if (channel >= PIOS_PPM_IN_MAX_NUM_CHANNELS) {
/* Channel out of range */
return 0;
}
if (ppm_dev->new_sample_semaphores[channel] == 0) {
vSemaphoreCreateBinary(ppm_dev->new_sample_semaphores[channel]);
}
return ppm_dev->new_sample_semaphores[channel];
}
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
/**
* Get the value of an input channel
* \param[in] channel Number of the channel desired (zero based)
@ -286,6 +321,15 @@ static void PIOS_PPM_tim_edge_cb(__attribute__((unused)) uint32_t tim_id, uint32
i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT;
}
#if defined(PIOS_INCLUDE_FREERTOS)
/* Signal that a new sample is ready on this channel. */
if (ppm_dev->new_sample_semaphores[chan_idx] != 0) {
signed portBASE_TYPE pxHigherPriorityTaskWoken = pdFALSE;
if (xSemaphoreGiveFromISR(ppm_dev->new_sample_semaphores[chan_idx], &pxHigherPriorityTaskWoken) == pdTRUE) {
portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); /* FIXME: is this the right place for his? */
}
}
#endif /* USE_FREERTOS */
}
ppm_dev->Fresh = true;

View File

@ -93,6 +93,7 @@
#define PIOS_INCLUDE_DSM
#define PIOS_INCLUDE_SBUS
#define PIOS_INCLUDE_GCSRCVR
/* #define PIOS_INCLUDE_OPLINKRCVR */
/* PIOS abstract receiver interface */
#define PIOS_INCLUDE_RCVR
@ -115,7 +116,6 @@
/* PIOS radio modules */
/* #define PIOS_INCLUDE_RFM22B */
/* #define PIOS_INCLUDE_RFM22B_COM */
/* #define PIOS_INCLUDE_RFM22B_RCVR */
/* #define PIOS_INCLUDE_PPM_OUT */
/* #define PIOS_RFM22B_DEBUG_ON_TELEM */

View File

@ -432,7 +432,77 @@ static const struct pios_tim_clock_cfg tim_4_cfg = {
},
};
static const struct pios_tim_channel pios_tim_ppm_flexi_port = {
static const struct pios_tim_channel pios_tim_all_port_pins[] = {
/* Main Tx */
{
.timer = TIM1,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
/* Main Rx */
{
.timer = TIM1,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
/* Flexi Tx */
{
.timer = TIM2,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.remap = GPIO_PartialRemap2_TIM2,
},
/* Flexi Rx */
{
.timer = TIM2,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.remap = GPIO_PartialRemap2_TIM2,
},
};
static const struct pios_tim_channel pios_tim_main_port_ppm = {
.timer = TIM1,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Mode = GPIO_Mode_IPD,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
};
static const struct pios_tim_channel pios_tim_flexi_port_ppm = {
.timer = TIM2,
.timer_chan = TIM_Channel_4,
.pin = {
@ -446,20 +516,126 @@ static const struct pios_tim_channel pios_tim_ppm_flexi_port = {
.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 */
#if defined(PIOS_INCLUDE_SERVO) && defined(PIOS_INCLUDE_TIM)
/*
* Servo outputs
*/
#include <pios_servo_priv.h>
const struct pios_servo_cfg pios_servo_main_cfg = {
.tim_oc_init = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
.TIM_OCPolarity = TIM_OCPolarity_High,
.TIM_OCNPolarity = TIM_OCPolarity_High,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
},
.channels = pios_tim_all_port_pins,
.num_channels = 2
};
#endif /* PIOS_INCLUDE_TIM */
const struct pios_servo_cfg pios_servo_flexi_cfg = {
.tim_oc_init = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
.TIM_OCPolarity = TIM_OCPolarity_High,
.TIM_OCNPolarity = TIM_OCPolarity_High,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
},
.channels = &(pios_tim_all_port_pins[2]),
.num_channels = 2
};
const struct pios_servo_cfg pios_servo_main_flexi_cfg = {
.tim_oc_init = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
.TIM_OCPolarity = TIM_OCPolarity_High,
.TIM_OCNPolarity = TIM_OCPolarity_High,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
},
.channels = pios_tim_all_port_pins,
.num_channels = 4
};
#endif /* PIOS_INCLUDE_SERVO && PIOS_INCLUDE_TIM */
/*
* PPM Inputs
*/
#if defined(PIOS_INCLUDE_PPM)
#include <pios_ppm_priv.h>
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_main_port_ppm,
.num_channels = 1,
};
const struct pios_ppm_cfg pios_ppm_flexi_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_flexi_port_ppm,
.num_channels = 1,
};
#endif /* PIOS_INCLUDE_PPM */
/*
* PPM Output
*/
#if defined(PIOS_INCLUDE_PPM_OUT)
#include <pios_ppm_out_priv.h>
const struct pios_ppm_out_cfg pios_main_ppm_out_cfg = {
.tim_oc_init = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
.TIM_OCPolarity = TIM_OCPolarity_Low,
.TIM_OCNPolarity = TIM_OCPolarity_Low,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
},
.channel = &(pios_tim_all_port_pins[0]),
};
const struct pios_ppm_out_cfg pios_flexi_ppm_out_cfg = {
.tim_oc_init = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
.TIM_OCPolarity = TIM_OCPolarity_Low,
.TIM_OCNPolarity = TIM_OCPolarity_Low,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
},
.channel = &(pios_tim_all_port_pins[2]),
};
#endif /* PIOS_INCLUDE_PPM_OUT */
#if defined(PIOS_INCLUDE_USART)
@ -576,74 +752,6 @@ void PIOS_RTC_IRQ_Handler(void)
#endif /* if defined(PIOS_INCLUDE_RTC) */
/*
* PPM Inputs
*/
#if defined(PIOS_INCLUDE_PPM)
#include <pios_ppm_priv.h>
const struct pios_ppm_cfg pios_ppm_flexi_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_flexi_port,
.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 */
/*
* PPM Output
*/
#if defined(PIOS_INCLUDE_PPM_OUT)
#include <pios_ppm_out_priv.h>
static const struct pios_tim_channel pios_tim_ppmout[] = {
{
.timer = TIM2,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.remap = GPIO_FullRemap_TIM2,
}
};
const struct pios_ppm_out_cfg pios_ppm_out_cfg = {
.tim_oc_init = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
.TIM_OCPolarity = TIM_OCPolarity_Low,
.TIM_OCNPolarity = TIM_OCPolarity_Low,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
},
.channel = pios_tim_ppmout,
};
#endif /* PIOS_INCLUDE_PPM_OUT */
#if defined(PIOS_INCLUDE_RCVR)
#include "pios_rcvr_priv.h"

View File

@ -49,10 +49,10 @@ ifndef TESTAPP
SRC += $(OPUAVOBJ)/callbackscheduler.c
## UAVObjects
SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c
SRC += $(OPUAVSYNTHDIR)/oplinkstatus.c
SRC += $(OPUAVSYNTHDIR)/oplinksettings.c
SRC += $(OPUAVSYNTHDIR)/objectpersistence.c
SRC += $(OPUAVSYNTHDIR)/oplinkreceiver.c
else
## Test Code
SRC += $(OPTESTS)/test_common.c

View File

@ -87,12 +87,13 @@
/* #define PIOS_INCLUDE_HCSR04 */
/* PIOS receiver drivers */
/* #define PIOS_INCLUDE_PWM */
#define PIOS_INCLUDE_PWM
#define PIOS_INCLUDE_PPM
/* #define PIOS_INCLUDE_PPM_FLEXI */
/* #define PIOS_INCLUDE_DSM */
/* #define PIOS_INCLUDE_SBUS */
#define PIOS_INCLUDE_GCSRCVR
/* #define PIOS_INCLUDE_GCSRCVR */
/* #define PIOS_INCLUDE_OPLINKRCVR */
/* PIOS abstract receiver interface */
#define PIOS_INCLUDE_RCVR
@ -100,7 +101,7 @@
/* PIOS common peripherals */
#define PIOS_INCLUDE_LED
#define PIOS_INCLUDE_IAP
/* #define PIOS_INCLUDE_SERVO */
#define PIOS_INCLUDE_SERVO
/* #define PIOS_INCLUDE_I2C_ESC */
/* #define PIOS_INCLUDE_OVERO */
/* #define PIOS_OVERO_SPI */
@ -115,7 +116,6 @@
/* PIOS radio modules */
#define PIOS_INCLUDE_RFM22B
#define PIOS_INCLUDE_RFM22B_COM
/* #define PIOS_INCLUDE_RFM22B_RCVR */
#define PIOS_INCLUDE_PPM_OUT
/* #define PIOS_RFM22B_DEBUG_ON_TELEM */

View File

@ -29,8 +29,12 @@
#include "inc/openpilot.h"
#include <pios_board_info.h>
#include <pios_ppm_out.h>
#include <oplinksettings.h>
#include <taskinfo.h>
#ifdef PIOS_INCLUDE_SERVO
#include <pios_servo.h>
#endif
/*
* Pull in the board-specific static HW definitions.
@ -75,6 +79,11 @@ uint8_t *pios_uart_tx_buffer;
uintptr_t pios_uavo_settings_fs_id;
uint8_t servo_count = 0;
// Forward definitions
static void PIOS_Board_PPM_callback(const int16_t *channels);
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
@ -115,33 +124,26 @@ void PIOS_Board_Init(void)
PIOS_RTC_Init(&pios_rtc_main_cfg);
#endif /* PIOS_INCLUDE_RTC */
OPLinkSettingsInitialize();
#if defined(PIOS_INCLUDE_LED)
PIOS_LED_Init(&pios_led_cfg);
#endif /* PIOS_INCLUDE_LED */
OPLinkSettingsData oplinkSettings;
/* IAP System Setup */
PIOS_IAP_Init();
// check for safe mode commands from gcs
if (PIOS_IAP_ReadBootCmd(0) == PIOS_IAP_CLEAR_FLASH_CMD_0 &&
PIOS_IAP_ReadBootCmd(1) == PIOS_IAP_CLEAR_FLASH_CMD_1 &&
PIOS_IAP_ReadBootCmd(2) == PIOS_IAP_CLEAR_FLASH_CMD_2) {
OPLinkSettingsGet(&oplinkSettings);
OPLinkSettingsSetDefaults(&oplinkSettings, 0);
OPLinkSettingsSet(&oplinkSettings);
// PIOS_EEPROM_Save((uint8_t*)&oplinkSettings, sizeof(OPLinkSettingsData));
for (uint32_t i = 0; i < 10; i++) {
PIOS_DELAY_WaitmS(100);
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
}
PIOS_FLASHFS_Format(pios_uavo_settings_fs_id);
PIOS_IAP_WriteBootCmd(0, 0);
PIOS_IAP_WriteBootCmd(1, 0);
PIOS_IAP_WriteBootCmd(2, 0);
}
OPLinkSettingsGet(&oplinkSettings);
#if defined(PIOS_INCLUDE_RFM22B)
OPLinkSettingsInitialize();
OPLinkStatusInitialize();
#endif /* PIOS_INCLUDE_RFM22B */
#if defined(PIOS_INCLUDE_LED)
PIOS_LED_Init(&pios_led_cfg);
#endif /* PIOS_INCLUDE_LED */
/* Initialize the delayed callback library */
CallbackSchedulerInitialize();
@ -212,16 +214,163 @@ void PIOS_Board_Init(void)
}
#endif
/* Allocate the uart buffers. */
pios_uart_rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_RX_BUF_LEN);
pios_uart_tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_TX_BUF_LEN);
// Configure the main port
OPLinkSettingsData oplinkSettings;
OPLinkSettingsGet(&oplinkSettings);
bool is_coordinator = (oplinkSettings.Coordinator == OPLINKSETTINGS_COORDINATOR_TRUE);
bool is_oneway = (oplinkSettings.OneWay == OPLINKSETTINGS_ONEWAY_TRUE);
bool ppm_only = (oplinkSettings.PPMOnly == OPLINKSETTINGS_PPMONLY_TRUE);
bool ppm_mode = false;
bool servo_main = false;
bool servo_flexi = false;
switch (oplinkSettings.MainPort) {
case OPLINKSETTINGS_MAINPORT_TELEMETRY:
case OPLINKSETTINGS_MAINPORT_SERIAL:
{
/* Configure the main port for uart serial */
#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);
}
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_MAIN;
#endif
break;
}
case OPLINKSETTINGS_MAINPORT_PPM:
{
#if defined(PIOS_INCLUDE_PPM)
/* PPM input is configured on the coordinator modem and output on the remote modem. */
if (is_coordinator) {
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.
#if defined(PIOS_INCLUDE_PPM_OUT)
else {
PIOS_PPM_Out_Init(&pios_ppm_out_id, &pios_main_ppm_out_cfg);
}
#endif /* PIOS_INCLUDE_PPM_OUT */
ppm_mode = true;
#endif /* PIOS_INCLUDE_PPM */
break;
}
case OPLINKSETTINGS_MAINPORT_PWM:
servo_main = true;
break;
case OPLINKSETTINGS_MAINPORT_DISABLED:
break;
}
// Configure the flexi port
switch (oplinkSettings.FlexiPort) {
case OPLINKSETTINGS_FLEXIPORT_TELEMETRY:
case OPLINKSETTINGS_FLEXIPORT_SERIAL:
{
/* Configure the flexi port as uart serial */
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);
}
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_FLEXI;
break;
}
case OPLINKSETTINGS_FLEXIPORT_PPM:
{
#if defined(PIOS_INCLUDE_PPM)
/* PPM input is configured on the coordinator modem and output on the remote modem. */
if (is_coordinator) {
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);
}
} else {
PIOS_PPM_Out_Init(&pios_ppm_out_id, &pios_flexi_ppm_out_cfg);
}
#endif /* PIOS_INCLUDE_PPM */
ppm_mode = true;
break;
}
case OPLINKSETTINGS_FLEXIPORT_PWM:
servo_flexi = true;
break;
case OPLINKSETTINGS_FLEXIPORT_DISABLED:
break;
}
// Configure the USB VCP port
switch (oplinkSettings.VCPPort) {
case OPLINKSETTINGS_VCPPORT_SERIAL:
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_USB_VCP;
break;
case OPLINKSETTINGS_VCPPORT_DISABLED:
break;
}
#if defined(PIOS_INCLUDE_SERVO)
if (servo_main) {
if (servo_flexi) {
servo_count = 4;
PIOS_Servo_Init(&pios_servo_main_flexi_cfg);
} else {
servo_count = 2;
PIOS_Servo_Init(&pios_servo_main_cfg);
}
} else if (servo_flexi) {
servo_count = 2;
PIOS_Servo_Init(&pios_servo_flexi_cfg);
}
ppm_mode = ppm_mode || (servo_count > 0);
#endif
// Initialize out status object.
OPLinkStatusData oplinkStatus;
OPLinkStatusGet(&oplinkStatus);
// Get our hardware information.
const struct pios_board_info *bdinfo = &pios_board_info_blob;
oplinkStatus.BoardType = bdinfo->board_type;
PIOS_BL_HELPER_FLASH_Read_Description(oplinkStatus.Description, OPLINKSTATUS_DESCRIPTION_NUMELEM);
PIOS_SYS_SerialNumberGetBinary(oplinkStatus.CPUSerial);
oplinkStatus.BoardRevision = bdinfo->board_rev;
/* Initalize the RFM22B radio COM device. */
#if defined(PIOS_INCLUDE_RFM22B)
{
const struct pios_board_info *bdinfo = &pios_board_info_blob;
if (oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) {
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
// Configure the RFM22B device
const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev);
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) {
PIOS_Assert(0);
}
// Configure the radio com interface
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);
PIOS_Assert(rx_buffer);
@ -232,15 +381,103 @@ void PIOS_Board_Init(void)
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 */
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
enum rfm22b_datarate datarate = RFM22_datarate_64000;
switch (oplinkSettings.ComSpeed) {
case OPLINKSETTINGS_COMSPEED_4800:
datarate = RFM22_datarate_9600;
break;
case OPLINKSETTINGS_COMSPEED_9600:
datarate = RFM22_datarate_19200;
break;
case OPLINKSETTINGS_COMSPEED_19200:
datarate = RFM22_datarate_32000;
break;
case OPLINKSETTINGS_COMSPEED_38400:
datarate = RFM22_datarate_64000;
break;
case OPLINKSETTINGS_COMSPEED_57600:
datarate = RFM22_datarate_100000;
break;
case OPLINKSETTINGS_COMSPEED_115200:
datarate = RFM22_datarate_192000;
break;
}
/* 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);
/* Set the modem Tx poer level */
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 radio configuration parameters.
PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, datarate, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, oplinkSettings.ChannelSet, is_coordinator, is_oneway, ppm_mode, ppm_only);
PIOS_RFM22B_SetCoordinatorID(pios_rfm22b_id, oplinkSettings.CoordID);
/* Set the PPM callback if we should be receiving PPM. */
if (ppm_mode) {
PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback);
}
// Reinitilize the modem to affect te changes.
PIOS_RFM22B_Reinit(pios_rfm22b_id);
} else {
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
}
// Update the object
OPLinkStatusSet(&oplinkStatus);
// Update the com baud rate.
uint32_t comBaud = 9600;
switch (oplinkSettings.ComSpeed) {
case OPLINKSETTINGS_COMSPEED_4800:
comBaud = 4800;
break;
case OPLINKSETTINGS_COMSPEED_9600:
comBaud = 9600;
break;
case OPLINKSETTINGS_COMSPEED_19200:
comBaud = 19200;
break;
case OPLINKSETTINGS_COMSPEED_38400:
comBaud = 38400;
break;
case OPLINKSETTINGS_COMSPEED_57600:
comBaud = 57600;
break;
case OPLINKSETTINGS_COMSPEED_115200:
comBaud = 115200;
break;
}
if (PIOS_COM_TELEMETRY) {
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, comBaud);
}
/* Remap AFIO pin */
GPIO_PinRemapConfig(GPIO_Remap_SWJ_NoJTRST, ENABLE);
@ -251,73 +488,23 @@ void PIOS_Board_Init(void)
PIOS_GPIO_Init();
}
void PIOS_InitUartMainPort()
static void PIOS_Board_PPM_callback(const int16_t *channels)
{
#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);
#if defined(PIOS_INCLUDE_PPM) && defined(PIOS_INCLUDE_PPM_OUT)
if (pios_ppm_out_id) {
for (uint8_t i = 0; i < RFM22B_PPM_NUM_CHANNELS; ++i) {
if (channels[i] != PIOS_RCVR_INVALID) {
PIOS_PPM_OUT_Set(PIOS_PPM_OUTPUT, i, channels[i]);
}
}
}
// 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_SERVO)
for (uint8_t i = 0; i < servo_count; ++i) {
uint16_t val = (channels[i] == PIOS_RCVR_INVALID) ? 0 : channels[i];
PIOS_Servo_Set(i, val);
}
#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 */
#endif /* PIOS_INCLUDE_SERVO */
#endif /* PIOS_INCLUDE_PPM && PIOS_INCLUDE_PPM_OUT */
}
/**

View File

@ -75,7 +75,9 @@
#define PIOS_WDG_TELEMETRYRX 0x0002
#define PIOS_WDG_RADIOTX 0x0004
#define PIOS_WDG_RADIORX 0x0008
#define PIOS_WDG_RFM22B 0x0016
#define PIOS_WDG_RFM22B 0x000f
#define PIOS_WDG_PPMINPUT 0x0010
#define PIOS_WDG_SERIALRX 0x0020
// ------------------------
// TELEMETRY
@ -247,6 +249,11 @@ extern uint32_t pios_ppm_out_id;
#define PIOS_PPM_MAX_DEVS 1
#define PIOS_PPM_NUM_INPUTS 8
// -------------------------
// Receiver PWM inputs
// -------------------------
#define PIOS_PWM_NUM_INPUTS 4
// -------------------------
// Servo outputs
// -------------------------

View File

@ -93,6 +93,7 @@
/* #define PIOS_INCLUDE_DSM */
/* #define PIOS_INCLUDE_SBUS */
/* #define PIOS_INCLUDE_GCSRCVR */
/* #define PIOS_INCLUDE_OPLINKRCVR */
/* PIOS abstract receiver interface */
/* #define PIOS_INCLUDE_RCVR */
@ -116,7 +117,6 @@
/* PIOS radio modules */
/* #define PIOS_INCLUDE_RFM22B */
/* #define PIOS_INCLUDE_RFM22B_COM */
/* #define PIOS_INCLUDE_RFM22B_RCVR */
/* #define PIOS_INCLUDE_PPM_OUT */
/* #define PIOS_RFM22B_DEBUG_ON_TELEM */

View File

@ -59,6 +59,7 @@ UAVOBJSRCFILENAMES += mixersettings
UAVOBJSRCFILENAMES += mixerstatus
UAVOBJSRCFILENAMES += nedaccel
UAVOBJSRCFILENAMES += objectpersistence
UAVOBJSRCFILENAMES += oplinkreceiver
UAVOBJSRCFILENAMES += overosyncstats
UAVOBJSRCFILENAMES += overosyncsettings
UAVOBJSRCFILENAMES += pathaction
@ -87,7 +88,10 @@ UAVOBJSRCFILENAMES += hwsettings
UAVOBJSRCFILENAMES += receiveractivity
UAVOBJSRCFILENAMES += cameradesired
UAVOBJSRCFILENAMES += camerastabsettings
UAVOBJSRCFILENAMES += altitudeholdsettings
UAVOBJSRCFILENAMES += altitudeholdsettings
UAVOBJSRCFILENAMES += oplinksettings
UAVOBJSRCFILENAMES += oplinkstatus
UAVOBJSRCFILENAMES += altitudeholddesired
UAVOBJSRCFILENAMES += waypoint
UAVOBJSRCFILENAMES += waypointactive

View File

@ -93,6 +93,7 @@
#define PIOS_INCLUDE_DSM
#define PIOS_INCLUDE_SBUS
#define PIOS_INCLUDE_GCSRCVR
#define PIOS_INCLUDE_OPLINKRCVR
/* PIOS abstract receiver interface */
#define PIOS_INCLUDE_RCVR
@ -115,7 +116,6 @@
/* PIOS radio modules */
#define PIOS_INCLUDE_RFM22B
#define PIOS_INCLUDE_RFM22B_COM
#define PIOS_INCLUDE_RFM22B_RCVR
/* #define PIOS_INCLUDE_PPM_OUT */
/* #define PIOS_RFM22B_DEBUG_ON_TELEM */

View File

@ -30,6 +30,10 @@
#include <uavobjectsinit.h>
#include <hwsettings.h>
#include <manualcontrolsettings.h>
#include <oplinksettings.h>
#include <oplinkstatus.h>
#include <oplinkreceiver.h>
#include <pios_oplinkrcvr_priv.h>
#include <taskinfo.h>
/*
@ -315,6 +319,17 @@ static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *ppm_cfg)
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id;
}
static void PIOS_Board_PPM_callback(const int16_t *channels)
{
uint8_t max_chan = (RFM22B_PPM_NUM_CHANNELS < OPLINKRECEIVER_CHANNEL_NUMELEM) ? RFM22B_PPM_NUM_CHANNELS : OPLINKRECEIVER_CHANNEL_NUMELEM;
OPLinkReceiverData opl_rcvr;
for (uint8_t i = 0; i < max_chan; ++i) {
opl_rcvr.Channel[i] = channels[i];
}
OPLinkReceiverSet(&opl_rcvr);
}
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
@ -391,8 +406,12 @@ void PIOS_Board_Init(void)
/* Initialize UAVObject libraries */
EventDispatcherInitialize();
UAVObjInitialize();
HwSettingsInitialize();
#if defined(PIOS_INCLUDE_RFM22B)
OPLinkSettingsInitialize();
OPLinkStatusInitialize();
#endif /* PIOS_INCLUDE_RFM22B */
/* Initialize the alarms library */
AlarmsInitialize();
@ -704,25 +723,77 @@ void PIOS_Board_Init(void)
/* Initalize the RFM22B radio COM device. */
#if defined(PIOS_INCLUDE_RFM22B)
uint8_t hwsettings_radioport;
HwSettingsRadioPortGet(&hwsettings_radioport);
uint8_t hwsettings_maxrfpower;
HwSettingsMaxRFPowerGet(&hwsettings_maxrfpower);
uint32_t hwsettings_deffreq;
HwSettingsDefaultFrequencyGet(&hwsettings_deffreq);
switch (hwsettings_radioport) {
case HWSETTINGS_RADIOPORT_DISABLED:
break;
case HWSETTINGS_RADIOPORT_TELEMETRY:
{
/* Fetch the OPinkSettings object. */
OPLinkSettingsData oplinkSettings;
OPLinkSettingsGet(&oplinkSettings);
// Initialize out status object.
OPLinkStatusData oplinkStatus;
OPLinkStatusGet(&oplinkStatus);
oplinkStatus.BoardType = bdinfo->board_type;
PIOS_BL_HELPER_FLASH_Read_Description(oplinkStatus.Description, OPLINKSTATUS_DESCRIPTION_NUMELEM);
PIOS_SYS_SerialNumberGetBinary(oplinkStatus.CPUSerial);
oplinkStatus.BoardRevision = bdinfo->board_rev;
/* Is the radio turned on? */
bool is_coordinator = (oplinkSettings.Coordinator == OPLINKSETTINGS_COORDINATOR_TRUE);
bool is_oneway = (oplinkSettings.OneWay == OPLINKSETTINGS_ONEWAY_TRUE);
bool ppm_mode = (oplinkSettings.PPM == OPLINKSETTINGS_PPM_TRUE);
bool ppm_only = (oplinkSettings.PPMOnly == OPLINKSETTINGS_PPMONLY_TRUE);
if (oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) {
/* Configure the RFM22B device. */
const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev);
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) {
PIOS_Assert(0);
}
// Set the modem parameters and reinitilize the modem.
PIOS_RFM22B_SetInitialFrequency(pios_rfm22b_id, hwsettings_deffreq);
switch (hwsettings_maxrfpower) {
/* Configure the radio com interface */
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);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN,
tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) {
PIOS_Assert(0);
}
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
enum rfm22b_datarate datarate = RFM22_datarate_64000;
switch (oplinkSettings.ComSpeed) {
case OPLINKSETTINGS_COMSPEED_4800:
datarate = RFM22_datarate_9600;
break;
case OPLINKSETTINGS_COMSPEED_9600:
datarate = RFM22_datarate_19200;
break;
case OPLINKSETTINGS_COMSPEED_19200:
datarate = RFM22_datarate_32000;
break;
case OPLINKSETTINGS_COMSPEED_38400:
datarate = RFM22_datarate_64000;
break;
case OPLINKSETTINGS_COMSPEED_57600:
datarate = RFM22_datarate_100000;
break;
case OPLINKSETTINGS_COMSPEED_115200:
datarate = RFM22_datarate_192000;
break;
}
/* Set the radio configuration parameters. */
PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, datarate, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, oplinkSettings.ChannelSet, is_coordinator, is_oneway, ppm_mode, ppm_only);
PIOS_RFM22B_SetCoordinatorID(pios_rfm22b_id, oplinkSettings.CoordID);
/* Set the PPM callback if we should be receiving PPM. */
if (ppm_mode) {
PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback);
}
/* Set the modem Tx poer level */
switch (oplinkSettings.MaxRFPower) {
case OPLINKSETTINGS_MAXRFPOWER_125:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0);
break;
@ -751,32 +822,14 @@ void PIOS_Board_Init(void)
// do nothing
break;
}
PIOS_RFM22B_Reinit(pios_rfm22b_id);
#ifdef PIOS_INCLUDE_RFM22B_COM
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);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN,
tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) {
PIOS_Assert(0);
}
#endif
#ifdef PIOS_INCLUDE_RFM22B_RCVR
if (PIOS_RFM22B_RCVR_Init(pios_rfm22b_id) != 0) {
PIOS_Assert(0);
}
uint32_t pios_rfm22b_rcvr_id;
if (PIOS_RCVR_Init(&pios_rfm22b_rcvr_id, &pios_rfm22b_rcvr_driver, pios_rfm22b_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPLINK] = pios_rfm22b_rcvr_id;
#endif
break;
}
/* Reinitialize the modem. */
PIOS_RFM22B_Reinit(pios_rfm22b_id);
} else {
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
}
OPLinkStatusSet(&oplinkStatus);
#endif /* PIOS_INCLUDE_RFM22B */
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PWM)
@ -835,6 +888,19 @@ void PIOS_Board_Init(void)
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id;
#endif /* PIOS_INCLUDE_GCSRCVR */
#if defined(PIOS_INCLUDE_OPLINKRCVR)
{
OPLinkReceiverInitialize();
uint32_t pios_oplinkrcvr_id;
PIOS_OPLinkRCVR_Init(&pios_oplinkrcvr_id);
uint32_t pios_oplinkrcvr_rcvr_id;
if (PIOS_RCVR_Init(&pios_oplinkrcvr_rcvr_id, &pios_oplinkrcvr_rcvr_driver, pios_oplinkrcvr_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPLINK] = pios_oplinkrcvr_rcvr_id;
}
#endif /* PIOS_INCLUDE_OPLINKRCVR */
#ifndef PIOS_ENABLE_DEBUG_PINS
// pios_servo_cfg points to the correct configuration based on input port settings
PIOS_Servo_Init(pios_servo_cfg);

View File

@ -229,6 +229,7 @@ extern uint32_t pios_packet_handler;
#define PIOS_RCVR_MAX_CHANNELS 12
#define PIOS_GCSRCVR_TIMEOUT_MS 100
#define PIOS_RFM22B_RCVR_TIMEOUT_MS 200
#define PIOS_OPLINK_RCVR_TIMEOUT_MS 100
// -------------------------
// Receiver PPM input

View File

@ -93,6 +93,7 @@
#define PIOS_INCLUDE_DSM
#define PIOS_INCLUDE_SBUS
#define PIOS_INCLUDE_GCSRCVR
/* #define PIOS_INCLUDE_OPLINKRCVR */
/* PIOS abstract receiver interface */
#define PIOS_INCLUDE_RCVR
@ -115,7 +116,6 @@
/* PIOS radio modules */
/* #define PIOS_INCLUDE_RFM22B */
/* #define PIOS_INCLUDE_RFM22B_COM */
/* #define PIOS_INCLUDE_RFM22B_RCVR */
/* #define PIOS_INCLUDE_PPM_OUT */
/* #define PIOS_RFM22B_DEBUG_ON_TELEM */

View File

@ -84,7 +84,8 @@
// #define PIOS_INCLUDE_SBUS
#define PIOS_INCLUDE_PPM
#define PIOS_INCLUDE_PWM
// #define PIOS_INCLUDE_GCSRCVR
/* #define PIOS_INCLUDE_GCSRCVR */
/* #define PIOS_INCLUDE_OPLINKRCVR */
#define PIOS_INCLUDE_IAP
#define PIOS_INCLUDE_BL_HELPER

View File

@ -59,10 +59,13 @@ int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId);
int32_t UAVTalkSendBuf(UAVTalkConnection connectionHandle, uint8_t *buf, uint16_t len);
UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte);
UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connection, uint8_t rxbyte);
UAVTalkRxState UAVTalkRelayInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte);
UAVTalkRxState UAVTalkRelayPacket(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle);
int32_t UAVTalkReceiveObject(UAVTalkConnection connectionHandle);
void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats);
void UAVTalkAddStats(UAVTalkConnection connection, UAVTalkStats *stats);
void UAVTalkResetStats(UAVTalkConnection connection);
void UAVTalkGetLastTimestamp(UAVTalkConnection connection, uint16_t *timestamp);
uint32_t UAVTalkGetPacketObjId(UAVTalkConnection connection);
#endif // UAVTALK_H
/**

View File

@ -136,6 +136,34 @@ void UAVTalkGetStats(UAVTalkConnection connectionHandle, UAVTalkStats *statsOut)
xSemaphoreGiveRecursive(connection->lock);
}
/**
* Get communication statistics counters
* \param[in] connection UAVTalkConnection to be used
* @param[out] statsOut Statistics counters
*/
void UAVTalkAddStats(UAVTalkConnection connectionHandle, UAVTalkStats *statsOut)
{
UAVTalkConnectionData *connection;
CHECKCONHANDLE(connectionHandle, connection, return );
// Lock
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
// Copy stats
statsOut->txBytes += connection->stats.txBytes;
statsOut->rxBytes += connection->stats.rxBytes;
statsOut->txObjectBytes += connection->stats.txObjectBytes;
statsOut->rxObjectBytes += connection->stats.rxObjectBytes;
statsOut->txObjects += connection->stats.txObjects;
statsOut->rxObjects += connection->stats.rxObjects;
statsOut->txErrors += connection->stats.txErrors;
statsOut->txErrors += connection->stats.txErrors;
// Release lock
xSemaphoreGiveRecursive(connection->lock);
}
/**
* Reset the statistics counters.
* \param[in] connection UAVTalkConnection to be used
@ -287,7 +315,7 @@ static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle
/**
* Process an byte from the telemetry stream.
* \param[in] connection UAVTalkConnection to be used
* \param[in] connectionHandle UAVTalkConnection to be used
* \param[in] rxbyte Received byte
* \return UAVTalkRxState
*/
@ -534,83 +562,117 @@ UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uin
UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(connectionHandle, rxbyte);
if (state == UAVTALK_STATE_COMPLETE) {
UAVTalkConnectionData *connection;
CHECKCONHANDLE(connectionHandle, connection, return -1);
UAVTalkInputProcessor *iproc = &connection->iproc;
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
receiveObject(connection, iproc->type, iproc->objId, iproc->instId, connection->rxBuffer, iproc->length);
xSemaphoreGiveRecursive(connection->lock);
UAVTalkReceiveObject(connectionHandle);
}
return state;
}
/**
* Process an byte from the telemetry stream, sending the packet out the output stream when it's complete
* This allows the interlieving of packets on an output UAVTalk stream, and is used by the OPLink device to
* relay packets from an input com port to a different output com port without sending one packet in the middle
* of another packet. Because this uses both the receive buffer and transmit buffer, it should only be used
* for relaying a packet, not for the standard sending and receiving of packets.
* Send a parsed packet received on one connection handle out on a different connection handle.
* The packet must be in a complete state, meaning it is completed parsing.
* The packet is re-assembled from the component parts into a complete message and sent.
* This can be used to relay packets from one UAVTalk connection to another.
* \param[in] connection UAVTalkConnection to be used
* \param[in] rxbyte Received byte
* \return UAVTalkRxState
* \return 0 Success
* \return -1 Failure
*/
UAVTalkRxState UAVTalkRelayInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte)
UAVTalkRxState UAVTalkRelayPacket(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle)
{
UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(connectionHandle, rxbyte);
UAVTalkConnectionData *inConnection;
if (state == UAVTALK_STATE_COMPLETE) {
UAVTalkConnectionData *connection;
CHECKCONHANDLE(connectionHandle, connection, return -1);
UAVTalkInputProcessor *iproc = &connection->iproc;
CHECKCONHANDLE(inConnectionHandle, inConnection, return -1);
UAVTalkInputProcessor *inIproc = &inConnection->iproc;
if (!connection->outStream) {
return -1;
}
// Setup type and object id fields
connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte
connection->txBuffer[1] = iproc->type;
// data length inserted here below
connection->txBuffer[4] = (uint8_t)(iproc->objId & 0xFF);
connection->txBuffer[5] = (uint8_t)((iproc->objId >> 8) & 0xFF);
connection->txBuffer[6] = (uint8_t)((iproc->objId >> 16) & 0xFF);
connection->txBuffer[7] = (uint8_t)((iproc->objId >> 24) & 0xFF);
// Setup instance ID if one is required
int32_t dataOffset = 8;
if (iproc->instanceLength > 0) {
connection->txBuffer[8] = (uint8_t)(iproc->instId & 0xFF);
connection->txBuffer[9] = (uint8_t)((iproc->instId >> 8) & 0xFF);
dataOffset = 10;
}
// Add timestamp when the transaction type is appropriate
if (iproc->type & UAVTALK_TIMESTAMPED) {
portTickType time = xTaskGetTickCount();
connection->txBuffer[dataOffset] = (uint8_t)(time & 0xFF);
connection->txBuffer[dataOffset + 1] = (uint8_t)((time >> 8) & 0xFF);
dataOffset += 2;
}
// Copy data (if any)
memcpy(&connection->txBuffer[dataOffset], connection->rxBuffer, iproc->length);
// Store the packet length
connection->txBuffer[2] = (uint8_t)((dataOffset + iproc->length) & 0xFF);
connection->txBuffer[3] = (uint8_t)(((dataOffset + iproc->length) >> 8) & 0xFF);
// Copy the checksum
connection->txBuffer[dataOffset + iproc->length] = iproc->cs;
// Send the buffer.
if (UAVTalkSendBuf(connectionHandle, connection->txBuffer, iproc->rxPacketLength) < 0) {
return UAVTALK_STATE_ERROR;
}
// The input packet must be completely parsed.
if (inIproc->state != UAVTALK_STATE_COMPLETE) {
return -1;
}
return state;
UAVTalkConnectionData *outConnection;
CHECKCONHANDLE(outConnectionHandle, outConnection, return -1);
if (!outConnection->outStream) {
return -1;
}
// Lock
xSemaphoreTakeRecursive(outConnection->lock, portMAX_DELAY);
// Setup type and object id fields
outConnection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte
outConnection->txBuffer[1] = inIproc->type;
// data length inserted here below
int32_t dataOffset = 8;
if (inIproc->objId != 0) {
outConnection->txBuffer[4] = (uint8_t)(inIproc->objId & 0xFF);
outConnection->txBuffer[5] = (uint8_t)((inIproc->objId >> 8) & 0xFF);
outConnection->txBuffer[6] = (uint8_t)((inIproc->objId >> 16) & 0xFF);
outConnection->txBuffer[7] = (uint8_t)((inIproc->objId >> 24) & 0xFF);
// Setup instance ID if one is required
if (inIproc->instanceLength > 0) {
outConnection->txBuffer[8] = (uint8_t)(inIproc->instId & 0xFF);
outConnection->txBuffer[9] = (uint8_t)((inIproc->instId >> 8) & 0xFF);
dataOffset = 10;
}
} else {
dataOffset = 4;
}
// Add timestamp when the transaction type is appropriate
if (inIproc->type & UAVTALK_TIMESTAMPED) {
portTickType time = xTaskGetTickCount();
outConnection->txBuffer[dataOffset] = (uint8_t)(time & 0xFF);
outConnection->txBuffer[dataOffset + 1] = (uint8_t)((time >> 8) & 0xFF);
dataOffset += 2;
}
// Copy data (if any)
memcpy(&outConnection->txBuffer[dataOffset], inConnection->rxBuffer, inIproc->length);
// Store the packet length
outConnection->txBuffer[2] = (uint8_t)((dataOffset + inIproc->length) & 0xFF);
outConnection->txBuffer[3] = (uint8_t)(((dataOffset + inIproc->length) >> 8) & 0xFF);
// Copy the checksum
outConnection->txBuffer[dataOffset + inIproc->length] = inIproc->cs;
// Send the buffer.
int32_t rc = (*outConnection->outStream)(outConnection->txBuffer, inIproc->rxPacketLength);
// Update stats
outConnection->stats.txBytes += rc;
// Release lock
xSemaphoreGiveRecursive(outConnection->lock);
// Done
if (rc != inIproc->rxPacketLength) {
return -1;
}
return 0;
}
/**
* Complete receiving a UAVTalk packet. This will cause the packet to be unpacked, acked, etc.
* \param[in] connectionHandle UAVTalkConnection to be used
* \return 0 Success
* \return -1 Failure
*/
int32_t UAVTalkReceiveObject(UAVTalkConnection connectionHandle)
{
UAVTalkConnectionData *connection;
CHECKCONHANDLE(connectionHandle, connection, return -1);
UAVTalkInputProcessor *iproc = &connection->iproc;
if (iproc->state != UAVTALK_STATE_COMPLETE) {
return -1;
}
receiveObject(connection, iproc->type, iproc->objId, iproc->instId, connection->rxBuffer, iproc->length);
return 0;
}
/**
@ -662,37 +724,17 @@ int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId)
}
/**
* Send a buffer containing a UAVTalk message through the telemetry link.
* This function locks the connection prior to sending.
* \param[in] connection UAVTalkConnection to be used
* \param[in] buf The data buffer containing the UAVTalk message
* \param[in] len The number of bytes to send from the data buffer
* \return 0 Success
* \return -1 Failure
* Get the object ID of the current packet.
* \param[in] connectionHandle UAVTalkConnection to be used
* \param[in] objId Object ID to send a NACK for
* \return The object ID, or 0 on error.
*/
int32_t UAVTalkSendBuf(UAVTalkConnection connectionHandle, uint8_t *buf, uint16_t len)
uint32_t UAVTalkGetPacketObjId(UAVTalkConnection connectionHandle)
{
UAVTalkConnectionData *connection;
CHECKCONHANDLE(connectionHandle, connection, return -1);
// Lock
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
// Output the buffer
int32_t rc = (*connection->outStream)(buf, len);
// Update stats
connection->stats.txBytes += len;
// Release lock
xSemaphoreGiveRecursive(connection->lock);
// Done
if (rc != len) {
return -1;
}
return 0;
CHECKCONHANDLE(connectionHandle, connection, return 0);
return connection->iproc.objId;
}
/**
@ -716,6 +758,9 @@ static int32_t receiveObject(UAVTalkConnectionData *connection,
UAVObjHandle obj;
int32_t ret = 0;
// Lock
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
// Get the handle to the Object. Will be zero
// if object does not exist.
obj = UAVObjGetByID(objId);
@ -734,6 +779,7 @@ static int32_t receiveObject(UAVTalkConnectionData *connection,
ret = -1;
}
break;
case UAVTALK_TYPE_OBJ_ACK:
case UAVTALK_TYPE_OBJ_ACK_TS:
// All instances, not allowed for OBJ_ACK messages
@ -772,6 +818,10 @@ static int32_t receiveObject(UAVTalkConnectionData *connection,
default:
ret = -1;
}
// Unlock
xSemaphoreGiveRecursive(connection->lock);
// Done
return ret;
}

View File

@ -33,7 +33,7 @@
ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_oplink = new Ui_PipXtremeWidget();
m_oplink = new Ui_OPLinkWidget();
m_oplink->setupUi(this);
// Connect to the OPLinkStatus object updates
@ -63,11 +63,16 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
addUAVObjectToWidgetRelation("OPLinkSettings", "MainPort", m_oplink->MainPort);
addUAVObjectToWidgetRelation("OPLinkSettings", "FlexiPort", m_oplink->FlexiPort);
addUAVObjectToWidgetRelation("OPLinkSettings", "VCPPort", m_oplink->VCPPort);
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
addUAVObjectToWidgetRelation("OPLinkSettings", "MinFrequency", m_oplink->MinimumFrequency);
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxFrequency", m_oplink->MaximumFrequency);
addUAVObjectToWidgetRelation("OPLinkSettings", "InitFrequency", m_oplink->InitFrequency);
addUAVObjectToWidgetRelation("OPLinkSettings", "ChannelSpacing", m_oplink->StepSize);
addUAVObjectToWidgetRelation("OPLinkSettings", "MinChannel", m_oplink->MinimumChannel);
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxChannel", m_oplink->MaximumChannel);
addUAVObjectToWidgetRelation("OPLinkSettings", "ChannelSet", m_oplink->ChannelSet);
addUAVObjectToWidgetRelation("OPLinkSettings", "CoordID", m_oplink->CoordID);
addUAVObjectToWidgetRelation("OPLinkSettings", "Coordinator", m_oplink->Coordinator);
addUAVObjectToWidgetRelation("OPLinkSettings", "OneWay", m_oplink->OneWayLink);
addUAVObjectToWidgetRelation("OPLinkSettings", "PPMOnly", m_oplink->PPMOnly);
addUAVObjectToWidgetRelation("OPLinkSettings", "PPM", m_oplink->PPM);
addUAVObjectToWidgetRelation("OPLinkStatus", "DeviceID", m_oplink->DeviceID);
addUAVObjectToWidgetRelation("OPLinkStatus", "RxGood", m_oplink->Good);
@ -89,82 +94,17 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
addUAVObjectToWidgetRelation("OPLinkStatus", "RXRate", m_oplink->RXRate);
addUAVObjectToWidgetRelation("OPLinkStatus", "TXRate", m_oplink->TXRate);
signalMapperAddBinding = new QSignalMapper(this);
signalMapperRemBinding = new QSignalMapper(this);
connect(m_oplink->BindingAdd_1, SIGNAL(clicked()), signalMapperAddBinding, SLOT(map()));
signalMapperAddBinding->setMapping(m_oplink->BindingAdd_1, (QWidget *)(m_oplink->BindingID_1));
connect(m_oplink->BindingRemove_1, SIGNAL(clicked()), signalMapperRemBinding, SLOT(map()));
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 *)));
// Connect the bind buttons
connect(m_oplink->Bind1, SIGNAL(clicked()), this, SLOT(bind1()));
connect(m_oplink->Bind2, SIGNAL(clicked()), this, SLOT(bind2()));
connect(m_oplink->Bind3, SIGNAL(clicked()), this, SLOT(bind3()));
connect(m_oplink->Bind4, SIGNAL(clicked()), this, SLOT(bind3()));
// Connect the selection changed signals.
connect(m_oplink->PPMOnly, SIGNAL(toggled(bool)), this, SLOT(ppmOnlyToggled(bool)));
connect(m_oplink->ComSpeed, SIGNAL(currentIndexChanged(int)), this, SLOT(comSpeedChanged(int)));
ppmOnlyToggled(m_oplink->PPMOnly->isChecked());
// Add scroll bar when necessary
QScrollArea *scroll = new QScrollArea;
@ -179,10 +119,7 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
}
ConfigPipXtremeWidget::~ConfigPipXtremeWidget()
{
delete signalMapperAddBinding;
delete signalMapperRemBinding;
}
{}
/*!
\brief Called by updates to @OPLinkStatus
@ -200,19 +137,19 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
quint32 pairid1 = pairIdField->getValue(0).toUInt();
m_oplink->PairID1->setText(QString::number(pairid1, 16).toUpper());
m_oplink->PairID1->setEnabled(false);
m_oplink->PairSelect1->setEnabled(pairid1);
m_oplink->Bind1->setEnabled(pairid1);
quint32 pairid2 = pairIdField->getValue(1).toUInt();
m_oplink->PairID2->setText(QString::number(pairIdField->getValue(1).toUInt(), 16).toUpper());
m_oplink->PairID2->setEnabled(false);
m_oplink->PairSelect2->setEnabled(pairid2);
m_oplink->Bind2->setEnabled(pairid2);
quint32 pairid3 = pairIdField->getValue(2).toUInt();
m_oplink->PairID3->setText(QString::number(pairIdField->getValue(2).toUInt(), 16).toUpper());
m_oplink->PairID3->setEnabled(false);
m_oplink->PairSelect3->setEnabled(pairid3);
m_oplink->Bind3->setEnabled(pairid3);
quint32 pairid4 = pairIdField->getValue(3).toUInt();
m_oplink->PairID4->setText(QString::number(pairIdField->getValue(3).toUInt(), 16).toUpper());
m_oplink->PairID4->setEnabled(false);
m_oplink->PairSelect4->setEnabled(pairid4);
m_oplink->Bind4->setEnabled(pairid4);
} else {
qDebug() << "PipXtremeGadgetWidget: Count not read PairID field.";
}
@ -295,6 +232,53 @@ void ConfigPipXtremeWidget::updateSettings(UAVObject *object)
if (!settingsUpdated) {
settingsUpdated = true;
// Enable components based on the board type connected.
UAVObjectField *board_type_field = oplinkStatusObj->getField("BoardType");
if (board_type_field) {
switch (board_type_field->getValue().toInt()) {
case 0x09: // Revolution
m_oplink->MainPort->setVisible(false);
m_oplink->MainPortLabel->setVisible(false);
m_oplink->FlexiPort->setVisible(false);
m_oplink->FlexiPortLabel->setVisible(false);
m_oplink->VCPPort->setVisible(false);
m_oplink->VCPPortLabel->setVisible(false);
m_oplink->FlexiIOPort->setVisible(false);
m_oplink->FlexiIOPortLabel->setVisible(false);
m_oplink->PPM->setVisible(true);
break;
case 0x03: // OPLinkMini
m_oplink->MainPort->setVisible(true);
m_oplink->MainPortLabel->setVisible(true);
m_oplink->FlexiPort->setVisible(true);
m_oplink->FlexiPortLabel->setVisible(true);
m_oplink->VCPPort->setVisible(true);
m_oplink->VCPPortLabel->setVisible(true);
m_oplink->FlexiIOPort->setVisible(false);
m_oplink->FlexiIOPortLabel->setVisible(false);
m_oplink->PPM->setVisible(false);
break;
case 0x0A:
m_oplink->MainPort->setVisible(true);
m_oplink->MainPortLabel->setVisible(true);
m_oplink->FlexiPort->setVisible(true);
m_oplink->FlexiPortLabel->setVisible(true);
m_oplink->VCPPort->setVisible(true);
m_oplink->VCPPortLabel->setVisible(true);
m_oplink->FlexiIOPort->setVisible(true);
m_oplink->FlexiIOPortLabel->setVisible(true);
m_oplink->PPM->setVisible(false);
break;
default:
// This shouldn't happen.
break;
}
} else {
qDebug() << "BoardType not found.";
}
// Enable the push buttons.
enableControls(true);
}
}
@ -303,35 +287,71 @@ void ConfigPipXtremeWidget::disconnected()
{
if (settingsUpdated) {
settingsUpdated = false;
// Enable the push buttons.
enableControls(false);
}
}
void ConfigPipXtremeWidget::addBinding(QWidget *w)
void ConfigPipXtremeWidget::SetPairID(QLineEdit *pairIdWidget)
{
if (QLineEdit * le = qobject_cast<QLineEdit *>(w)) {
// Get the pair ID out of the selection widget
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);
}
// Get the pair ID out of the selection widget
quint32 pairID = 0;
bool okay;
// Store the ID in the first open slot (or the last slot if all are full).
le->setText(QString::number(pairID, 16).toUpper());
pairID = pairIdWidget->text().toUInt(&okay, 16);
// Store the ID in the coord ID field.
m_oplink->CoordID->setText(QString::number(pairID, 16).toUpper());
}
void ConfigPipXtremeWidget::bind1()
{
SetPairID(m_oplink->PairID1);
}
void ConfigPipXtremeWidget::bind2()
{
SetPairID(m_oplink->PairID1);
}
void ConfigPipXtremeWidget::bind3()
{
SetPairID(m_oplink->PairID1);
}
void ConfigPipXtremeWidget::bind4()
{
SetPairID(m_oplink->PairID1);
}
void ConfigPipXtremeWidget::ppmOnlyToggled(bool on)
{
if (on) {
m_oplink->PPM->setEnabled(false);
m_oplink->OneWayLink->setEnabled(false);
m_oplink->ComSpeed->setEnabled(false);
} else {
m_oplink->PPM->setEnabled(true);
m_oplink->OneWayLink->setEnabled(true);
m_oplink->ComSpeed->setEnabled(true);
// Change the comspeed from 4800 of PPM only is turned off.
if (m_oplink->ComSpeed->currentIndex() == OPLinkSettings::COMSPEED_4800) {
m_oplink->ComSpeed->setCurrentIndex(OPLinkSettings::COMSPEED_9600);
}
}
}
void ConfigPipXtremeWidget::removeBinding(QWidget *w)
void ConfigPipXtremeWidget::comSpeedChanged(int index)
{
if (QLineEdit * le = qobject_cast<QLineEdit *>(w)) {
le->setText(QString::number(0, 16).toUpper());
qDebug() << "comSpeedChanged: " << index;
switch (index) {
case OPLinkSettings::COMSPEED_4800:
m_oplink->PPMOnly->setChecked(true);
break;
default:
m_oplink->PPMOnly->setChecked(false);
break;
}
}

View File

@ -44,7 +44,7 @@ public slots:
void updateSettings(UAVObject *object1);
private:
Ui_PipXtremeWidget *m_oplink;
Ui_OPLinkWidget *m_oplink;
// The OPLink status UAVObject
UAVDataObject *oplinkStatusObj;
@ -55,14 +55,16 @@ private:
// Are the settings current?
bool settingsUpdated;
// Signal mappers to add arguments to signals.
QSignalMapper *signalMapperAddBinding;
QSignalMapper *signalMapperRemBinding;
void SetPairID(QLineEdit *pairIdWidget);
private slots:
void disconnected();
void addBinding(QWidget *w);
void removeBinding(QWidget *w);
void bind1();
void bind2();
void bind3();
void bind4();
void ppmOnlyToggled(bool toggled);
void comSpeedChanged(int index);
};
#endif // CONFIGTXPIDWIDGET_H

View File

@ -65,10 +65,6 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
addUAVObjectToWidgetRelation("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
addUAVObjectToWidgetRelation("HwSettings", "RadioPort", m_ui->cbModem);
addUAVObjectToWidgetRelation("HwSettings", "MaxRFPower", m_ui->cbTxPower);
addUAVObjectToWidgetRelation("HwSettings", "DefaultFrequency", m_ui->leInitFreq);
connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
setupCustomCombos();
@ -95,7 +91,6 @@ void ConfigRevoHWWidget::setupCustomCombos()
connect(m_ui->cbFlexi, SIGNAL(currentIndexChanged(int)), this, SLOT(flexiPortChanged(int)));
connect(m_ui->cbMain, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged(int)));
connect(m_ui->cbModem, SIGNAL(currentIndexChanged(int)), this, SLOT(modemPortChanged(int)));
}
void ConfigRevoHWWidget::refreshWidgetsValues(UAVObject *obj)
@ -106,7 +101,6 @@ void ConfigRevoHWWidget::refreshWidgetsValues(UAVObject *obj)
usbVCPPortChanged(0);
mainPortChanged(0);
flexiPortChanged(0);
modemPortChanged(0);
m_refreshing = false;
}
@ -203,9 +197,6 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_TELEMETRY) {
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
}
if (m_ui->cbModem->currentIndex() == HwSettings::RADIOPORT_TELEMETRY) {
m_ui->cbModem->setCurrentIndex(HwSettings::RADIOPORT_DISABLED);
}
break;
case HwSettings::RM_FLEXIPORT_GPS:
m_ui->cbFlexiGPSSpeed->setVisible(true);
@ -249,9 +240,6 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
}
if (m_ui->cbModem->currentIndex() == HwSettings::RADIOPORT_TELEMETRY) {
m_ui->cbModem->setCurrentIndex(HwSettings::RADIOPORT_DISABLED);
}
break;
case HwSettings::RM_MAINPORT_GPS:
m_ui->cbMainGPSSpeed->setVisible(true);
@ -280,32 +268,6 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
}
}
void ConfigRevoHWWidget::modemPortChanged(int index)
{
Q_UNUSED(index);
if (m_ui->cbModem->currentIndex() == HwSettings::RADIOPORT_TELEMETRY) {
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_TELEMETRY) {
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
}
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
}
m_ui->lblTxPower->setVisible(true);
m_ui->cbTxPower->setVisible(true);
m_ui->lblInitFreq->setVisible(true);
m_ui->leInitFreq->setVisible(true);
if (!m_refreshing) {
QMessageBox::warning(this, tr("Warning"), tr("Activating the Radio requires an antenna be attached or modem damage will occur."));
}
} else {
m_ui->lblTxPower->setVisible(false);
m_ui->cbTxPower->setVisible(false);
m_ui->lblInitFreq->setVisible(false);
m_ui->leInitFreq->setVisible(false);
}
}
void ConfigRevoHWWidget::openHelp()
{
QDesktopServices::openUrl(QUrl("http://wiki.openpilot.org/x/GgDBAQ", QUrl::StrictMode));

View File

@ -57,7 +57,6 @@ private slots:
void usbHIDPortChanged(int index);
void flexiPortChanged(int index);
void mainPortChanged(int index);
void modemPortChanged(int index);
void openHelp();
};

View File

@ -113,8 +113,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>810</width>
<height>665</height>
<width>818</width>
<height>673</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout_3">
@ -122,59 +122,7 @@
<number>12</number>
</property>
<item row="2" column="2">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
<item row="7" column="0">
<widget class="QLabel" name="label_8">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>USB VCP Function</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="14" column="3">
<widget class="QLabel" name="lblMainSpeed">
<property name="text">
<string>Speed</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="6" column="5">
<widget class="QComboBox" name="cbSonar">
<property name="enabled">
<bool>false</bool>
</property>
</widget>
</item>
<item row="9" column="0">
<widget class="QLabel" name="lblUSBVCPSpeed">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Speed</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QComboBox" name="cbRcvr"/>
</item>
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
<item row="5" column="0">
<widget class="QLabel" name="label_4">
<property name="sizePolicy">
@ -191,26 +139,6 @@
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QComboBox" name="cbUSBHIDFunction"/>
</item>
<item row="10" column="0">
<widget class="QComboBox" name="cbUSBVCPSpeed">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
<item row="12" column="3">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Main Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="12" column="4">
<spacer name="horizontalSpacer_2">
<property name="orientation">
@ -227,8 +155,28 @@
</property>
</spacer>
</item>
<item row="12" column="5">
<spacer name="horizontalSpacer_6">
<item row="15" column="1">
<layout class="QVBoxLayout" name="verticalLayout_5">
<property name="spacing">
<number>0</number>
</property>
<item alignment="Qt::AlignTop">
<widget class="QComboBox" name="cbFlexiTelemSpeed">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
<item alignment="Qt::AlignTop">
<widget class="QComboBox" name="cbFlexiGPSSpeed"/>
</item>
<item alignment="Qt::AlignTop">
<widget class="QComboBox" name="cbFlexiComSpeed"/>
</item>
</layout>
</item>
<item row="16" column="1">
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
@ -243,6 +191,16 @@
</property>
</spacer>
</item>
<item row="14" column="3">
<widget class="QLabel" name="lblMainSpeed">
<property name="text">
<string>Speed</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="1" column="1" rowspan="11" colspan="4" alignment="Qt::AlignHCenter|Qt::AlignVCenter">
<widget class="QLabel" name="label_2">
<property name="sizePolicy">
@ -274,9 +232,116 @@
</property>
</widget>
</item>
<item row="13" column="1">
<widget class="QComboBox" name="cbFlexi"/>
</item>
<item row="16" column="4">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>70</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="12" column="1">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Flexi Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="6" column="5">
<widget class="QComboBox" name="cbSonar">
<property name="enabled">
<bool>false</bool>
</property>
</widget>
</item>
<item row="13" column="3">
<widget class="QComboBox" name="cbMain"/>
</item>
<item row="10" column="5">
<spacer name="verticalSpacer_6">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="12" column="3">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Main Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QComboBox" name="cbUSBVCPSpeed">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
<item row="12" column="5">
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>120</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="8" column="0">
<widget class="QComboBox" name="cbUSBVCPFunction"/>
</item>
<item row="6" column="0">
<widget class="QComboBox" name="cbUSBHIDFunction"/>
</item>
<item row="9" column="0">
<widget class="QLabel" name="lblUSBVCPSpeed">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Speed</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="5" column="5">
<widget class="QLabel" name="label_9">
<property name="sizePolicy">
@ -293,147 +358,6 @@
</property>
</widget>
</item>
<item row="13" column="3">
<widget class="QComboBox" name="cbMain"/>
</item>
<item row="15" column="1">
<layout class="QVBoxLayout" name="verticalLayout_5">
<property name="spacing">
<number>0</number>
</property>
<item alignment="Qt::AlignTop">
<widget class="QComboBox" name="cbFlexiTelemSpeed">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
<item alignment="Qt::AlignTop">
<widget class="QComboBox" name="cbFlexiGPSSpeed"/>
</item>
<item alignment="Qt::AlignTop">
<widget class="QComboBox" name="cbFlexiComSpeed"/>
</item>
</layout>
</item>
<item row="12" column="0">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>120</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="12" column="1">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Flexi Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="15" column="3">
<layout class="QVBoxLayout" name="verticalLayout_6">
<property name="spacing">
<number>0</number>
</property>
<item>
<widget class="QComboBox" name="cbMainTelemSpeed">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="cbMainGPSSpeed"/>
</item>
<item>
<widget class="QComboBox" name="cbMainComSpeed"/>
</item>
</layout>
</item>
<item row="13" column="1">
<widget class="QComboBox" name="cbFlexi"/>
</item>
<item row="12" column="2">
<widget class="QLabel" name="label">
<property name="text">
<string>Radio</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="13" column="2">
<widget class="QComboBox" name="cbModem"/>
</item>
<item row="14" column="2">
<widget class="QLabel" name="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">
<widget class="QLabel" name="lblFlexiSpeed">
<property name="text">
<string>Speed</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="16" column="1">
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>120</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_7">
<property name="sizePolicy">
@ -466,6 +390,38 @@
</property>
</spacer>
</item>
<item row="12" column="0">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>120</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="7" column="0">
<widget class="QLabel" name="label_8">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>USB VCP Function</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<spacer name="verticalSpacer_4">
<property name="orientation">
@ -482,21 +438,38 @@
</property>
</spacer>
</item>
<item row="16" column="2">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
<item row="14" column="1">
<widget class="QLabel" name="lblFlexiSpeed">
<property name="text">
<string>Speed</string>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>120</width>
<height>10</height>
</size>
</widget>
</item>
<item row="15" column="3">
<layout class="QVBoxLayout" name="verticalLayout_6">
<property name="spacing">
<number>0</number>
</property>
</spacer>
<item>
<widget class="QComboBox" name="cbMainTelemSpeed">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="cbMainGPSSpeed"/>
</item>
<item>
<widget class="QComboBox" name="cbMainComSpeed"/>
</item>
</layout>
</item>
<item row="3" column="0">
<widget class="QComboBox" name="cbRcvr"/>
</item>
<item row="16" column="3">
<spacer name="horizontalSpacer_9">
@ -562,22 +535,6 @@
</property>
</spacer>
</item>
<item row="10" column="5">
<spacer name="verticalSpacer_6">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="11" column="5">
<spacer name="verticalSpacer_9">
<property name="orientation">
@ -594,6 +551,19 @@
</property>
</spacer>
</item>
<item row="16" column="2">
<spacer name="horizontalSpacer_10">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>80</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item row="0" column="2">

View File

@ -1,7 +1,7 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>PipXtremeWidget</class>
<widget class="QWidget" name="PipXtremeWidget">
<class>OPLinkWidget</class>
<widget class="QWidget" name="OPLinkWidget">
<property name="geometry">
<rect>
<x>0</x>
@ -23,10 +23,7 @@
<enum>QFrame::Raised</enum>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="4" column="0" colspan="2">
<layout class="QHBoxLayout" name="horizontalLayout_12"/>
</item>
<item row="5" column="0" colspan="2">
<item row="6" column="0" colspan="2">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="message">
@ -113,7 +110,24 @@
</item>
</layout>
</item>
<item row="2" column="0" colspan="2">
<item row="5" column="0" colspan="2">
<layout class="QHBoxLayout" name="horizontalLayout_12">
<item>
<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>
</item>
<item row="3" column="0" colspan="2">
<widget class="QFrame" name="frame_4">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
@ -136,132 +150,16 @@
<bold>true</bold>
</font>
</property>
<property name="layoutDirection">
<enum>Qt::LeftToRight</enum>
</property>
<property name="title">
<string>Status</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<layout class="QGridLayout" name="gridLayout_4">
<item row="0" column="0">
<widget class="QLabel" name="label_9">
<property name="text">
<string>Firmware Ver.</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="1" colspan="3">
<widget class="QLineEdit" name="FirmwareVersion">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</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="1" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Serial Number</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="1" colspan="3">
<widget class="QLineEdit" name="SerialNumber">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="acceptDrops">
<bool>false</bool>
</property>
<property name="toolTip">
<string>The modems serial number</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="frame">
<bool>true</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="DeviceIDLabel">
<property name="text">
<string>Device ID</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="5">
<widget class="QLineEdit" name="DeviceID">
<property name="minimumSize">
@ -366,6 +264,163 @@
</property>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="label_9">
<property name="text">
<string>Firmware Ver.</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="1" colspan="3">
<widget class="QLineEdit" name="FirmwareVersion">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</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="1" column="7">
<widget class="QLineEdit" name="RSSI">
<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="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Serial Number</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="1" colspan="3">
<widget class="QLineEdit" name="SerialNumber">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="acceptDrops">
<bool>false</bool>
</property>
<property name="toolTip">
<string>The modems serial number</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="frame">
<bool>true</bool>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="DeviceIDLabel">
<property name="text">
<string>Device ID</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="LinkQualityLabel">
<property name="text">
@ -418,13 +473,13 @@
</property>
</widget>
</item>
<item row="1" column="7">
<widget class="QLineEdit" name="RSSI">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
<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>
@ -438,6 +493,9 @@
<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;
@ -448,6 +506,9 @@
/* 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>
@ -922,47 +983,6 @@
</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">
@ -1254,21 +1274,14 @@
<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">
<item row="5" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel4">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="3" column="2">
<item row="5" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar4">
<property name="minimum">
<number>-127</number>
@ -1287,14 +1300,14 @@
</property>
</widget>
</item>
<item row="1" column="3">
<item row="3" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel2">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="1" column="1">
<item row="3" column="1">
<widget class="QLineEdit" name="PairID2">
<property name="maximumSize">
<size>
@ -1304,7 +1317,7 @@
</property>
</widget>
</item>
<item row="1" column="2">
<item row="3" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar2">
<property name="minimum">
<number>-127</number>
@ -1323,14 +1336,17 @@
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel1">
<property name="text">
<string>-100dB</string>
<item row="5" column="1">
<widget class="QLineEdit" name="PairID4">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item row="0" column="2">
<item row="2" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar1">
<property name="minimum">
<number>-127</number>
@ -1349,44 +1365,14 @@
</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">
<widget class="QLabel" name="PairSignalStrengthLabel1">
<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">
<item row="4" column="2">
<widget class="QProgressBar" name="PairSignalStrengthBar3">
<property name="minimum">
<number>-127</number>
@ -1405,14 +1391,14 @@
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QRadioButton" name="PairSelect2">
<item row="4" column="3">
<widget class="QLabel" name="PairSignalStrengthLabel3">
<property name="text">
<string/>
<string>-100dB</string>
</property>
</widget>
</item>
<item row="2" column="1">
<item row="4" column="1">
<widget class="QLineEdit" name="PairID3">
<property name="maximumSize">
<size>
@ -1422,10 +1408,80 @@
</property>
</widget>
</item>
<item row="2" 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="3" column="0">
<widget class="QRadioButton" name="PairSelect4">
<widget class="QPushButton" name="Bind2">
<property name="text">
<string/>
<string>Bind</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QPushButton" name="Bind1">
<property name="text">
<string>Bind</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QPushButton" name="Bind4">
<property name="text">
<string>Bind</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QPushButton" name="Bind3">
<property name="text">
<string>Bind</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="CoordIDLabel">
<property name="layoutDirection">
<enum>Qt::LeftToRight</enum>
</property>
<property name="text">
<string>Coord ID</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QLineEdit" name="CoordID">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="maxLength">
<number>8</number>
</property>
</widget>
</item>
<item row="6" column="2">
<widget class="QCheckBox" name="Coordinator">
<property name="statusTip">
<string>This modem will be a coordinator and other modems will bind to it.</string>
</property>
<property name="text">
<string>Coordinator</string>
</property>
</widget>
</item>
@ -1435,990 +1491,6 @@
</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">
<widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
@ -2437,57 +1509,34 @@
<string>Configuration</string>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<widget class="QLabel" name="MainPortLabel">
<item row="4" column="3">
<widget class="QComboBox" name="ComSpeed">
<property name="statusTip">
<string>Com speed in bps.</string>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QLabel" name="ComSpeedLabel">
<property name="text">
<string>Main Port</string>
<string>Com Speed</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">
<item row="9" column="2">
<widget class="QLabel" name="VCPPortLabel">
<property name="text">
<string>Min Freq</string>
<string>VCP Port</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">
<item row="7" column="3">
<widget class="QComboBox" name="FlexiPort">
<property name="maximumSize">
<size>
@ -2500,35 +1549,18 @@
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="MaximumFrequencyLabel">
<item row="6" column="2">
<widget class="QLabel" name="MainPortLabel">
<property name="text">
<string>Max Freq</string>
<string>Main Port</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 name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="VCPPort">
<item row="6" column="3">
<widget class="QComboBox" name="MainPort">
<property name="maximumSize">
<size>
<width>16777215</width>
@ -2536,38 +1568,11 @@
</size>
</property>
<property name="toolTip">
<string>Choose the function for the USB virtual com port</string>
<string>Choose the function for the main 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>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="MaxRFTxPowerLabel">
<property name="text">
<string>Max Power</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="3" column="1">
<item row="0" column="3">
<widget class="QComboBox" name="MaxRFTxPower">
<property name="maximumSize">
<size>
@ -2586,56 +1591,157 @@
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QLabel" name="StepSizeLabel">
<item row="0" column="2">
<widget class="QLabel" name="MaxRFTxPowerLabel">
<property name="text">
<string>Step Size</string>
<string>Max Power</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="StepSize">
<item row="9" column="3">
<widget class="QComboBox" name="VCPPort">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string extracomment="The channel spacing (Hz)"/>
<string>Choose the function for the USB virtual com port</string>
</property>
</widget>
</item>
<item row="10" column="2">
<widget class="QLabel" name="FlexiIOPortLabel">
<property name="text">
<string>FlexiIO Port</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="10" column="3">
<widget class="QComboBox" name="FlexiIOPort"/>
</item>
<item row="7" column="2">
<widget class="QLabel" name="FlexiPortLabel">
<property name="text">
<string>Flexi Port</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="0">
<widget class="QCheckBox" name="OneWayLink">
<property name="statusTip">
<string>If selected, data will only be transmitted from the coordinator to the Rx modem.</string>
</property>
<property name="text">
<string>One-Way Link</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QCheckBox" name="PPMOnly">
<property name="statusTip">
<string>Only PPM packets will be transmitted.</string>
</property>
<property name="text">
<string>PPM Only</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="MaximumChannelLabel">
<property name="text">
<string>Max Chan</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QSpinBox" name="MaximumChannel">
<property name="toolTip">
<string>Channel 0 is 430 MHz, channel 249 is 440 MHz, and the channel spacing is 40 KHz.</string>
</property>
<property name="maximum">
<number>249</number>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="MinimumChannelLabel">
<property name="text">
<string>Min Chan</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QSpinBox" name="MinimumChannel">
<property name="toolTip">
<string>Channel 0 is 430 MHz, channel 249 is 440 MHz, and the channel spacing is 40 KHz.</string>
</property>
<property name="maximum">
<number>249</number>
</property>
</widget>
</item>
<item row="9" column="0">
<widget class="QLabel" name="ChannelSetLabel">
<property name="text">
<string>Channel Set</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="9" column="1">
<widget class="QSpinBox" name="ChannelSet">
<property name="toolTip">
<string>Sets the random sequence of channels to use for frequency hopping.</string>
</property>
<property name="maximum">
<number>249</number>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QCheckBox" name="PPM">
<property name="statusTip">
<string>PPM packets will be received by this modem. Must be selected if Coordinator modem is configured for PPM.</string>
</property>
<property name="text">
<string>PPM</string>
</property>
</widget>
</item>
</layout>
</widget>
</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>
</widget>
</item>
</layout>
</widget>
<tabstops>
<tabstop>PairSelect1</tabstop>
<tabstop>PairID1</tabstop>
<tabstop>PairSelect2</tabstop>
<tabstop>PairID2</tabstop>
<tabstop>PairSelect3</tabstop>
<tabstop>PairID3</tabstop>
<tabstop>PairSelect4</tabstop>
<tabstop>PairID4</tabstop>
<tabstop>FirmwareVersion</tabstop>
<tabstop>SerialNumber</tabstop>
<tabstop>MaxRFTxPower</tabstop>
<tabstop>Apply</tabstop>
<tabstop>Save</tabstop>
</tabstops>

View File

@ -101,6 +101,7 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \
$$UAVOBJECT_SYNTHETICS/poilocation.h \
$$UAVOBJECT_SYNTHETICS/oplinksettings.h \
$$UAVOBJECT_SYNTHETICS/oplinkstatus.h \
$$UAVOBJECT_SYNTHETICS/oplinkreceiver.h \
$$UAVOBJECT_SYNTHETICS/osdsettings.h \
$$UAVOBJECT_SYNTHETICS/waypoint.h \
$$UAVOBJECT_SYNTHETICS/waypointactive.h \
@ -185,6 +186,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
$$UAVOBJECT_SYNTHETICS/poilocation.cpp \
$$UAVOBJECT_SYNTHETICS/oplinksettings.cpp \
$$UAVOBJECT_SYNTHETICS/oplinkstatus.cpp \
$$UAVOBJECT_SYNTHETICS/oplinkreceiver.cpp \
$$UAVOBJECT_SYNTHETICS/osdsettings.cpp \
$$UAVOBJECT_SYNTHETICS/waypoint.cpp \
$$UAVOBJECT_SYNTHETICS/waypointactive.cpp \

View File

@ -70,6 +70,7 @@ SRC += $(PIOSCOMMON)/pios_l3gd20.c
SRC += $(PIOSCOMMON)/pios_mpu6000.c
SRC += $(PIOSCOMMON)/pios_mpxv.c
SRC += $(PIOSCOMMON)/pios_ms5611.c
SRC += $(PIOSCOMMON)/pios_oplinkrcvr.c
SRC += $(PIOSCOMMON)/pios_video.c
SRC += $(PIOSCOMMON)/pios_wavplay.c
@ -83,7 +84,6 @@ SRC += $(PIOSCOMMON)/pios_flash_jedec.c
SRC += $(PIOSCOMMON)/pios_rcvr.c
SRC += $(PIOSCOMMON)/pios_rfm22b.c
SRC += $(PIOSCOMMON)/pios_rfm22b_com.c
SRC += $(PIOSCOMMON)/pios_rfm22b_rcvr.c
SRC += $(PIOSCOMMON)/pios_sbus.c
SRC += $(PIOSCOMMON)/pios_sdcard.c

View File

@ -15,10 +15,6 @@
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Outputs,Outputs" defaultvalue="PWM"/>
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM2,DSMX (10bit),DSMX (11bit),DebugConsole,ComBridge,OsdHk" defaultvalue="Telemetry"/>
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM2,DSMX (10bit),DSMX (11bit),DebugConsole,ComBridge,OsdHk" defaultvalue="Disabled"/>
<field name="RadioPort" units="function" type="enum" elements="1" options="Disabled,Telemetry" defaultvalue="Disabled"/>
<field name="MaxRFPower" units="mW" type="enum" elements="1" options="1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="1.25"/>
<field name="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="GPSSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>

View File

@ -0,0 +1,10 @@
<xml>
<object name="OPLinkReceiver" singleinstance="true" settings="false">
<description>A receiver channel group carried over the OPLink radio.</description>
<field name="Channel" units="us" type="int16" elements="8"/>
<access gcs="readonly" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="onchange" period="0"/>
<telemetryflight acked="false" updatemode="onchange" period="0"/>
<logging updatemode="manual" period="0"/>
</object>
</xml>

View File

@ -1,19 +1,19 @@
<xml>
<object name="OPLinkSettings" singleinstance="true" settings="true">
<description>OPLink configurations options.</description>
<field name="Bindings" units="hex" type="uint32" elements="8" defaultvalue="0"/>
<field name="RemoteMainPort" units="" type="enum" elements="8" options="Disabled,Serial,PPM" defaultvalue="Disabled"/>
<field name="RemoteFlexiPort" units="" type="enum" elements="8" options="Disabled,Serial,PPM" defaultvalue="Disabled"/>
<field name="RemoteVCPPort" units="" type="enum" elements="8" options="Disabled,Serial" defaultvalue="Disabled"/>
<field name="ComSpeed" units="bps" type="enum" elements="8" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="38400"/>
<field name="MainPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM" defaultvalue="Telemetry"/>
<field name="FlexiPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM" defaultvalue="Disabled"/>
<field name="Coordinator" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="OneWay" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="PPM" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="PPMOnly" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="CoordID" units="hex" type="uint32" elements="1" defaultvalue="0"/>
<field name="MainPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM,PWM" defaultvalue="Disabled"/>
<field name="FlexiPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM,PWM" 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="1.25"/>
<field name="MinFrequency" units="Hz" type="uint32" elements="1" defaultvalue="430000000"/>
<field name="MaxFrequency" units="Hz" type="uint32" elements="1" defaultvalue="440000000"/>
<field name="InitFrequency" units="Hz" type="uint32" elements="1" defaultvalue="433000000"/>
<field name="ChannelSpacing" units="Hz" type="uint32" elements="1" defaultvalue="75000"/>
<field name="ComSpeed" units="bps" type="enum" elements="1" options="4800,9600,19200,38400,57600,115200" defaultvalue="38400"/>
<field name="MaxRFPower" units="mW" type="enum" elements="1" options="0,1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="0"/>
<field name="MinChannel" units="" type="uint8" elements="1" defaultvalue="0"/>
<field name="MaxChannel" units="" type="uint8" elements="1" defaultvalue="250"/>
<field name="ChannelSet" units="" type="uint8" elements="1" defaultvalue="39"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>

View File

@ -24,13 +24,13 @@
<field name="RXRate" units="Bps" type="uint16" elements="1" defaultvalue="0"/>
<field name="TXSeq" units="" type="uint16" elements="1" defaultvalue="0"/>
<field name="RXSeq" units="" type="uint16" elements="1" defaultvalue="0"/>
<field name="LinkState" units="function" type="enum" elements="1" options="Disconnected,Connecting,Connected" defaultvalue="Disconnected"/>
<field name="LinkState" units="function" type="enum" elements="1" options="Disabled,Enabled,Disconnected,Connecting,Connected" defaultvalue="Disabled"/>
<field name="PairIDs" units="hex" type="uint32" elements="4" defaultvalue="0"/>
<field name="PairSignalStrengths" units="dBm" type="int8" elements="4" defaultvalue="-127"/>
<access gcs="readonly" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="1000"/>
<telemetryflight acked="false" updatemode="throttled" period="500"/>
<logging updatemode="periodic" period="1000"/>
</object>
</xml>

View File

@ -10,6 +10,7 @@
<elementname>TelemetryTx</elementname>
<elementname>TelemetryTxPri</elementname>
<elementname>TelemetryRx</elementname>
<elementname>RadioRx</elementname>
<elementname>GPS</elementname>
<elementname>ManualControl</elementname>
<elementname>Altitude</elementname>
@ -44,6 +45,7 @@
<elementname>TelemetryTx</elementname>
<elementname>TelemetryTxPri</elementname>
<elementname>TelemetryRx</elementname>
<elementname>RadioRx</elementname>
<elementname>GPS</elementname>
<elementname>ManualControl</elementname>
<elementname>Altitude</elementname>
@ -82,6 +84,7 @@
<elementname>TelemetryTx</elementname>
<elementname>TelemetryTxPri</elementname>
<elementname>TelemetryRx</elementname>
<elementname>RadioRx</elementname>
<elementname>GPS</elementname>
<elementname>ManualControl</elementname>
<elementname>Altitude</elementname>